Compare commits

...

35 Commits

Author SHA1 Message Date
Pedro Roque 8a700471b4 Merge branch 'main' into dev-boat 2026-01-14 11:53:54 -08:00
Pedro-Roque 076e07444d feat: update gz commit 2026-01-14 11:52:02 -08:00
Pedro-Roque afdac4bd4c feat: reverted changes to old boat on ROMFS 2026-01-14 11:50:08 -08:00
Pedro-Roque 39965d3ef1 feat: add romfs for boat 2026-01-14 11:45:39 -08:00
Pedro-Roque 348b8f7f56 feat: add basic boat 2026-01-14 11:45:20 -08:00
Farhang 8e658a6e2d github: simplify bug report issue template (#26191)
* Simplify bug report issue template to reduce clutter

- Reduced from 11 fields to 2 consolidated fields
- Enabled blank issues for flexibility
- Combined optional fields into single "Flight Log / Additional Information" section
- Added helpful tips at top instead of separate required fields
- Eliminates empty field clutter in submitted issues while maintaining guidance

* Fix inconsistent YAML indentation in bug report template
2026-01-14 09:59:52 -08:00
Jonas Eschmann db2c6b2abe feature: Integrating the RAPTOR foundation policy (#26082)
* moving raptor

bump

compiles and raptor mode appears

hovering with RAPTOR seems to work

Using Raptor to execute offboard commands works (using multirobot f03825a5795a77c5a095f799eeb8e0b646fe7176 to feed the trajectory_setpoint). Requires more testing

simplified rotmat

runtime inference frequency multiple

arming request response reflects actual readiness

adjusting to fit IMU gyro ratemax

relaxing control timing warning thresholds for SITL

Using mode registration to signal if offboard commands should be forwarded to trajectory_setpoint instead of just hardcoding vehicle_status.nav_state == vehicle_status_s::NAVIGATION_STATE_OFFBOARD

adopting new "request_offboard_setpoint" in raptor module

replace offboard seems good

mc_raptor: overwrite offboard parameter

separate raptor config

addendum

Raptor off by default

RAPTOR readme

Loading raptor checkpoint from tar works.

check if load was successful

refactoring: cutting out the pure C interface to allow direct testing of the policy input/output behavior from the file, without fully loading it into memory first

adapter not needed anymore

ripping out test observation mode (not used in a long time)

fixing warnings

bump RLtools to fix the remaining warnings

Loading RAPTOR checkpoint from sdcard seems to work on FMU-6C

embedding Raptor policy into flash works again

also printing checkpoint name when using the embedded policy

cleaner handling of the checkpoint name

back to reading from file

ripping out visual odometry checks

cleaner

more debug but no success

bump rlt

bump

pre next rebase

we can publish the no angvel update because we latch onto it with the scheduled work item anyways

this kind of runs on the 6c

still bad

SIH almost flying

saving stale traj setpoint yaw

new error. timestamp not the problem anymore

bump rlt; SIH works with executor

shaping up

bumping blob (include tar checkpoint)

cleaning up

fixing formatting

update readme

* moving raptor

bump

compiles and raptor mode appears

hovering with RAPTOR seems to work

Using Raptor to execute offboard commands works (using multirobot f03825a5795a77c5a095f799eeb8e0b646fe7176 to feed the trajectory_setpoint). Requires more testing

simplified rotmat

runtime inference frequency multiple

arming request response reflects actual readiness

adjusting to fit IMU gyro ratemax

relaxing control timing warning thresholds for SITL

Using mode registration to signal if offboard commands should be forwarded to trajectory_setpoint instead of just hardcoding vehicle_status.nav_state == vehicle_status_s::NAVIGATION_STATE_OFFBOARD

adopting new "request_offboard_setpoint" in raptor module

replace offboard seems good

mc_raptor: overwrite offboard parameter

separate raptor config

addendum

Raptor off by default

RAPTOR readme

Loading raptor checkpoint from tar works.

check if load was successful

refactoring: cutting out the pure C interface to allow direct testing of the policy input/output behavior from the file, without fully loading it into memory first

adapter not needed anymore

ripping out test observation mode (not used in a long time)

fixing warnings

bump RLtools to fix the remaining warnings

Loading RAPTOR checkpoint from sdcard seems to work on FMU-6C

embedding Raptor policy into flash works again

also printing checkpoint name when using the embedded policy

cleaner handling of the checkpoint name

back to reading from file

ripping out visual odometry checks

cleaner

more debug but no success

bump rlt

bump

pre next rebase

we can publish the no angvel update because we latch onto it with the scheduled work item anyways

this kind of runs on the 6c

still bad

SIH almost flying

saving stale traj setpoint yaw

new error. timestamp not the problem anymore

bump rlt; SIH works with executor

shaping up

bumping blob (include tar checkpoint)

cleaning up

fixing formatting

update readme

updating gitignore

* fixing format and declaring submodules as cmake dependencies

* adding uORB message documentation

* fixing comment alignment

* Adding option to restrict mc_raptor to not listen to the trajectory_setpoint (use the position and yaw at activation time as reference instead)

* bump RLtools; relax timing thresholds and adding real world readme

* smooth traj tracking performance

* Measuring trajectory_setpoint timing (providing stats in raptor_status); reverting accidental .gitignore modification

* More ideomatic way of setting the path to the policy checkpoint

* Reset trajectory_setpoint on raptor mode activation

* Adding internal trajectory generation (feeding trajectory_setpoint over Mavlink is too noisy). Quite agile trajectory tracking, good performance

* stable flight

* Update msg/versioned/RaptorInput.msg

Co-authored-by: Hamish Willee <hamishwillee@gmail.com>

* adopting message formatting conventions

* sort raptor.px4board

* Archiving RegisterExtComponentRequestV1.msg

* Add message versioning for VehicleStatus v2 and RegisterExtComponentRequest v2

* fixing formatting

* making internal reference configurable via command

* RAPTOR docs wip

* raptor internal reference documentation

* Finishing RAPTOR docs first draft

* adding logging instructions

* Fixing missing command documentation test error

* fixing format

* adding motor layout warning

* raptor minimal subedit - prettier, images etc

* Improve intro

* Fix up Neural_Networks version

* Mentioning "Adaptive" in the RAPTOR documentation's title

* Adding clarifications about the internal reference trajectory generator

* Removing "foundation policy" wording

* Fixing new-line check

* Removing redundant (evident through directory hierarchy) raptor_ from filenames

* Unifying Neural Network docs (mc_nn_control and mc_raptor) under the "Neural Network" topic

* Fix to standard structure

* Making the distinction between mc_nn_control and mc_raptor more clear and fixing the comparison table

* Removing trajectory_setpoint forwarding flag from external mode registration request and from the vehicle status

* Trivial layout and wording fixes

* fixing docs error

---------

Co-authored-by: Hamish Willee <hamishwillee@gmail.com>
2026-01-14 09:47:47 -08:00
mahima-yoga 95b8328162 FixedWingLandDetector: force to landed during runway takeoff 2026-01-14 17:01:11 +01:00
mahima-yoga 6de6abfb64 RunwayTakeoff: add the RunwayTakeoffState to the FixedWingRunwayControl.msg 2026-01-14 17:01:11 +01:00
jmackay2 e371c4edd9 Fix the test data matrix script (#24745)
Co-authored-by: jmackay2 <jmackay2@gmail.com>
2026-01-13 13:47:24 -09:00
Matthias Grob 473ef5fd06 uavcan: esc: fix actuator test on uavcan ESCs that consume ArmingStatus (#26255)
* uavcan esc: remove unused includes

* uavcan arming_status: disarm when terminated

To stay consistent with kill.

* uavcan: publish armed during actuator tests to make it possible spinning motors
2026-01-13 10:57:54 -09:00
Phil-Engljaehringer 46d9b14ba0 Feat: Add driver for TMP102 temperature sensor for Skynode-N (#26241)
* feat: added driver for tmp102 temperature sensor

* style: removed new line

* style: adjusted date in header

* style: removed duplicated logging

* fix: moved start-up command from rc.board_sensors to rc.sensors

* style: used consexpr for expected config reg value

* feat: added retry logic to probe function

* style: added _ as prefix to global variable

* style: used make format

* fix: corrected temperature calculation

* fix: mask AL-bit in probe function

* style: removed header files from CMakeLists

* style: used correct english in comments

* refactor: return error right after failure

* style: moved init call to correct place

* fix: corrected temperature calculation (again)

* refactor: removed _curr_pr variable => always have to set PR to desired register on read

* fix: add multi logged topic
2026-01-12 18:42:51 +01:00
Balduin 66e21497a6 FwLateralLongitudinalControl: publish flight phase also if unknown, and with limited rate (#26251)
* FwLateralLongitudinalControl: publish uknown flight phase if TECS not running

* FwLateralLongitudinalControl: publish flight phase with lower rate

For this we store the new flight phase in a local variable, which is
returned by tecs_update_pitch_throttle (but initialised outside to
unknown in case TECS does not run).
2026-01-12 15:30:26 +01:00
Matthias Grob de49edc428 failsafe web simulation: end user friendly mode names + add Altitude cruise and External 1 2026-01-12 11:30:07 +01:00
Matthias Grob b5846fd8c2 Commander: unify RC loss and data link exception options 2026-01-12 11:30:07 +01:00
Silvan ec6dd286fc Commander: COM_RCL_EXCEPT consider all auto modes triggered by action in bit 1
Signed-off-by: Silvan <silvan@auterion.com>
2026-01-12 11:30:07 +01:00
Hamish Willee cf50ecf41b Split out PX4 v1.17 release note (#26225) 2026-01-10 14:06:19 +11:00
Jaeyoung Lim 9fe69d4f33 Make flap slew rate configurable (#26240)
* Make flap slew rate configurable

* Dynamically update params
2026-01-09 06:37:34 -08:00
fakerror f4247aee58 rover_mecanum: enable yaw control via MAVLink SET_POSITION_TARGET commands (#26218)
* rover_mecanum: enable yaw control via MAVLink SET_POSITION_TARGET commands

* Maintain the original judgment conditions

---------

Co-authored-by: V <null>
2026-01-09 08:08:53 -05:00
Beniamino Pozzan ec8f34325e chore(rCS posix): move param override through env var after airframe selection (#26193)
Signed-off-by: Beniamino Pozzan <beniamino.pozzan@gmail.com>
2026-01-09 12:15:45 +01:00
Matthias Grob 0e615816b3 commander/failsafe: fix user takeover not possible in fallback Land action when configured RTL is not possible 2026-01-09 10:10:23 +01:00
Matthias Grob 4cf4f82233 failsafe unit test: add cases for 1 allow taking over from degraded failsafes 2 not cause immediate takeover when failsafe happens because of mode switch
The first test makes sure the user can take over when an RTL failsafe was triggered but degraded to a Land.

The second test rules out the easiest fix of removing the condition `_selected_action == selected_action` which causes the problem for test one but is there for a reason.
2026-01-09 10:10:23 +01:00
mengchaoheng 5f83c186ee Checks for identical parameter changes 2026-01-09 08:53:09 +01:00
Hamish Willee e761297003 Fixed Wing Loiter Modes - Orbit and Figure 8 (#26194) 2026-01-09 17:12:43 +11:00
Alex Klimaj 27181619fc Update GPS submodule (#26238) 2026-01-08 10:24:28 -09:00
Patrik Dominik Pordi 210239324d Added ARK G5 and G5 Heading RTK GPSs (#26154) 2026-01-09 05:59:09 +11:00
Mathieu Bresciani c71e2d41d6 Fixedwing: Fix circular landing when global origin is not set (#26223)
When not specified by navigator, the center of the landing orbit is set
to the current position when landing is triggered.
2026-01-08 14:44:00 +01:00
mahima-yoga 7c318a3296 MulticopterPositionControl: prevent velocity integrator filling up from stale acceleration setpoints
When position control is disabled, clear the setpoint properly to prevent stale values. This fixes a bug where switching to position mode in the same control loop as a hover thrust estimate update could fill up the velocity integrator.
2026-01-08 11:16:52 +01:00
Julian Oes 0375f1a6f0 airframes: don't mess with logging profile (#26234)
I don't think we should change the logging profile based on the type of
airframe configured. Instead, this is an option you set based on the
phase of development/testing you're in.

This came up because the KakuteH7v2 which is 4050 by default would log
excessively which is not a good idea with only 128 MB flash storage.
2026-01-07 20:31:52 -09:00
Pascal 0ef4f1b7bd Add uxrce dds flow control flag (#26209)
* added flow control bitfield

* shortened to 16 char param name length

* refactored changes for uxrce flow control param

* reverted additions to docs

* Update src/modules/uxrce_dds_client/module.yaml

Co-authored-by: Hamish Willee <hamishwillee@gmail.com>

---------

Co-authored-by: minotico <81227020-minotico@users.noreply.github.com>
Co-authored-by: Jacob Dahl <37091262+dakejahl@users.noreply.github.com>
Co-authored-by: Hamish Willee <hamishwillee@gmail.com>
2026-01-07 16:59:03 -09:00
Erkki Eilonen 598066653a cmake: set CMAKE_CXX_STANDARD 17 to match code assumptions (#25767)
Usage of std::in_place_t implies C++17
2026-01-07 16:56:16 -09:00
Claudio Chies 86e1356e0a Extend SENS_GPS_PRIME usage for UAVCAN GNSS devices (#26126)
* UAVCAN: extent SENS_GPS_PRIME usage to UAVCAN GNSS devices

* use convenience function

Co-authored-by: Matthias Grob <maetugr@gmail.com>

* Update src/drivers/uavcan/sensors/gnss.cpp

Co-authored-by: Øyvind Taksdal Stubhaug <o_github@oystub.com>

* Apply suggestion from @MaEtUgR

Co-authored-by: Matthias Grob <maetugr@gmail.com>

* Fix type casting in GPS prime range check

* reverted parameter default

* UAVCAN: fix and improve device_id logic (#26135)

* UAVCAN: extent SENS_GPS_PRIME usage to UAVCAN GNSS devices

* use convenience function

Co-authored-by: Matthias Grob <maetugr@gmail.com>

* Update src/drivers/uavcan/sensors/gnss.cpp

Co-authored-by: Øyvind Taksdal Stubhaug <o_github@oystub.com>

* Apply suggestion from @MaEtUgR

Co-authored-by: Matthias Grob <maetugr@gmail.com>

* Fix type casting in GPS prime range check

* UAVCAN: fix and improve device_id logic

* Added bus information to more UAVCAN drivers

* Fix device_id registration in UavcanBarometerBridge

---------

Co-authored-by: Matthias Grob <maetugr@gmail.com>
Co-authored-by: Øyvind Taksdal Stubhaug <o_github@oystub.com>
Co-authored-by: Jacob Dahl <37091262+dakejahl@users.noreply.github.com>

---------

Co-authored-by: Matthias Grob <maetugr@gmail.com>
Co-authored-by: Øyvind Taksdal Stubhaug <o_github@oystub.com>
Co-authored-by: Jacob Dahl <37091262+dakejahl@users.noreply.github.com>
2026-01-07 10:19:07 -09:00
Balduin 450cf79fc8 FwLateralLongitudinalControl: Publish flight phase (#26219)
* FwLateralLongitudinalControl: publish flight phase

* FwLateralLongitudinalControl: consolidate hrt_absolute_time calls

* FwLateralLongitudinalControl: Name time variables correctly

* FwLateralLongitudinalControl: pass current time as argument rather than class member

* FwLateralLongitudinalControl: use local position timestamp
2026-01-07 11:10:38 +01:00
Claudio Chies 1ff36422c9 docs: UAVCAN asset tracking (#26152) 2026-01-07 14:46:15 +11:00
Nick 38b6a9abf3 pwm: Add PWM center support to Wheel and Gimbal (#26211)
* Add Wheel and Gimbal support to PWM center

* Document Center feature for PWM Gimbal
2026-01-06 18:05:35 +01:00
129 changed files with 3886 additions and 598 deletions
+29 -76
View File
@@ -3,92 +3,45 @@ description: Create a report to help us improve
title: "[Bug] "
labels: ["bug-report"]
body:
- type: markdown
attributes:
value: |
**Tips for a great bug report:**
- Describe what went wrong and what you expected
- Include a flight log link from [logs.px4.io](http://logs.px4.io/) if possible
- Mention your PX4 version, flight controller, and vehicle type if relevant
- type: textarea
attributes:
label: Describe the bug
description: A clear and concise description of the bug.
description: A clear description of the bug and what you expected to happen.
placeholder: |
What happened and what did you expect instead?
Steps to reproduce (if applicable):
1.
2.
3.
validations:
required: true
- type: textarea
attributes:
label: To Reproduce
label: Flight Log / Additional Information
description: |
Steps to reproduce the behavior.
1. Drone switched on '...'
2. Uploaded mission '....' (attach QGC mission file)
3. Took off '....'
4. See error
validations:
required: false
**Flight log** (highly recommended for flight-related issues):
- Upload to [PX4 Flight Review](http://logs.px4.io/) and paste the link
- type: textarea
attributes:
label: Expected behavior
description: A clear and concise description of what you expected to happen.
validations:
required: false
- type: textarea
attributes:
label: Screenshot / Media
description: Add screenshot / media if you have them
- type: textarea
attributes:
label: Flight Log
description: |
*Always* provide a link to the flight log file:
- Download the flight log file from the vehicle ([tutorial](https://docs.px4.io/main/en/getting_started/flight_reporting.html)).
- Upload the log to the [PX4 Flight Review](http://logs.px4.io/)
- Share the link to the log (Copy and paste the URL of the log)
**Additional details** (if relevant):
- PX4 version (output of `ver all` in MAVLink Shell)
- Flight controller model
- Vehicle type (multicopter, fixed-wing, VTOL, etc.)
- Screenshots or media
placeholder: |
# PASTE HERE THE LINK TO THE LOG
Flight log link:
Version:
Hardware:
validations:
required: false
- type: markdown
attributes:
value: |
## Setup
- type: textarea
attributes:
label: Software Version
description: |
Which version of PX4 are you using?
placeholder: |
# If you don't know the version, paste the output of `ver all` in the MAVLink Shell of QGC
validations:
required: false
- type: input
attributes:
label: Flight controller
description: Specify your flight controller model (what type is it, where was it bought from, ...).
validations:
required: false
- type: dropdown
attributes:
label: Vehicle type
options:
- Multicopter
- Helicopter
- Fixed Wing
- Hybrid VTOL
- Airship/Balloon
- Rover
- Boat
- Submarine
- Other
- type: textarea
attributes:
label: How are the different components wired up (including port information)
description: Details about how all is wired.
- type: textarea
attributes:
label: Additional context
description: Add any other context about the problem here.
+1 -1
View File
@@ -1,4 +1,4 @@
blank_issues_enabled: false
blank_issues_enabled: true
contact_links:
- name: Support Question
url: https://docs.px4.io/main/en/contribute/support.html#forums-and-chat
+6
View File
@@ -103,3 +103,9 @@
[submodule "src/drivers/ins/sbgecom/sbgECom"]
path = src/drivers/ins/sbgecom/sbgECom
url = https://github.com/PX4/sbgECom.git
[submodule "src/modules/mc_raptor/blob"]
path = src/modules/mc_raptor/blob
url = https://github.com/rl-tools/px4-blob
[submodule "src/lib/rl_tools/rl_tools"]
path = src/lib/rl_tools/rl_tools
url = https://github.com/rl-tools/rl-tools.git
+10
View File
@@ -6,6 +6,16 @@ CONFIG:
buildType: RelWithDebInfo
settings:
CONFIG: px4_sitl_default
px4_sitl_raptor:
short: px4_sitl_raptor
buildType: RelWithDebInfo
settings:
CONFIG: px4_sitl_raptor
px4_sitl_raptor_debug:
short: px4_sitl_raptor_debug
buildType: Debug
settings:
CONFIG: px4_sitl_raptor
px4_sitl_spacecraft:
short: px4_sitl_spacecraft
buildType: RelWithDebInfo
+1 -1
View File
@@ -267,7 +267,7 @@ endif()
set(package-contact "px4users@googlegroups.com")
set(CMAKE_CXX_STANDARD 14)
set(CMAKE_CXX_STANDARD 17)
set(CMAKE_CXX_STANDARD_REQUIRED ON)
set(CMAKE_C_STANDARD 11)
set(CMAKE_C_STANDARD_REQUIRED ON)
@@ -0,0 +1,35 @@
#!/bin/sh
#
# @name Boat
#
. ${R}etc/init.d/rc.uuv_defaults
PX4_SIMULATOR=${PX4_SIMULATOR:=gz}
PX4_GZ_WORLD=${PX4_GZ_WORLD:=ocean}
PX4_SIM_MODEL=${PX4_SIM_MODEL:=boat}
param set-default SIM_GZ_EN 1
param set-default CA_AIRFRAME 9
param set-default CA_ROTOR_COUNT 2
param set-default CA_ROTOR0_AX 1
param set-default CA_ROTOR0_AZ 0
param set-default CA_ROTOR0_KM 0
param set-default CA_ROTOR0_PX -2
param set-default CA_ROTOR0_PY -1
param set-default CA_ROTOR1_AX 1
param set-default CA_ROTOR1_AZ 0
param set-default CA_ROTOR1_KM 0
param set-default CA_ROTOR1_PX -2
param set-default CA_ROTOR1_PY 1
param set-default CA_R_REV 3
param set-default CA_SV_CS_COUNT 1
param set-default CA_SV_CS0_TYPE 4
param set-default CA_SV_CS0_TRQ_Y 1
param set-default SIM_GZ_EC_FUNC1 101
param set-default SIM_GZ_EC_FUNC2 102
param set-default SIM_GZ_SV_FUNC1 201
@@ -111,6 +111,8 @@ px4_add_romfs_files(
17001_flightgear_tf-g1
17002_flightgear_tf-g2
40000_gz_boat
50000_gz_rover_differential
51000_gz_rover_ackermann
52000_gz_rover_mecanum
+9 -9
View File
@@ -126,15 +126,6 @@ then
set AUTOCNF yes
fi
# Allow overriding parameters via env variables: export PX4_PARAM_{name}={value}
env | while IFS='=' read -r line; do
value=${line#*=}
name=${line%%=*}
case $name in
"PX4_PARAM_"*) param set "${name#PX4_PARAM_}" "$value" ;;
esac
done
# multi-instance setup
# shellcheck disable=SC2154
param set MAV_SYS_ID $((px4_instance+1))
@@ -238,6 +229,15 @@ then
exit 1
fi
# Allow overriding parameters via env variables: export PX4_PARAM_{name}={value}
env | while IFS='=' read -r line; do
value=${line#*=}
name=${line%%=*}
case $name in
"PX4_PARAM_"*) param set "${name#PX4_PARAM_}" "$value" ;;
esac
done
dataman start
# only start the simulator if not in replay mode, as both control the lockstep time
@@ -77,9 +77,6 @@ param set-default NAV_ACC_RAD 2
param set-default RTL_DESCEND_ALT 5
param set-default RTL_RETURN_ALT 5
# Logging Parameters
param set-default SDLOG_PROFILE 131
# Sensors Parameters
param set-default SENS_CM8JL65_CFG 104
param set-default SENS_FLOW_MAXHGT 25
@@ -78,9 +78,6 @@ param set-default NAV_ACC_RAD 2
param set-default RTL_DESCEND_ALT 5
param set-default RTL_RETURN_ALT 5
# Logging Parameters
param set-default SDLOG_PROFILE 131
# Sensors Parameters
param set-default SENS_CM8JL65_CFG 202
param set-default SENS_FLOW_MAXHGT 25
@@ -29,9 +29,6 @@ param set-default MPC_MAN_TILT_MAX 60
param set-default THR_MDL_FAC 0.3
# enable high-rate logging profile (helps with tuning)
param set-default SDLOG_PROFILE 19
param set-default IMU_DGYRO_CUTOFF 50
param set-default IMU_GYRO_CUTOFF 90
+6
View File
@@ -41,3 +41,9 @@ if param compare -s MC_NN_EN 1
then
mc_nn_control start
fi
if param compare -s MC_RAPTOR_ENABLE 1
then
mc_raptor start
fi
+6
View File
@@ -237,6 +237,12 @@ then
tla2528 start -X
fi
# Start TMP102 temperature sensor
if param compare SENS_EN_TMP102 1
then
tmp102 start -X
fi
# probe for optional external I2C devices
if param compare SENS_EXT_I2C_PRB 1
then
+95
View File
@@ -0,0 +1,95 @@
CONFIG_BOARD_ARCHITECTURE="cortex-m7"
CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS0"
CONFIG_BOARD_SERIAL_GPS2="/dev/ttyS6"
CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS5"
CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS3"
CONFIG_BOARD_SERIAL_TEL3="/dev/ttyS1"
CONFIG_BOARD_TOOLCHAIN="arm-none-eabi"
CONFIG_BOARD_UAVCAN_TIMER_OVERRIDE=2
CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y
CONFIG_COMMON_DISTANCE_SENSOR=y
CONFIG_COMMON_LIGHT=y
CONFIG_COMMON_MAGNETOMETER=y
CONFIG_COMMON_OPTICAL_FLOW=y
CONFIG_COMMON_TELEMETRY=y
CONFIG_DRIVERS_ACTUATORS_VERTIQ_IO=y
CONFIG_DRIVERS_ADC_BOARD_ADC=y
CONFIG_DRIVERS_BAROMETER_MS5611=y
CONFIG_DRIVERS_BATT_SMBUS=y
CONFIG_DRIVERS_CAMERA_CAPTURE=y
CONFIG_DRIVERS_CAMERA_TRIGGER=y
CONFIG_DRIVERS_CDCACM_AUTOSTART=y
CONFIG_DRIVERS_DSHOT=y
CONFIG_DRIVERS_GNSS_SEPTENTRIO=y
CONFIG_DRIVERS_GPS=y
CONFIG_DRIVERS_HEATER=y
CONFIG_DRIVERS_IMU_BOSCH_BMI055=y
CONFIG_DRIVERS_IMU_BOSCH_BMI088=y
CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
CONFIG_DRIVERS_POWER_MONITOR_INA228=y
CONFIG_DRIVERS_POWER_MONITOR_INA238=y
CONFIG_DRIVERS_PWM_OUT=y
CONFIG_DRIVERS_PX4IO=y
CONFIG_DRIVERS_TONE_ALARM=y
CONFIG_DRIVERS_UAVCAN=y
CONFIG_LIB_RL_TOOLS=y
CONFIG_MODULES_AIRSPEED_SELECTOR=y
CONFIG_MODULES_BATTERY_STATUS=y
CONFIG_MODULES_CAMERA_FEEDBACK=y
CONFIG_MODULES_COMMANDER=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_DATAMAN=y
CONFIG_MODULES_EKF2=y
CONFIG_MODULES_ESC_BATTERY=y
CONFIG_MODULES_EVENTS=y
CONFIG_MODULES_FLIGHT_MODE_MANAGER=y
CONFIG_MODULES_FW_ATT_CONTROL=n
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=n
CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=n
CONFIG_MODULES_FW_MODE_MANAGER=n
CONFIG_MODULES_FW_RATE_CONTROL=n
CONFIG_MODULES_GIMBAL=y
CONFIG_MODULES_GYRO_CALIBRATION=y
CONFIG_MODULES_LAND_DETECTOR=y
CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=y
CONFIG_MODULES_LOAD_MON=y
CONFIG_MODULES_LOGGER=y
CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y
CONFIG_MODULES_MANUAL_CONTROL=y
CONFIG_MODULES_MAVLINK=y
CONFIG_MODULES_MC_ATT_CONTROL=y
CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y
CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y
CONFIG_MODULES_MC_POS_CONTROL=y
CONFIG_MODULES_MC_RAPTOR=y
CONFIG_MODULES_MC_RATE_CONTROL=y
CONFIG_MODULES_NAVIGATOR=y
CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_SENSORS=y
CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=y
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
CONFIG_MODULES_UXRCE_DDS_CLIENT=y
CONFIG_MODULES_VTOL_ATT_CONTROL=n
CONFIG_NUM_MISSION_ITMES_SUPPORTED=1000
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_BSONDUMP=y
CONFIG_SYSTEMCMDS_DMESG=y
CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y
CONFIG_SYSTEMCMDS_I2CDETECT=y
CONFIG_SYSTEMCMDS_LED_CONTROL=y
CONFIG_SYSTEMCMDS_MFT=y
CONFIG_SYSTEMCMDS_MTD=y
CONFIG_SYSTEMCMDS_NSHTERM=y
CONFIG_SYSTEMCMDS_PARAM=y
CONFIG_SYSTEMCMDS_PERF=y
CONFIG_SYSTEMCMDS_REBOOT=y
CONFIG_SYSTEMCMDS_SD_BENCH=y
CONFIG_SYSTEMCMDS_SYSTEM_TIME=y
CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y
CONFIG_SYSTEMCMDS_TOP=y
CONFIG_SYSTEMCMDS_TUNE_CONTROL=y
CONFIG_SYSTEMCMDS_UORB=y
CONFIG_SYSTEMCMDS_VER=y
CONFIG_SYSTEMCMDS_WORK_QUEUE=y
CONFIG_USE_IFCI_CONFIGURATION=y
+89
View File
@@ -0,0 +1,89 @@
CONFIG_BOARD_ETHERNET=y
CONFIG_BOARD_ROOT_PATH="."
CONFIG_BOARD_TESTING=y
CONFIG_COMMON_SIMULATION=y
CONFIG_DRIVERS_CAMERA_TRIGGER=y
CONFIG_DRIVERS_GNSS_SEPTENTRIO=y
CONFIG_DRIVERS_GPS=y
CONFIG_DRIVERS_OSD_MSP_OSD=y
CONFIG_DRIVERS_TONE_ALARM=y
CONFIG_EKF2_VERBOSE_STATUS=y
CONFIG_EXAMPLES_DYN_HELLO=y
CONFIG_EXAMPLES_FAKE_GPS=y
CONFIG_EXAMPLES_FAKE_IMU=y
CONFIG_EXAMPLES_FAKE_MAGNETOMETER=y
CONFIG_EXAMPLES_HELLO=y
CONFIG_EXAMPLES_PX4_MAVLINK_DEBUG=y
CONFIG_EXAMPLES_PX4_SIMPLE_APP=y
CONFIG_EXAMPLES_WORK_ITEM=y
CONFIG_FIGURE_OF_EIGHT=y
CONFIG_LIB_RL_TOOLS=y
CONFIG_MAVLINK_DIALECT="development"
CONFIG_MODE_NAVIGATOR_VTOL_TAKEOFF=y
CONFIG_MODULES_AIRSHIP_ATT_CONTROL=y
CONFIG_MODULES_AIRSPEED_SELECTOR=y
CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=y
CONFIG_MODULES_CAMERA_FEEDBACK=y
CONFIG_MODULES_COMMANDER=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_DATAMAN=y
CONFIG_MODULES_EKF2=y
CONFIG_MODULES_EVENTS=y
CONFIG_MODULES_FLIGHT_MODE_MANAGER=y
CONFIG_MODULES_FW_ATT_CONTROL=y
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y
CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y
CONFIG_MODULES_FW_MODE_MANAGER=y
CONFIG_MODULES_FW_RATE_CONTROL=y
CONFIG_MODULES_GIMBAL=y
CONFIG_MODULES_GYRO_CALIBRATION=y
CONFIG_MODULES_GYRO_FFT=y
CONFIG_MODULES_LAND_DETECTOR=y
CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=y
CONFIG_MODULES_LOAD_MON=y
CONFIG_MODULES_LOCAL_POSITION_ESTIMATOR=y
CONFIG_MODULES_LOGGER=y
CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y
CONFIG_MODULES_MANUAL_CONTROL=y
CONFIG_MODULES_MAVLINK=y
CONFIG_MODULES_MC_ATT_CONTROL=y
CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y
CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y
CONFIG_MODULES_MC_POS_CONTROL=y
CONFIG_MODULES_MC_RAPTOR=y
CONFIG_MODULES_MC_RATE_CONTROL=y
CONFIG_MODULES_NAVIGATOR=y
CONFIG_MODULES_PAYLOAD_DELIVERER=y
CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_REPLAY=y
CONFIG_MODULES_ROVER_ACKERMANN=y
CONFIG_MODULES_ROVER_DIFFERENTIAL=y
CONFIG_MODULES_ROVER_MECANUM=y
CONFIG_MODULES_SENSORS=y
CONFIG_MODULES_SIMULATION_GZ_BRIDGE=y
CONFIG_MODULES_SIMULATION_GZ_MSGS=y
CONFIG_MODULES_SIMULATION_GZ_PLUGINS=y
CONFIG_MODULES_SIMULATION_SENSOR_AGP_SIM=y
CONFIG_MODULES_SPACECRAFT=n
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
CONFIG_MODULES_UUV_ATT_CONTROL=y
CONFIG_MODULES_UUV_POS_CONTROL=y
CONFIG_MODULES_UXRCE_DDS_CLIENT=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_NUM_MISSION_ITMES_SUPPORTED=10000
CONFIG_PLATFORM_POSIX=y
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_BSONDUMP=y
CONFIG_SYSTEMCMDS_DYN=y
CONFIG_SYSTEMCMDS_FAILURE=y
CONFIG_SYSTEMCMDS_LED_CONTROL=y
CONFIG_SYSTEMCMDS_PARAM=y
CONFIG_SYSTEMCMDS_PERF=y
CONFIG_SYSTEMCMDS_SD_BENCH=y
CONFIG_SYSTEMCMDS_SHUTDOWN=y
CONFIG_SYSTEMCMDS_SYSTEM_TIME=y
CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y
CONFIG_SYSTEMCMDS_TUNE_CONTROL=y
CONFIG_SYSTEMCMDS_UORB=y
CONFIG_SYSTEMCMDS_VER=y
CONFIG_SYSTEMCMDS_WORK_QUEUE=y
Binary file not shown.

After

Width:  |  Height:  |  Size: 550 KiB

File diff suppressed because one or more lines are too long

After

Width:  |  Height:  |  Size: 81 KiB

File diff suppressed because one or more lines are too long

After

Width:  |  Height:  |  Size: 57 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 204 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 5.5 KiB

After

Width:  |  Height:  |  Size: 37 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 210 KiB

+9 -4
View File
@@ -128,7 +128,7 @@
- [LED Meanings](getting_started/led_meanings.md)
- [Tune/Sound Meanings](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 Controllers (Autopilots)](flight_controller/index.md)
- [Flight Controller Selection](getting_started/flight_controller_selection.md)
@@ -271,6 +271,8 @@
- [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)
@@ -820,9 +822,11 @@
- [Camera Integration/Architecture](camera/camera_architecture.md)
- [Computer Vision](advanced/computer_vision.md)
- [Motion Capture (VICON, Optitrack, NOKOV)](tutorials/motion-capture.md)
- [Neural Networks](advanced/neural_networks.md)
- [Neural Network Module Utilities](advanced/nn_module_utilities.md)
- [TensorFlow Lite Micro (TFLM)](advanced/tflm.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)
- [Installing driver for Intel RealSense R200](advanced/realsense_intel_driver.md)
- [Switching State Estimators](advanced/switching_state_estimators.md)
- [Out-of-Tree Modules](advanced/out_of_tree_modules.md)
@@ -902,6 +906,7 @@
- [Licenses](contribute/licenses.md)
- [Releases](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 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 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 values may also be provided in gimbal documentation.
## Gimbal Control in Missions
+1 -119
View File
@@ -1,119 +1 @@
# 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.
### 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).
<Redirect to="../neural_networks/mc_neural_network_control" />
+4
View File
@@ -10,6 +10,10 @@ 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.
+7 -11
View File
@@ -121,21 +121,22 @@ 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 [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).
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).
Additional (and underlying) parameter settings are shown below.
| Parameter | Setting | Description |
| ----------------------------------------------------------------------------------------------------- | --------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- |
| <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_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_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) | Failsafe Action | Disabled, Loiter, Return, Land, Disarm, Terminate. |
| <a id="COM_RCL_EXCEPT"></a>[COM_RCL_EXCEPT](../advanced_config/parameter_reference.md#COM_RCL_EXCEPT) | RC Loss Exceptions | Set the modes in which manual control loss is ignored: Mission, Hold, Offboard. |
| <a id="COM_RCL_EXCEPT"></a>[COM_RCL_EXCEPT](../advanced_config/parameter_reference.md#COM_RCL_EXCEPT) | RC Loss Exceptions | Set modes in which manual control loss is ignored. |
## Data Link Loss Failsafe
The Data Link Loss failsafe is triggered if a telemetry link (connection to ground station) is lost.
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)
@@ -145,12 +146,7 @@ The settings and underlying parameters are shown below.
| ---------------------- | ------------------------------------------------------------------------ | --------------------------------------------------------------------------------- |
| Data Link Loss Timeout | [COM_DL_LOSS_T](../advanced_config/parameter_reference.md#COM_DL_LOSS_T) | Amount of time after losing the data connection before the failsafe will trigger. |
| Failsafe Action | [NAV_DLL_ACT](../advanced_config/parameter_reference.md#NAV_DLL_ACT) | Disabled, Hold mode, Return mode, Land mode, Disarm, Terminate. |
The following settings also apply, but are not displayed in the QGC UI.
| Setting | Parameter | Description |
| ----------------------------------------------------------- | -------------------------------------------------------------------------- | ---------------------------------------------------- |
| <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. |
| <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. |
## Geofence Failsafe
+68
View File
@@ -0,0 +1,68 @@
# 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.
:::
## Overview
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.
## Flight Log Analysis
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
@@ -0,0 +1,112 @@
# 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)
## Where to Buy
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)
- Sensors
- [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
- Buzzer
- 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
- Dimensions
- 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
## Hardware Setup
### Wiring
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.
### Mounting
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)).
The steps are:
- 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 Configuration
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 Meanings
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
@@ -0,0 +1,150 @@
# 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)
## Where to Buy
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)
- Sensors
- [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
- Buzzer
- 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
- Dimensions
- 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
## Hardware Setup
### Wiring
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.
### Mounting
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)).
The steps are:
- 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 Configuration
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 Meanings
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,6 +27,8 @@ 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).
## Supported Hardware
+1 -1
View File
@@ -1,6 +1,6 @@
# Gain compression
<Badge type="tip" text="main (planned for: PX4 v1.17)" />
<Badge type="tip" text="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="main (planned for: PX4 v1.17)" />
<Badge type="tip" text="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="main (planned for: PX4 v1.17)" />
<Badge type="tip" text="PX4 v1.17" />
:::warning
PX4 does not manufacture this (or any) autopilot.
+18 -16
View File
@@ -1,6 +1,6 @@
# AP-H743-R1
# AP-H743-R1 Flight Controller
<Badge type="tip" text="main (planned for: PX4 v1.17)" />
<Badge type="tip" text="PX4 v1.17" />
:::warning
PX4 does not manufacture this (or any) autopilot.
@@ -50,6 +50,7 @@ These flight controllers are [manufacturer supported](../flight_controller/autop
Order from [X-MAV](https://www.x-mav.cn/).
## Radio Control
A Radio Control (RC) system is required if you want to manually control your vehicle (PX4 does not require a radio system for autonomous flight modes).
You will need to select a compatible transmitter/receiver and then bind them so that they communicate (read the instructions that come with your specific transmitter/receiver).
@@ -59,14 +60,14 @@ CRSF receiver must be wired to a spare port (UART) on the Flight Controller. The
## Serial Port Mapping
| UART | Device | Port |
| ------ | ---------- | ------------- |
| USART1 | /dev/ttyS0 | GPS |
| USART2 | /dev/ttyS1 | GPS2 |
| USART3 | /dev/ttyS2 | TELEM1 |
| UART4 | /dev/ttyS3 | TELEM2 |
| UART7 | /dev/ttyS4 | TELEM3 |
| UART8 | /dev/ttyS5 | SERIAL4 |
| UART | Device | Port |
| ------ | ---------- | ------- |
| USART1 | /dev/ttyS0 | GPS |
| USART2 | /dev/ttyS1 | GPS2 |
| USART3 | /dev/ttyS2 | TELEM1 |
| UART4 | /dev/ttyS3 | TELEM2 |
| UART7 | /dev/ttyS4 | TELEM3 |
| UART8 | /dev/ttyS5 | SERIAL4 |
## PWM Output
@@ -133,13 +134,14 @@ The complete set of supported configurations can be found in the [Airframe Refer
## Debug Port
### SWD
The [SWD interface](../debug/swd_debug.md) operate on the **FMU-DEBUG** port (`FMU-DEBUG`).
The debug port (`FMU-DEBUG`) uses a [JST SM04B-GHS-TB](https://www.digikey.com/en/products/detail/jst-sales-america-inc/SM04B-GHS-TB/807788) connector and has the following pinout:
| Pin | Signal | Volt |
| ------- | -------------- | ----- |
| 1 (red) | 5V+ | +5V |
| 2 (blk) | FMU_SWDIO | +3.3V |
| 3 (blk) | FMU_SWCLK | +3.3V |
| 4 (blk) | GND | GND |
| Pin | Signal | Volt |
| ------- | --------- | ----- |
| 1 (red) | 5V+ | +5V |
| 2 (blk) | FMU_SWDIO | +3.3V |
| 3 (blk) | FMU_SWCLK | +3.3V |
| 4 (blk) | GND | GND |
+68 -9
View File
@@ -2,11 +2,14 @@
<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 (circle) around its current GPS position and maintain its current altitude.
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.
:::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 switch.
It is usually activated with a pre-programmed RC switch.
:::
::: info
@@ -24,24 +27,80 @@ It is usually activated with a pre-programmed switch.
:::
## Technical Summary
## Loiter modes
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.
### Default Loiter
RC stick movement is ignored.
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.
### Parameters
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
```
## Parameters
Hold mode behaviour can be configured using the parameters below.
| Parameter | Description |
| -------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------- |
| [NAV_LOITER_RAD](../advanced_config/parameter_reference.md#NAV_LOITER_RAD) | The radius of the loiter circle. |
| <a id="NAV_LOITER_RAD"></a>[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="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)" />.
- 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" />.
- QGroundControl does not support `MAV_CMD_NAV_TAKEOFF` (at time of writing).
:::
+48 -40
View File
@@ -20,52 +20,59 @@ The RTK compatible devices below that are expected to work with PX4 (it omits di
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).
| Device | GPS | Compass | [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 | ✓ | | ✓ | |
| Device | GPS | Compass | [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 | ✓ | | ✓ | |
<!-- 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
[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
[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
[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
Notes:
@@ -143,6 +150,7 @@ The RTK GPS connection is essentially plug and play:
![survey-in](../../assets/qgc/setup/rtk/qgc_rtk_survey-in.png)
1. Once Survey-in completes:
- 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 -2
View File
@@ -321,7 +321,7 @@ 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.
- <Badge type="tip" text="PX4 v1.17" /> [`UXRCE_DDS_NS_IDX`](../advanced_config/parameter_reference.md#UXRCE_DDS_NS_IDX): Index-based namespace definition
- [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.
@@ -426,7 +426,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) 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) <Badge type="tip" text="PX4 v1.17" /> 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
@@ -0,0 +1,21 @@
# 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) | ✘ |
@@ -0,0 +1,119 @@
# 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.
### 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).
@@ -2,7 +2,7 @@
The neural control module ([mc_nn_control](../modules/modules_controller.md#mc-nn-control)) implements an end-to-end controller utilizing neural networks.
The parts of the module directly concerned with generating the code for the trained neural network and integrating it into the module are covered in [TensorFlow Lite Micro (TFLM)](../advanced/tflm.md).
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
@@ -75,7 +75,7 @@ Which timing library is included and used is based on wether PX4 is built with N
## Changing the setpoint
The module uses the [TrajectorySetpoint](../msg_docs/TrajectorySetpoint.md) messages position fields to define its target.
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.
+221
View File
@@ -0,0 +1,221 @@
# 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.
## Overview
![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).
## Structure
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.
## Features
- 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
## Usage
### 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
#### Setup
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)
### Troubleshooting
#### Logging
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
```
@@ -1,6 +1,6 @@
# TensorFlow Lite Micro (TFLM)
The PX4 [Multicopter Neural Network](../advanced/neural_networks.md) module ([mc_nn_control](../modules/modules_controller.md#mc-nn-control)) integrates a neural network that uses the [TensorFlow Lite Micro (TFLM)](https://github.com/tensorflow/tflite-micro) inference library.
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.
@@ -68,7 +68,7 @@ The `_input_tensor` is also defined, it is fetched from `_control_interpreter->i
The `_input_tensor` is filled in the `PopulateInputTensor()` function.
`_input_tensor` works by accessing the `->data.f` member array and fill in the required inputs for your network.
The inputs used in the control network is covered in [Neural Networks](../advanced/neural_networks.md).
The inputs used in the control network is covered in [MC Neural Networks Control](../neural_networks/mc_neural_network_control.md).
### Outputs
+2
View File
@@ -129,6 +129,7 @@ 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))
@@ -138,6 +139,7 @@ Please continue reading for [upgrade instructions](#upgrade-guide).
- Parameter to always start mavlink stream via USB. ([PX4-Autopilot#22234](https://github.com/PX4/PX4-Autopilot/pull/22234))
- Refactor: MAVLink message handling in one function, reference instead of pointer to main instance ([PX4-Autopilo#23219](https://github.com/PX4/PX4-Autopilot/pull/22234))
- mavlink log handler rewrite for improved effeciency ([PX4-Autopilo#23219](https://github.com/PX4/PX4-Autopilot/pull/22234))
### Multi-Rotor
- [Multirotor] add yaw torque low pass filter ([PX4-Autopilot#24173](https://github.com/PX4/PX4-Autopilot/pull/24173))
+134
View File
@@ -0,0 +1,134 @@
# 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)).
-->
### Control
<!--
- 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))
-->
### Simulation
- 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))
### Rover
- 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
+2 -1
View File
@@ -2,7 +2,8 @@
A list of PX4 release notes, they contain a list of the changes that went into each release, explaining the included features, bug fixes, deprecations and updates in detail.
- [main](../releases/main.md) (changes since v1.16)
- [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)
- [v1.16](../releases/1.16.md)
- [v1.15](../releases/1.15.md)
- [v1.14](../releases/1.14.md)
+30 -6
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.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.
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.
:::
## Read Before Upgrading
TBD …
- TBD …
Please continue reading for [upgrade instructions](#upgrade-guide).
@@ -45,8 +45,7 @@ Please continue reading for [upgrade instructions](#upgrade-guide).
### Control
- 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](https://github.com/PX4/PX4-Autopilot/pull/25435)).
### Estimation
@@ -59,19 +58,34 @@ Please continue reading for [upgrade instructions](#upgrade-guide).
### Simulation
- 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 / ROS2
### uXRCE-DDS / Zenoh / ROS2
- TBD
<!-- MOVED THIS TO v1.17
- [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
@@ -92,16 +106,26 @@ 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))
-->
### Rover
- 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
@@ -341,9 +341,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="main (planned for: 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="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="main (planned for: PX4 v1.17)" /> Direct access to rover control setpoints (Position, Speed, Attitude, Rate, Throttle and Steering).
- [Rover Setpoints](#rover-setpoints): <Badge type="tip" text="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).
@@ -410,7 +410,7 @@ _goto_setpoint->update(
#### Fixed-Wing Lateral and Longitudinal Setpoint (FwLateralLongitudinalSetpointType)
<Badge type="warning" text="Fixed wing only" /> <Badge type="tip" text="main (planned for: PX4 v1.17)" />
<Badge type="warning" text="Fixed wing only" /> <Badge type="tip" text="PX4 v1.17" />
::: info
This setpoint type is supported for fixed-wing vehicles and for VTOLs in fixed-wing mode.
@@ -552,7 +552,7 @@ If you want to control an actuator that does not control the vehicle's motion, b
#### Rover Setpoints
<Badge type="tip" text="main (planned for: PX4 v1.17)" /> <Badge type="warning" text="Experimental" />
<Badge type="tip" text="PX4 v1.17" /> <Badge type="warning" text="Experimental" />
The rover modules use a hierarchical structure to propagate setpoints:
@@ -586,7 +586,7 @@ An example for a rover specific drive mode using the `RoverSpeedAttitudeSetpoint
### Controlling a VTOL
<Badge type="tip" text="main (planned for: PX4 v1.17)" /> <Badge type="warning" text="Experimental" />
<Badge type="tip" text="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:
+3 -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 `main` (expected to be PX4 v1.17).
- SIH for Ackermann Rover from `main`.
- SIH for MC Hexacopter X from PX4 v1.17.
- SIH for Ackermann Rover from PX4 v1.17.
### Benefits
@@ -339,6 +339,7 @@ You can find a full list of available values for `PWM_MAIN_FUNCn` [here](../adva
Alternatively, you can use the [`PWM_AUX_FUNCn`](../advanced_config/parameter_reference.md#PWM_AUX_FUNC1) parameters.
You may also configure the output as desired:
- Disarmed PWM: ([`PWM_MAIN_DISn`](../advanced_config/parameter_reference.md#PWM_MAIN_DIS1) / [`PWM_AUX_DIS1`](../advanced_config/parameter_reference.md#PWM_AUX_DIS1))
- Minimum PWM ([`PWM_MAIN_MINn`](../advanced_config/parameter_reference.md#PWM_MAIN_MIN1) / [`PWM_AUX_MINn`](../advanced_config/parameter_reference.md#PWM_AUX_MIN1))
- Maximum PWM ([`PWM_MAIN_MAXn`](../advanced_config/parameter_reference.md#PWM_MAIN_MAX1) / [`PWM_AUX_MAXn`](../advanced_config/parameter_reference.md#PWM_AUX_MAX1))
+2
View File
@@ -257,6 +257,8 @@ set(msg_files
versioned/LongitudinalControlConfiguration.msg
versioned/ManualControlSetpoint.msg
versioned/ModeCompleted.msg
versioned/RaptorInput.msg
versioned/RaptorStatus.msg
versioned/RegisterExtComponentReply.msg
versioned/RegisterExtComponentRequest.msg
versioned/TrajectorySetpoint.msg
+8 -1
View File
@@ -1,8 +1,15 @@
# Auxiliary control fields for fixed-wing runway takeoff/landing
# Passes information from the FixedWingModeManager to the FixedWingAttitudeController
# Passes information from the FixedWingModeManager to the FixedWingAttitudeController (wheel control) and FixedWingLandDetector (takeoff state)
uint64 timestamp # [us] time since system start
uint8 STATE_THROTTLE_RAMP = 0 # ramping up throttle
uint8 STATE_CLAMPED_TO_RUNWAY = 1 # clamped to runway, controlling yaw directly (wheel or rudder)
uint8 STATE_CLIMBOUT = 2 # climbout to safe height before navigation
uint8 STATE_FLYING = 3 # navigate freely
uint8 runway_takeoff_state # Current state of runway takeoff state machine
bool wheel_steering_enabled # Flag that enables the wheel steering.
float32 wheel_steering_nudging_rate # [norm] [@range -1, 1] [FRD] Manual wheel nudging, added to controller output. NAN is interpreted as 0.
+18
View File
@@ -0,0 +1,18 @@
# Raptor Input
# The exact inputs to the Raptor foundation policy.
# Having access to the exact inputs helps with debugging and post-hoc analysis.
uint32 MESSAGE_VERSION = 0
uint64 timestamp # [us] Time since system start
uint64 timestamp_sample # [us] Sampling timestamp of the data this control response is based on
bool active # Signals if the policy is active (aka publishing actuator_motors)
float32[3] position # [m] [@frame FLU] Position of the vehicle_local_position frame
float32[4] orientation # [-] Orientation in the vehicle_attitude frame but using the FLU convention as a unit quaternion (w, x, y, z)
float32[3] linear_velocity # [m/s] [@frame FLU] Linear velocity in the vehicle_local_position frame
float32[3] angular_velocity # [rad/s] [@frame FLU] Angular velocity in the body frame
uint8 ACTION_DIM = 4 # Policy output dimensionality (for quadrotors)
float32[4] previous_action # [@range -1, 1] Previous action. Motor commands normalized to [-1, 1]
# TOPICS raptor_input
+46
View File
@@ -0,0 +1,46 @@
# Raptor Status
# Diagnostic messages for the Raptor foundation policy.
# This diagnostic data is useful for debugging (e.g. identifying missing input information).
uint32 MESSAGE_VERSION = 0
uint64 timestamp # [us] Time since system start
uint64 timestamp_sample # [us] Sampling timestamp of the data this control response is based on
bool subscription_update_angular_velocity # [bool] Flag signalling if the vehicle_angular_velocity was updated
bool subscription_update_local_position # [bool] Flag signalling if the vehicle_local_position was updated
bool subscription_update_attitude # [bool] Flag signalling if the vehicle_attitude was updated
bool subscription_update_trajectory_setpoint # [bool] Flag signalling if the trajectory_setpoint was updated
bool subscription_update_vehicle_status # [bool] Flag signalling if the vehicle_status was updated
uint8 exit_reason # [enum] Exit reason identifier. Representing conditions that lead to the Raptor policy not being executed
uint8 EXIT_REASON_NONE = 0 # No exit reason => Raptor control step was executed (actuator_motors should have been published)
uint8 EXIT_REASON_NO_ANGULAR_VELOCITY_UPDATE = 1 # We synchronize the control onto the input observation with the highest update frequency, which is vehicle_angular_velocity. If there was no update, we do not need to execute the policy again
uint8 EXIT_REASON_NOT_ALL_OBSERVATIONS_SET = 2 # We can not execute the policy if not all observations are available
uint8 EXIT_REASON_ANGULAR_VELOCITY_STALE = 3 # If OBSERVATION_TIMEOUT_ANGULAR_VELOCITY is exceeded, we treat the vehicle_angular_velocity as stale and can not run the policy
uint8 EXIT_REASON_LOCAL_POSITION_STALE = 4 # If OBSERVATION_TIMEOUT_LOCAL_POSITION is exceeded, we treat the vehicle_local_position as stale and can not run the policy
uint8 EXIT_REASON_ATTITUDE_STALE = 5 # If OBSERVATION_TIMEOUT_ATTITUDE is exceeded, we treat the vehicle_attitude as stale and can not run the policy
uint8 EXIT_REASON_EXECUTOR_STATUS_SOURCE_NOT_CONTROL = 6 # The executor that runs the policy can run in oversampling mode, where it decides if the policy should be ran based on the timestamp and not based on fixed synchronization onto the vehicle_angular_velocity. In this case the executor can decide to skip running the policy if the interval is too small, in which case this flag is set.
uint32 timestamp_last_vehicle_angular_velocity # [us] Timestamp of the last received vehicle_angular_velocity message
uint32 timestamp_last_vehicle_local_position # [us] Timestamp of the last received vehicle_local_position message
uint32 timestamp_last_vehicle_attitude # [us] Timestamp of the last received vehicle_attitude message
uint32 timestamp_last_trajectory_setpoint # [us] Timestamp of the last received trajectory_setpoint message
bool vehicle_angular_velocity_stale # [bool] True if vehicle_angular_velocity data is considered stale (exceeded timeout)
bool vehicle_local_position_stale # [bool] True if vehicle_local_position data is considered stale (exceeded timeout)
bool vehicle_attitude_stale # [bool] True if vehicle_attitude data is considered stale (exceeded timeout)
bool trajectory_setpoint_stale # [bool] True if trajectory_setpoint data is considered stale (exceeded timeout)
bool active # [bool] True if the Raptor policy is currently active (publishing actuator_motors)
uint8 substep # [-] The policy is trained at a fixed frequency (e.g. 100 Hz) but we might want to use it for control at higher frequencies (e.g. 400 Hz), which leads to a number of intermediate steps before the actual policy state is advanced (in this case 4 = 400 Hz / 100 Hz). This field provides the current substep (e.g. 0-3).
float32 control_interval # [s] Time interval between control updates
float32 trajectory_setpoint_dt_mean # [us] The average trajectory setpoint arrival time interval (since Raptor mode activation within NUM_TRAJECTORY_SETPOINT_DTS received trajectory_setpoint messages)
float32 trajectory_setpoint_dt_max # [us] The max trajectory setpoint arrival time interval (since Raptor mode activation and within NUM_TRAJECTORY_SETPOINT_DTS received trajectory_setpoint messages)
float32 trajectory_setpoint_dt_max_since_activation # [us] The max trajectory setpoint arrival time interval (since Raptor mode activation)
float32[3] internal_reference_position # [m] [@frame FLU] Internal reference position
float32[3] internal_reference_linear_velocity # [m/s] [@frame FLU] Internal reference linear velocity
# TOPICS raptor_status
+2
View File
@@ -184,6 +184,7 @@
#define DRV_IMU_DEVTYPE_UAVCAN 0x87
#define DRV_MAG_DEVTYPE_UAVCAN 0x88
#define DRV_DIST_DEVTYPE_UAVCAN 0x89
#define DRV_HYGRO_DEVTYPE_UAVCAN 0x8A
#define DRV_ADC_DEVTYPE_ADS1115 0x90
@@ -266,6 +267,7 @@
#define DRV_TEMP_DEVTYPE_MCP9808 0xEE
#define DRV_TEMP_DEVTYPE_TMP102 0xF0
#define DRV_DEVTYPE_UNUSED 0xff
@@ -0,0 +1,45 @@
############################################################################
#
# Copyright (c) 2026 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.
#
############################################################################
px4_add_module(
MODULE drivers__temperature_sensor__tmp102
MAIN tmp102
COMPILE_FLAGS
SRCS
tmp102_main.cpp
tmp102.cpp
MODULE_CONFIG
module.yaml
DEPENDS
px4_work_queue
)
@@ -0,0 +1,5 @@
menuconfig DRIVERS_TEMPERATURE_SENSOR_TMP102
bool "TMP102 temperature sensor"
default n
---help---
Enable support for the TMP102 temperature sensor
@@ -0,0 +1,15 @@
__max_num_config_instances: &max_num_config_instances 1
module_name: TMP102
parameters:
- group: Sensors
definitions:
SENS_EN_TMP102:
description:
short: Enable TMP102
long: |
Enable the driver for the TMP102 temperature sensor
type: boolean
reboot_required: true
default: 0
@@ -0,0 +1,129 @@
/****************************************************************************
*
* Copyright (c) 2026 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.
*
****************************************************************************/
#include "tmp102.h"
TMP102::TMP102(const I2CSPIDriverConfig &config) :
I2C(config),
I2CSPIDriver(config),
_cycle_perf(perf_alloc(PC_ELAPSED, MODULE_NAME": single-sample")),
_comms_errors(perf_alloc(PC_COUNT, MODULE_NAME": comms errors"))
{
}
TMP102::~TMP102()
{
ScheduleClear();
perf_free(_cycle_perf);
perf_free(_comms_errors);
}
void TMP102::RunImpl()
{
if (should_exit()) {
exit_and_cleanup();
return;
}
perf_begin(_cycle_perf);
float temperature = read_temperature();
if (std::isnan(temperature)) {
perf_count(_comms_errors);
} else {
sensor_temp_s _sensor_temp{};
_sensor_temp.timestamp = hrt_absolute_time();
_sensor_temp.temperature = temperature;
_sensor_temp.device_id = get_device_id();
_sensor_temp_pub.publish(_sensor_temp);
}
perf_end(_cycle_perf);
}
int TMP102::probe()
{
uint16_t conf_reg;
for (int i = 0; i < 3; i++) {
if (read_reg(TMP102_CONFIG_REG, conf_reg) == PX4_OK && (conf_reg | 0x0020) == DEFAULT_CONFIG_REG) { // Mask the AL bit
return PX4_OK;
}
px4_sleep(1);
}
return PX4_ERROR;
}
int TMP102::init()
{
int ret = I2C::init();
if (ret != PX4_OK) {
PX4_ERR("TMP102, I2C init failed");
return ret;
}
_sensor_temp_pub.advertise();
ScheduleOnInterval(250_ms); // DEFAULT SAMPLE RATE IS 4HZ => 250ms INTERVAL
return PX4_OK;
}
float TMP102::read_temperature()
{
uint16_t tmp_data;
if (read_reg(TMP102_TEMP_REG, tmp_data) != PX4_OK) {
return NAN;
}
float temperature = ((int16_t)(tmp_data) >> 4) * 0.0625f;
return temperature;
}
int TMP102::read_reg(uint8_t reg, uint16_t &data)
{
uint8_t tmp_data[2];
tmp_data[0] = reg;
if (transfer(tmp_data, 1, nullptr, 0) != PX4_OK) { // Set the PR to the desired register
return PX4_ERROR;
}
int ret = transfer(nullptr, 0, tmp_data, 2); // Read the data from the desired register
data = (tmp_data[0] << 8) | tmp_data[1];
return ret;
}
@@ -0,0 +1,73 @@
/****************************************************************************
*
* Copyright (c) 2026 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.
*
****************************************************************************/
#pragma once
#include <stdint.h>
#include <drivers/device/i2c.h>
#include <px4_platform_common/i2c_spi_buses.h>
#include <uORB/topics/sensor_temp.h>
#include <uORB/PublicationMulti.hpp>
#include <lib/perf/perf_counter.h>
#include <drivers/drv_hrt.h>
using namespace time_literals;
#define TMP102_TEMP_REG 0x00
#define TMP102_CONFIG_REG 0x01
#define TMP102_TLOW_REG 0x02
#define TMP102_THIGH_REG 0x03
constexpr uint16_t DEFAULT_CONFIG_REG = 0x60A0; // 12-bit resolution, comparator mode, active low, 4Hz
class TMP102 : public device::I2C, public I2CSPIDriver<TMP102>
{
public:
TMP102(const I2CSPIDriverConfig &config);
~TMP102() override;
int init() override;
int probe() override;
void RunImpl();
static void print_usage();
protected:
void print_status();
private:
uORB::PublicationMulti<sensor_temp_s> _sensor_temp_pub{ORB_ID(sensor_temp)};
perf_counter_t _cycle_perf;
perf_counter_t _comms_errors;
float read_temperature();
int read_reg(uint8_t address, uint16_t &data);
};
@@ -0,0 +1,90 @@
/****************************************************************************
*
* Copyright (c) 2026 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.
*
****************************************************************************/
/**
* @file tmp102_main.cpp
* @author Philipp Engljaehringer
*
* Driver for the TMP102 Temperature Sensor connected via I2C.
*/
#include "tmp102.h"
#include <px4_platform_common/module.h>
void TMP102::print_usage()
{
PRINT_MODULE_USAGE_NAME("tmp102", "driver");
PRINT_MODULE_USAGE_COMMAND("start");
PRINT_MODULE_USAGE_PARAMS_I2C_SPI_DRIVER(true, false);
PRINT_MODULE_USAGE_PARAMS_I2C_ADDRESS(0x48);
PRINT_MODULE_USAGE_DEFAULT_COMMANDS();
}
void TMP102::print_status()
{
I2CSPIDriverBase::print_status();
perf_print_counter(_cycle_perf);
perf_print_counter(_comms_errors);
}
extern "C" int tmp102_main(int argc, char *argv[])
{
using ThisDriver = TMP102;
BusCLIArguments cli{true, false};
cli.default_i2c_frequency = 400000;
cli.i2c_address = 0x48;
const char *verb = cli.parseDefaultArguments(argc, argv);
if (!verb) {
ThisDriver::print_usage();
return -1;
}
BusInstanceIterator iterator(MODULE_NAME, cli, DRV_TEMP_DEVTYPE_TMP102);
if (!strcmp(verb, "start")) {
return ThisDriver::module_start(cli, iterator);
}
if (!strcmp(verb, "stop")) {
return ThisDriver::module_stop(iterator);
}
if (!strcmp(verb, "status")) {
return ThisDriver::module_status(iterator);
}
ThisDriver::print_usage();
return -1;
}
-2
View File
@@ -43,8 +43,6 @@
#include <drivers/drv_hrt.h>
#include <lib/atmosphere/atmosphere.h>
#define MOTOR_BIT(x) (1<<(x))
using namespace time_literals;
UavcanEscController::UavcanEscController(uavcan::INode &node) :
+1 -5
View File
@@ -47,13 +47,9 @@
#include <uavcan/uavcan.hpp>
#include <uavcan/equipment/esc/RawCommand.hpp>
#include <uavcan/equipment/esc/Status.hpp>
#include <lib/perf/perf_counter.h>
#include <uORB/PublicationMulti.hpp>
#include <uORB/topics/actuator_outputs.h>
#include <uORB/topics/esc_status.h>
#include <drivers/drv_hrt.h>
#include <drivers/uavcan/node_info.hpp>
#include <parameters/param.h>
#include "../node_info.hpp"
class UavcanEscController
{
+2 -3
View File
@@ -66,10 +66,9 @@ void UavcanArmingStatus::periodic_update(const uavcan::TimerEvent &)
if (_actuator_armed_sub.update(&actuator_armed)) {
uavcan::equipment::safety::ArmingStatus cmd;
if (actuator_armed.lockdown || actuator_armed.kill) {
cmd.status = cmd.STATUS_DISARMED;
bool lockdown_active = actuator_armed.lockdown || actuator_armed.termination || actuator_armed.kill;
} else if (actuator_armed.armed) {
if (!lockdown_active && (actuator_armed.armed || _is_actuator_test_running)) {
cmd.status = cmd.STATUS_FULLY_ARMED;
} else {
+3
View File
@@ -57,6 +57,8 @@ public:
*/
int init();
void setActuatorTestRunning(bool running) {_is_actuator_test_running = running;}
private:
/*
* Max update rate to avoid exessive bus traffic
@@ -80,4 +82,5 @@ private:
uORB::Subscription _actuator_armed_sub{ORB_ID(actuator_armed)};
bool _is_actuator_test_running = false;
};
+7 -8
View File
@@ -43,7 +43,9 @@ const char *const UavcanAccelBridge::NAME = "accel";
UavcanAccelBridge::UavcanAccelBridge(uavcan::INode &node, NodeInfoPublisher *node_info_publisher) :
UavcanSensorBridgeBase("uavcan_accel", ORB_ID(sensor_accel), node_info_publisher),
_sub_imu_data(node)
{ }
{
set_device_type(DRV_ACC_DEVTYPE_UAVCAN);
}
int UavcanAccelBridge::init()
{
@@ -59,7 +61,7 @@ int UavcanAccelBridge::init()
void UavcanAccelBridge::imu_sub_cb(const uavcan::ReceivedDataStructure<uavcan::equipment::ahrs::RawIMU> &msg)
{
uavcan_bridge::Channel *channel = get_channel_for_node(msg.getSrcNodeID().get());
uavcan_bridge::Channel *channel = get_channel_for_node(msg.getSrcNodeID().get(), msg.getIfaceIndex());
const hrt_abstime timestamp_sample = hrt_absolute_time();
@@ -87,13 +89,10 @@ void UavcanAccelBridge::imu_sub_cb(const uavcan::ReceivedDataStructure<uavcan::e
int UavcanAccelBridge::init_driver(uavcan_bridge::Channel *channel)
{
// update device id as we now know our device node_id
DeviceId device_id{_device_id};
// Build device ID using node_id and interface index
uint32_t device_id = make_uavcan_device_id(static_cast<uint8_t>(channel->node_id), channel->iface_index);
device_id.devid_s.devtype = DRV_ACC_DEVTYPE_UAVCAN;
device_id.devid_s.address = static_cast<uint8_t>(channel->node_id);
channel->h_driver = new PX4Accelerometer(device_id.devid);
channel->h_driver = new PX4Accelerometer(device_id);
if (channel->h_driver == nullptr) {
return PX4_ERROR;
+7 -10
View File
@@ -49,7 +49,9 @@ UavcanBarometerBridge::UavcanBarometerBridge(uavcan::INode &node, NodeInfoPublis
UavcanSensorBridgeBase("uavcan_baro", ORB_ID(sensor_baro), node_info_publisher),
_sub_air_pressure_data(node),
_sub_air_temperature_data(node)
{ }
{
set_device_type(DRV_BARO_DEVTYPE_UAVCAN);
}
int UavcanBarometerBridge::init()
{
@@ -91,7 +93,7 @@ void UavcanBarometerBridge::air_pressure_sub_cb(const
{
const hrt_abstime timestamp_sample = hrt_absolute_time();
uavcan_bridge::Channel *channel = get_channel_for_node(msg.getSrcNodeID().get());
uavcan_bridge::Channel *channel = get_channel_for_node(msg.getSrcNodeID().get(), msg.getIfaceIndex());
if (channel == nullptr) {
// Something went wrong - no channel to publish on; return
@@ -105,23 +107,18 @@ void UavcanBarometerBridge::air_pressure_sub_cb(const
return;
}
DeviceId device_id{};
device_id.devid_s.bus = 0;
device_id.devid_s.bus_type = DeviceBusType_UAVCAN;
device_id.devid_s.devtype = DRV_BARO_DEVTYPE_UAVCAN;
device_id.devid_s.address = static_cast<uint8_t>(channel->node_id);
uint32_t device_id = make_uavcan_device_id(msg);
// Register barometer capability with NodeInfoPublisher after first successful message
if (_node_info_publisher != nullptr) {
_node_info_publisher->registerDeviceCapability(msg.getSrcNodeID().get(), device_id.devid,
_node_info_publisher->registerDeviceCapability(msg.getSrcNodeID().get(), device_id,
NodeInfoPublisher::DeviceCapability::BAROMETER);
}
// publish
sensor_baro_s sensor_baro{};
sensor_baro.timestamp_sample = timestamp_sample;
sensor_baro.device_id = device_id.devid;
sensor_baro.device_id = device_id;
sensor_baro.pressure = msg.static_pressure;
if (PX4_ISFINITE(_last_temperature_kelvin) && (_last_temperature_kelvin >= 0.f)) {
@@ -49,6 +49,7 @@ UavcanDifferentialPressureBridge::UavcanDifferentialPressureBridge(uavcan::INode
UavcanSensorBridgeBase("uavcan_differential_pressure", ORB_ID(differential_pressure), node_info_publisher),
_sub_air(node)
{
set_device_type(DRV_DIFF_PRESS_DEVTYPE_UAVCAN);
}
int UavcanDifferentialPressureBridge::init()
@@ -68,8 +69,6 @@ void UavcanDifferentialPressureBridge::air_sub_cb(const
{
const hrt_abstime timestamp_sample = hrt_absolute_time();
_device_id.devid_s.devtype = DRV_DIFF_PRESS_DEVTYPE_UAVCAN;
_device_id.devid_s.address = msg.getSrcNodeID().get() & 0xFF;
float diff_press_pa = msg.differential_pressure;
int32_t differential_press_rev = 0;
param_get(param_find("SENS_DPRES_REV"), &differential_press_rev);
@@ -83,7 +82,7 @@ void UavcanDifferentialPressureBridge::air_sub_cb(const
differential_pressure_s report{};
report.timestamp_sample = timestamp_sample;
report.device_id = _device_id.devid;
report.device_id = make_uavcan_device_id(msg);
report.differential_pressure_pa = diff_press_pa;
report.temperature = temperature_c;
report.timestamp = hrt_absolute_time();
+2 -7
View File
@@ -41,6 +41,7 @@ UavcanFlowBridge::UavcanFlowBridge(uavcan::INode &node, NodeInfoPublisher *node_
UavcanSensorBridgeBase("uavcan_flow", ORB_ID(sensor_optical_flow), node_info_publisher),
_sub_flow(node)
{
set_device_type(DRV_FLOW_DEVTYPE_UAVCAN);
}
int
@@ -61,13 +62,7 @@ void UavcanFlowBridge::flow_sub_cb(const uavcan::ReceivedDataStructure<com::hex:
sensor_optical_flow_s flow{};
flow.timestamp_sample = hrt_absolute_time(); // TODO
device::Device::DeviceId device_id;
device_id.devid_s.bus_type = device::Device::DeviceBusType::DeviceBusType_UAVCAN;
device_id.devid_s.bus = 0;
device_id.devid_s.devtype = DRV_FLOW_DEVTYPE_UAVCAN;
device_id.devid_s.address = msg.getSrcNodeID().get() & 0xFF;
flow.device_id = device_id.devid;
flow.device_id = make_uavcan_device_id(msg);
flow.pixel_flow[0] = msg.flow_integral[0];
flow.pixel_flow[1] = msg.flow_integral[1];
+2 -1
View File
@@ -404,7 +404,8 @@ void UavcanGnssBridge::process_fixx(const uavcan::ReceivedDataStructure<FixType>
const uint8_t spoofing_state)
{
sensor_gps_s sensor_gps{};
sensor_gps.device_id = get_device_id();
sensor_gps.device_id = make_uavcan_device_id(msg);
// Register GPS capability with NodeInfoPublisher after first successful message
if (_node_info_publisher != nullptr) {
+2 -1
View File
@@ -42,6 +42,7 @@ UavcanGnssRelativeBridge::UavcanGnssRelativeBridge(uavcan::INode &node, NodeInfo
UavcanSensorBridgeBase("uavcan_gnss_relative", ORB_ID(sensor_gnss_relative), node_info_publisher),
_sub_rel_pos_heading(node)
{
set_device_type(DRV_GPS_DEVTYPE_UAVCAN);
}
int
@@ -70,7 +71,7 @@ void UavcanGnssRelativeBridge::rel_pos_heading_sub_cb(const
sensor_gnss_relative.position_length = msg.relative_distance_m;
sensor_gnss_relative.position[2] = msg.relative_down_pos_m;
sensor_gnss_relative.device_id = get_device_id();
sensor_gnss_relative.device_id = make_uavcan_device_id(msg);
// Register GPS capability with NodeInfoPublisher after first successful message
if (_node_info_publisher != nullptr) {
+7 -8
View File
@@ -43,7 +43,9 @@ const char *const UavcanGyroBridge::NAME = "gyro";
UavcanGyroBridge::UavcanGyroBridge(uavcan::INode &node, NodeInfoPublisher *node_info_publisher) :
UavcanSensorBridgeBase("uavcan_gyro", ORB_ID(sensor_gyro), node_info_publisher),
_sub_imu_data(node)
{ }
{
set_device_type(DRV_GYR_DEVTYPE_UAVCAN);
}
int UavcanGyroBridge::init()
{
@@ -59,7 +61,7 @@ int UavcanGyroBridge::init()
void UavcanGyroBridge::imu_sub_cb(const uavcan::ReceivedDataStructure<uavcan::equipment::ahrs::RawIMU> &msg)
{
uavcan_bridge::Channel *channel = get_channel_for_node(msg.getSrcNodeID().get());
uavcan_bridge::Channel *channel = get_channel_for_node(msg.getSrcNodeID().get(), msg.getIfaceIndex());
if (channel == nullptr) {
// Something went wrong - no channel to publish on; return
@@ -87,13 +89,10 @@ void UavcanGyroBridge::imu_sub_cb(const uavcan::ReceivedDataStructure<uavcan::eq
int UavcanGyroBridge::init_driver(uavcan_bridge::Channel *channel)
{
// update device id as we now know our device node_id
DeviceId device_id{_device_id};
// Build device ID using node_id and interface index
uint32_t device_id = make_uavcan_device_id(static_cast<uint8_t>(channel->node_id), channel->iface_index);
device_id.devid_s.devtype = DRV_GYR_DEVTYPE_UAVCAN;
device_id.devid_s.address = static_cast<uint8_t>(channel->node_id);
channel->h_driver = new PX4Gyroscope(device_id.devid);
channel->h_driver = new PX4Gyroscope(device_id);
if (channel->h_driver == nullptr) {
return PX4_ERROR;
+2 -1
View File
@@ -42,6 +42,7 @@ UavcanHygrometerBridge::UavcanHygrometerBridge(uavcan::INode &node, NodeInfoPubl
UavcanSensorBridgeBase("uavcan_hygrometer_sensor", ORB_ID(sensor_hygrometer), node_info_publisher),
_sub_hygro(node)
{
set_device_type(DRV_HYGRO_DEVTYPE_UAVCAN);
}
int UavcanHygrometerBridge::init()
@@ -64,7 +65,7 @@ void UavcanHygrometerBridge::hygro_sub_cb(const uavcan::ReceivedDataStructure<dr
sensor_hygrometer_s report{};
report.timestamp_sample = timestamp_sample;
report.device_id = 0; // TODO
report.device_id = make_uavcan_device_id(msg);
report.temperature = msg.temperature + atmosphere::kAbsoluteNullCelsius;
report.humidity = msg.humidity;
report.timestamp = hrt_absolute_time();
+6 -8
View File
@@ -49,6 +49,7 @@ UavcanMagnetometerBridge::UavcanMagnetometerBridge(uavcan::INode &node, NodeInfo
_sub_mag(node),
_sub_mag2(node)
{
set_device_type(DRV_MAG_DEVTYPE_UAVCAN);
}
int UavcanMagnetometerBridge::init()
@@ -73,7 +74,7 @@ int UavcanMagnetometerBridge::init()
void UavcanMagnetometerBridge::mag_sub_cb(const
uavcan::ReceivedDataStructure<uavcan::equipment::ahrs::MagneticFieldStrength> &msg)
{
uavcan_bridge::Channel *channel = get_channel_for_node(msg.getSrcNodeID().get());
uavcan_bridge::Channel *channel = get_channel_for_node(msg.getSrcNodeID().get(), msg.getIfaceIndex());
if (channel == nullptr) {
// Something went wrong - no channel to publish on; return
@@ -104,7 +105,7 @@ void
UavcanMagnetometerBridge::mag2_sub_cb(const
uavcan::ReceivedDataStructure<uavcan::equipment::ahrs::MagneticFieldStrength2> &msg)
{
uavcan_bridge::Channel *channel = get_channel_for_node(msg.getSrcNodeID().get());
uavcan_bridge::Channel *channel = get_channel_for_node(msg.getSrcNodeID().get(), msg.getIfaceIndex());
if (channel == nullptr || channel->instance < 0) {
// Something went wrong - no channel to publish on; return
@@ -134,13 +135,10 @@ UavcanMagnetometerBridge::mag2_sub_cb(const
int UavcanMagnetometerBridge::init_driver(uavcan_bridge::Channel *channel)
{
// update device id as we now know our device node_id
DeviceId device_id{_device_id};
// Build device ID using node_id and interface index
uint32_t device_id = make_uavcan_device_id(static_cast<uint8_t>(channel->node_id), channel->iface_index);
device_id.devid_s.devtype = DRV_MAG_DEVTYPE_UAVCAN;
device_id.devid_s.address = static_cast<uint8_t>(channel->node_id);
channel->h_driver = new PX4Magnetometer(device_id.devid, ROTATION_NONE);
channel->h_driver = new PX4Magnetometer(device_id, ROTATION_NONE);
if (channel->h_driver == nullptr) {
return PX4_ERROR;
+7 -8
View File
@@ -45,7 +45,9 @@ const char *const UavcanRangefinderBridge::NAME = "rangefinder";
UavcanRangefinderBridge::UavcanRangefinderBridge(uavcan::INode &node, NodeInfoPublisher *node_info_publisher) :
UavcanSensorBridgeBase("uavcan_rangefinder", ORB_ID(distance_sensor), node_info_publisher),
_sub_range_data(node)
{ }
{
set_device_type(DRV_DIST_DEVTYPE_UAVCAN);
}
int UavcanRangefinderBridge::init()
{
@@ -66,7 +68,7 @@ int UavcanRangefinderBridge::init()
void UavcanRangefinderBridge::range_sub_cb(const
uavcan::ReceivedDataStructure<uavcan::equipment::range_sensor::Measurement> &msg)
{
uavcan_bridge::Channel *channel = get_channel_for_node(msg.getSrcNodeID().get());
uavcan_bridge::Channel *channel = get_channel_for_node(msg.getSrcNodeID().get(), msg.getIfaceIndex());
if (channel == nullptr || channel->instance < 0) {
// Something went wrong - no channel to publish on; return
@@ -125,13 +127,10 @@ void UavcanRangefinderBridge::range_sub_cb(const
int UavcanRangefinderBridge::init_driver(uavcan_bridge::Channel *channel)
{
// update device id as we now know our device node_id
DeviceId device_id{_device_id};
// Build device ID using node_id and interface index
uint32_t device_id = make_uavcan_device_id(static_cast<uint8_t>(channel->node_id), channel->iface_index);
device_id.devid_s.devtype = DRV_DIST_DEVTYPE_UAVCAN;
device_id.devid_s.address = static_cast<uint8_t>(channel->node_id);
channel->h_driver = new PX4Rangefinder(device_id.devid, distance_sensor_s::ROTATION_DOWNWARD_FACING);
channel->h_driver = new PX4Rangefinder(device_id, distance_sensor_s::ROTATION_DOWNWARD_FACING);
if (channel->h_driver == nullptr) {
return PX4_ERROR;
+2 -1
View File
@@ -316,7 +316,7 @@ UavcanSensorBridgeBase::publish(const int node_id, const void *report)
(void)orb_publish(_orb_topic, channel->orb_advert, report);
}
uavcan_bridge::Channel *UavcanSensorBridgeBase::get_channel_for_node(int node_id)
uavcan_bridge::Channel *UavcanSensorBridgeBase::get_channel_for_node(int node_id, uint8_t iface_index)
{
uavcan_bridge::Channel *channel = nullptr;
@@ -354,6 +354,7 @@ uavcan_bridge::Channel *UavcanSensorBridgeBase::get_channel_for_node(int node_id
// initialize the driver, which registers the class device name and uORB publisher
channel->node_id = node_id;
channel->iface_index = iface_index;
int ret = init_driver(channel);
if (ret != PX4_OK) {
+29 -1
View File
@@ -92,6 +92,7 @@ struct Channel {
orb_advert_t orb_advert{nullptr};
int instance{-1};
void *h_driver{nullptr};
uint8_t iface_index{0};
};
} // namespace uavcan_bridge
@@ -138,7 +139,34 @@ protected:
*/
virtual int init_driver(uavcan_bridge::Channel *channel) { return PX4_OK; };
uavcan_bridge::Channel *get_channel_for_node(int node_id);
uavcan_bridge::Channel *get_channel_for_node(int node_id, uint8_t iface_index);
/**
* Builds a unique device ID from a UAVCAN message
* @param msg UAVCAN message (must have getSrcNodeID() and getIfaceIndex() methods)
* @return Complete device ID with node address and interface encoded
*/
template<typename T>
uint32_t make_uavcan_device_id(const uavcan::ReceivedDataStructure<T> &msg) const
{
return make_uavcan_device_id(msg.getSrcNodeID().get(), msg.getIfaceIndex());
}
/**
* Builds a unique device ID from node ID and interface index
* @param node_id UAVCAN node ID
* @param iface_index CAN interface index (0 = CAN1, 1 = CAN2, etc.)
* @return Complete device ID with node address and interface encoded
*/
uint32_t make_uavcan_device_id(uint8_t node_id, uint8_t iface_index) const
{
device::Device::DeviceId device_id{};
device_id.devid_s.devtype = get_device_type();
device_id.devid_s.address = node_id;
device_id.devid_s.bus_type = device::Device::DeviceBusType_UAVCAN;
device_id.devid_s.bus = iface_index;
return device_id.devid;
}
public:
virtual ~UavcanSensorBridgeBase();
+4
View File
@@ -969,6 +969,10 @@ UavcanNode::Run()
}
}
#if defined(CONFIG_UAVCAN_OUTPUTS_CONTROLLER)
_arming_status_controller.setActuatorTestRunning(_mixing_interface_esc.isActuatorTestRunning());
#endif
perf_end(_cycle_perf);
pthread_mutex_unlock(&_node_mutex);
+2
View File
@@ -136,6 +136,8 @@ public:
MixingOutput &mixingOutput() { return _mixing_output; }
bool isActuatorTestRunning() const { return _mixing_output.isActuatorTestRunning(); }
protected:
void Run() override;
private:
+1
View File
@@ -68,6 +68,7 @@ add_subdirectory(pure_pursuit EXCLUDE_FROM_ALL)
add_subdirectory(rate_control EXCLUDE_FROM_ALL)
add_subdirectory(rc EXCLUDE_FROM_ALL)
add_subdirectory(ringbuffer EXCLUDE_FROM_ALL)
add_subdirectory(rl_tools EXCLUDE_FROM_ALL)
add_subdirectory(rover_control EXCLUDE_FROM_ALL)
add_subdirectory(rtl EXCLUDE_FROM_ALL)
add_subdirectory(sensor_calibration EXCLUDE_FROM_ALL)
+5 -2
View File
@@ -1,7 +1,9 @@
from __future__ import print_function
#!/usr/bin/env python3
from pylab import *
from pprint import pprint
import scipy.linalg
import sys
# test cases, derived from doc/nasa_rotation_def.pdf
@@ -47,7 +49,7 @@ def quat_prod(q, r):
def dcm_to_euler(dcm):
return array([
arctan(dcm[2,1]/ dcm[2,2]),
arctan(-dcm[2,0]/ std::sqrt(1 - dcm[2,0]**2)),
arctan(-dcm[2,0]/ (1 - dcm[2,0]**2)**0.5),
arctan(dcm[1,0]/ dcm[0,0]),
])
@@ -75,6 +77,7 @@ psi = 0.3
print('euler', phi, theta, psi)
q = euler_to_quat(phi, theta, psi)
FLT_EPSILON = sys.float_info.epsilon
assert(abs(norm(q) - 1) < FLT_EPSILON)
assert(abs(norm(q) - 1) < FLT_EPSILON)
assert(norm(array(quat_to_euler(q)) - array([phi, theta, psi])) < FLT_EPSILON)
+4 -2
View File
@@ -545,8 +545,10 @@ uint16_t MixingOutput::output_limit_calc_single(int i, float value) const
float output = _disarmed_value[i];
if (_function_assignment[i] >= OutputFunction::Servo1
&& _function_assignment[i] <= OutputFunction::ServoMax
if (((_function_assignment[i] >= OutputFunction::Servo1
&& _function_assignment[i] <= OutputFunction::ServoMax) || _function_assignment[i] == OutputFunction::Landing_Gear_Wheel
|| (_function_assignment[i] >= OutputFunction::Gimbal_Roll
&& _function_assignment[i] <= OutputFunction::Gimbal_Yaw))
&& _param_handles[i].center != PARAM_INVALID
&& _center_value[i] >= 800
&& _center_value[i] <= 2200) {
+1
View File
@@ -163,6 +163,7 @@ public:
void setMaxTopicUpdateRate(unsigned max_topic_update_interval_us);
const actuator_armed_s &armed() const { return _armed; }
bool isActuatorTestRunning() const { return _actuator_test.inTestMode(); }
void setAllFailsafeValues(uint16_t value);
void setAllDisarmedValues(uint16_t value);
+1 -1
View File
@@ -438,7 +438,7 @@ param_set_internal(param_t param, const void *val, bool mark_saved, bool notify_
}
if (user_config.store(param, new_value)) {
params_unsaved.set(param, !mark_saved);
params_unsaved.set(param, !mark_saved && param_changed);
result = PX4_OK;
} else {
+15
View File
@@ -0,0 +1,15 @@
if(CONFIG_LIB_RL_TOOLS)
px4_add_git_submodule(TARGET git_rl_tools PATH "rl_tools")
add_library(rl_tools INTERFACE)
target_include_directories(rl_tools INTERFACE
${CMAKE_CURRENT_SOURCE_DIR}/rl_tools/include
)
target_compile_features(rl_tools INTERFACE cxx_std_17)
target_compile_options(rl_tools INTERFACE
-Wno-unused-parameter
-Wno-unused-variable
-Wno-unused-local-typedefs
)
endif()
+7
View File
@@ -0,0 +1,7 @@
config LIB_RL_TOOLS
bool "RLtools"
default n
---help---
RLtools is a header-only library for reinforcement learning and neural networks.
It enables running trained RL policies on embedded devices.
This library is used for running RL-based controllers on the PX4 autopilot.
+9 -5
View File
@@ -607,13 +607,14 @@ PARAM_DEFINE_INT32(NAV_RCL_ACT, 2);
/**
* Manual control loss exceptions
*
* Specify modes where manual control loss is ignored and no failsafe is triggered.
* Specify modes in which stick input is ignored and no failsafe action is triggered.
* External modes requiring stick input will still failsafe.
* Auto modes are: Hold, Takeoff, Land, RTL, Descend, Follow Target, Precland, Orbit.
*
* @min 0
* @max 31
* @bit 0 Mission
* @bit 1 Hold
* @bit 1 Auto modes
* @bit 2 Offboard
* @bit 3 External Mode
* @bit 4 Altitude Cruise
@@ -624,13 +625,16 @@ PARAM_DEFINE_INT32(COM_RCL_EXCEPT, 0);
/**
* Datalink loss exceptions
*
* Specify modes in which datalink loss is ignored and the failsafe action not triggered.
* Specify modes in which ground control station connection loss is ignored and no failsafe action is triggered.
* See also COM_RCL_EXCEPT.
*
* @min 0
* @max 7
* @max 31
* @bit 0 Mission
* @bit 1 Hold
* @bit 1 Auto modes
* @bit 2 Offboard
* @bit 3 External Mode
* @bit 4 Altitude Cruise
* @group Commander
*/
PARAM_DEFINE_INT32(COM_DLL_EXCEPT, 0);
@@ -182,21 +182,23 @@
<tr>
<td><label for="intended_nav_state">Intended Mode:&nbsp;</label></td>
<td><select id="intended_nav_state">
<option value="0">MANUAL</option>
<option value="10">ACRO</option>
<option value="15">STAB</option>
<option value="1">ALTCTL</option>
<option value="2" selected>POSCTL</option>
<option value="3">AUTO_MISSION</option>
<option value="4">AUTO_LOITER</option>
<option value="5">AUTO_RTL</option>
<option value="17">AUTO_TAKEOFF</option>
<option value="18">AUTO_LAND</option>
<option value="19">AUTO_FOLLOW_TARGET</option>
<option value="20">AUTO_PRECLAND</option>
<option value="22">AUTO_VTOL_TAKEOFF</option>
<option value="14">OFFBOARD</option>
<option value="21">ORBIT</option>
<option value="0">Manual</option>
<option value="10">Acro</option>
<option value="15">Stabilized</option>
<option value="1">Altitude</option>
<option value="8">Altitude Cruise</option>
<option value="2" selected>Position</option>
<option value="3">Mission</option>
<option value="4">Hold</option>
<option value="5">Return</option>
<option value="17">Takeoff</option>
<option value="18">Land</option>
<option value="19">Follow</option>
<option value="20">Precision Land</option>
<option value="22">VTOL Takeoff</option>
<option value="14">Offboard</option>
<option value="21">Orbit</option>
<option value="23">External 1</option>
</select>
</td>
<td></td>
+48 -48
View File
@@ -442,18 +442,53 @@ FailsafeBase::ActionOptions Failsafe::fromRemainingFlightTimeLowActParam(int par
return options;
}
bool Failsafe::isFailsafeIgnored(uint8_t user_intended_mode, int32_t exception_mask_parameter)
{
switch (user_intended_mode) {
case vehicle_status_s::NAVIGATION_STATE_AUTO_MISSION:
return exception_mask_parameter & (int)LinkLossExceptionBits::Mission;
case vehicle_status_s::NAVIGATION_STATE_AUTO_LOITER:
case vehicle_status_s::NAVIGATION_STATE_AUTO_TAKEOFF:
case vehicle_status_s::NAVIGATION_STATE_AUTO_VTOL_TAKEOFF:
case vehicle_status_s::NAVIGATION_STATE_AUTO_LAND:
case vehicle_status_s::NAVIGATION_STATE_AUTO_RTL:
case vehicle_status_s::NAVIGATION_STATE_DESCEND:
case vehicle_status_s::NAVIGATION_STATE_AUTO_FOLLOW_TARGET:
case vehicle_status_s::NAVIGATION_STATE_AUTO_PRECLAND:
case vehicle_status_s::NAVIGATION_STATE_ORBIT:
return exception_mask_parameter & (int)LinkLossExceptionBits::AutoModes;
case vehicle_status_s::NAVIGATION_STATE_OFFBOARD:
return exception_mask_parameter & (int)LinkLossExceptionBits::Offboard;
case vehicle_status_s::NAVIGATION_STATE_EXTERNAL1:
case vehicle_status_s::NAVIGATION_STATE_EXTERNAL2:
case vehicle_status_s::NAVIGATION_STATE_EXTERNAL3:
case vehicle_status_s::NAVIGATION_STATE_EXTERNAL4:
case vehicle_status_s::NAVIGATION_STATE_EXTERNAL5:
case vehicle_status_s::NAVIGATION_STATE_EXTERNAL6:
case vehicle_status_s::NAVIGATION_STATE_EXTERNAL7:
case vehicle_status_s::NAVIGATION_STATE_EXTERNAL8:
return exception_mask_parameter & (int)LinkLossExceptionBits::ExternalMode;
case vehicle_status_s::NAVIGATION_STATE_ALTITUDE_CRUISE:
return exception_mask_parameter & (int)LinkLossExceptionBits::AltitudeCruise;
default:
return false;
}
}
void Failsafe::checkStateAndMode(const hrt_abstime &time_us, const State &state,
const failsafe_flags_s &status_flags)
{
updateArmingState(time_us, state.armed, status_flags);
const bool in_forward_flight = state.vehicle_type == vehicle_status_s::VEHICLE_TYPE_FIXED_WING
|| state.vtol_in_transition_mode;
// Do not enter failsafe while doing a vtol takeoff after the vehicle has started a transition and before it reaches the loiter
// altitude. The vtol takeoff navigaton mode will set mission_finished to true as soon as the loiter is established
const bool ignore_any_link_loss_vtol_takeoff_fixedwing = state.user_intended_mode ==
vehicle_status_s::NAVIGATION_STATE_AUTO_VTOL_TAKEOFF
const bool in_forward_flight = (state.vehicle_type == vehicle_status_s::VEHICLE_TYPE_FIXED_WING) || state.vtol_in_transition_mode;
const bool ignore_any_link_loss_vtol_takeoff_fixedwing = (state.user_intended_mode == vehicle_status_s::NAVIGATION_STATE_AUTO_VTOL_TAKEOFF)
&& in_forward_flight && !state.mission_finished;
// Manual control (RC or joystick) loss
@@ -462,59 +497,23 @@ void Failsafe::checkStateAndMode(const hrt_abstime &time_us, const State &state,
_manual_control_lost_at_arming = false;
}
const bool rc_loss_ignored_mission = state.user_intended_mode == vehicle_status_s::NAVIGATION_STATE_AUTO_MISSION
&& (_param_com_rcl_except.get() & (int)ManualControlLossExceptionBits::Mission);
const bool rc_loss_ignored_loiter = state.user_intended_mode == vehicle_status_s::NAVIGATION_STATE_AUTO_LOITER
&& (_param_com_rcl_except.get() & (int)ManualControlLossExceptionBits::Hold);
const bool rc_loss_ignored_offboard = state.user_intended_mode == vehicle_status_s::NAVIGATION_STATE_OFFBOARD
&& (_param_com_rcl_except.get() & (int)ManualControlLossExceptionBits::Offboard);
const bool rc_loss_ignored_takeoff = (state.user_intended_mode == vehicle_status_s::NAVIGATION_STATE_AUTO_TAKEOFF ||
state.user_intended_mode == vehicle_status_s::NAVIGATION_STATE_AUTO_VTOL_TAKEOFF)
&& (_param_com_rcl_except.get() & (int)ManualControlLossExceptionBits::Hold);
const bool rc_loss_ignored_altitude_cruise = (state.user_intended_mode ==
vehicle_status_s::NAVIGATION_STATE_ALTITUDE_CRUISE
&& (_param_com_rcl_except.get() & (int)ManualControlLossExceptionBits::AltitudeCruise));
const bool rc_loss_ignored_external_mode =
(state.user_intended_mode == vehicle_status_s::NAVIGATION_STATE_EXTERNAL1 ||
state.user_intended_mode == vehicle_status_s::NAVIGATION_STATE_EXTERNAL2 ||
state.user_intended_mode == vehicle_status_s::NAVIGATION_STATE_EXTERNAL3 ||
state.user_intended_mode == vehicle_status_s::NAVIGATION_STATE_EXTERNAL4 ||
state.user_intended_mode == vehicle_status_s::NAVIGATION_STATE_EXTERNAL5 ||
state.user_intended_mode == vehicle_status_s::NAVIGATION_STATE_EXTERNAL6 ||
state.user_intended_mode == vehicle_status_s::NAVIGATION_STATE_EXTERNAL7 ||
state.user_intended_mode == vehicle_status_s::NAVIGATION_STATE_EXTERNAL8)
&& (_param_com_rcl_except.get() & (int)ManualControlLossExceptionBits::ExternalMode);
const bool rc_loss_ignored = rc_loss_ignored_mission || rc_loss_ignored_loiter || rc_loss_ignored_offboard ||
rc_loss_ignored_takeoff || rc_loss_ignored_external_mode || ignore_any_link_loss_vtol_takeoff_fixedwing
|| _manual_control_lost_at_arming || rc_loss_ignored_altitude_cruise;
const bool rc_loss_ignored = isFailsafeIgnored(state.user_intended_mode, _param_com_rcl_except.get())
|| ignore_any_link_loss_vtol_takeoff_fixedwing || _manual_control_lost_at_arming;
if (_param_com_rc_in_mode.get() != int32_t(RcInMode::DisableManualControl) && !rc_loss_ignored) {
CHECK_FAILSAFE(status_flags, manual_control_signal_lost,
fromNavDllOrRclActParam(_param_nav_rcl_act.get()).causedBy(Cause::ManualControlLoss));
}
// GCS connection loss
// Ground control station connection loss
const bool dll_loss_ignored_land = state.user_intended_mode == vehicle_status_s::NAVIGATION_STATE_AUTO_LAND
|| state.user_intended_mode == vehicle_status_s::NAVIGATION_STATE_AUTO_PRECLAND;
const bool dll_loss_ignored_mission = state.user_intended_mode == vehicle_status_s::NAVIGATION_STATE_AUTO_MISSION
&& (_param_com_dll_except.get() & (int)DatalinkLossExceptionBits::Mission);
const bool dll_loss_ignored_loiter = state.user_intended_mode == vehicle_status_s::NAVIGATION_STATE_AUTO_LOITER
&& (_param_com_dll_except.get() & (int)DatalinkLossExceptionBits::Hold);
const bool dll_loss_ignored_offboard = state.user_intended_mode == vehicle_status_s::NAVIGATION_STATE_OFFBOARD
&& (_param_com_dll_except.get() & (int)DatalinkLossExceptionBits::Offboard);
const bool dll_loss_ignored_takeoff = (state.user_intended_mode == vehicle_status_s::NAVIGATION_STATE_AUTO_TAKEOFF ||
state.user_intended_mode == vehicle_status_s::NAVIGATION_STATE_AUTO_VTOL_TAKEOFF)
&& (_param_com_dll_except.get() & (int)DatalinkLossExceptionBits::Hold);
const bool dll_loss_ignored = dll_loss_ignored_mission || dll_loss_ignored_loiter || dll_loss_ignored_offboard ||
dll_loss_ignored_takeoff || ignore_any_link_loss_vtol_takeoff_fixedwing || dll_loss_ignored_land;
const bool dll_loss_ignored = isFailsafeIgnored(state.user_intended_mode, _param_com_dll_except.get())
|| ignore_any_link_loss_vtol_takeoff_fixedwing || dll_loss_ignored_land;
if (_param_nav_dll_act.get() != int32_t(gcs_connection_loss_failsafe_mode::Disabled) && !dll_loss_ignored) {
CHECK_FAILSAFE(status_flags, gcs_connection_lost,
fromNavDllOrRclActParam(_param_nav_dll_act.get()).causedBy(Cause::GCSConnectionLoss));
CHECK_FAILSAFE(status_flags, gcs_connection_lost, fromNavDllOrRclActParam(_param_nav_dll_act.get()).causedBy(Cause::GCSConnectionLoss));
}
// VTOL transition failure (quadchute)
@@ -531,7 +530,8 @@ void Failsafe::checkStateAndMode(const hrt_abstime &time_us, const State &state,
// If manual control loss and GCS connection loss are disabled and we lose both command links and the mission finished,
// trigger RTL to avoid losing the vehicle
if ((_param_com_rc_in_mode.get() == int32_t(RcInMode::DisableManualControl) || rc_loss_ignored_mission)
if ((_param_com_rc_in_mode.get() == int32_t(RcInMode::DisableManualControl)
|| isFailsafeIgnored(state.user_intended_mode, _param_com_rcl_except.get()))
&& _param_nav_dll_act.get() == int32_t(gcs_connection_loss_failsafe_mode::Disabled)
&& state.mission_finished) {
_last_state_mission_control_lost = checkFailsafe(_caller_id_mission_control_lost, _last_state_mission_control_lost,
+4 -8
View File
@@ -53,20 +53,14 @@ protected:
private:
void updateArmingState(const hrt_abstime &time_us, bool armed, const failsafe_flags_s &status_flags);
enum class ManualControlLossExceptionBits : int32_t {
enum class LinkLossExceptionBits : int32_t {
Mission = (1 << 0),
Hold = (1 << 1),
AutoModes = (1 << 1),
Offboard = (1 << 2),
ExternalMode = (1 << 3),
AltitudeCruise = (1 << 4)
};
enum class DatalinkLossExceptionBits : int32_t {
Mission = (1 << 0),
Hold = (1 << 1),
Offboard = (1 << 2)
};
// COM_LOW_BAT_ACT parameter values
enum class LowBatteryAction : int32_t {
Warning = 0, // Warning
@@ -175,6 +169,8 @@ private:
static ActionOptions fromPosLowActParam(int param_value);
static ActionOptions fromRemainingFlightTimeLowActParam(int param_value);
static bool isFailsafeIgnored(uint8_t user_intended_mode, int32_t exception_mask_parameter);
const int _caller_id_mode_fallback{genCallerId()};
bool _last_state_mode_fallback{false};
const int _caller_id_mission_control_lost{genCallerId()};
@@ -35,6 +35,7 @@
#include "framework.h"
#include <uORB/topics/vehicle_status.h>
#include "../ModeUtil/mode_requirements.hpp"
// to run: make tests TESTFILTER=failsafe_test
@@ -50,16 +51,16 @@ protected:
void checkStateAndMode(const hrt_abstime &time_us, const State &state,
const failsafe_flags_s &status_flags) override
{
CHECK_FAILSAFE(status_flags, manual_control_signal_lost,
ActionOptions(Action::RTL).clearOn(ClearCondition::OnModeChangeOrDisarm));
CHECK_FAILSAFE(status_flags, manual_control_signal_lost, ActionOptions(Action::RTL).clearOn(ClearCondition::OnModeChangeOrDisarm));
CHECK_FAILSAFE(status_flags, gcs_connection_lost, Action::Descend);
if (state.user_intended_mode == vehicle_status_s::NAVIGATION_STATE_AUTO_MISSION) {
CHECK_FAILSAFE(status_flags, mission_failure, Action::Descend);
}
CHECK_FAILSAFE(status_flags, wind_limit_exceeded,
ActionOptions(Action::RTL).allowUserTakeover(UserTakeoverAllowed::Never));
CHECK_FAILSAFE(status_flags, wind_limit_exceeded, ActionOptions(Action::RTL).allowUserTakeover(UserTakeoverAllowed::Never));
CHECK_FAILSAFE(status_flags, battery_low_remaining_time, ActionOptions(Action::RTL).causedBy(Cause::RemainingFlightTimeLow));
CHECK_FAILSAFE(status_flags, offboard_control_signal_lost, ActionOptions(Action::Hold));
_last_state_test = checkFailsafe(_caller_id_test, _last_state_test, status_flags.fd_motor_failure
&& status_flags.fd_critical_failure, ActionOptions(Action::Terminate).cannotBeDeferred());
@@ -258,6 +259,77 @@ TEST_F(FailsafeTest, takeover_denied)
ASSERT_EQ(failsafe.selectedAction(), FailsafeBase::Action::Terminate);
}
TEST_F(FailsafeTest, can_takeover_degraded_failsafe)
{
FailsafeTester failsafe(nullptr);
FailsafeBase::State state{};
state.armed = true;
state.user_intended_mode = vehicle_status_s::NAVIGATION_STATE_MANUAL;
state.vehicle_type = vehicle_status_s::VEHICLE_TYPE_ROTARY_WING;
hrt_abstime time = 3847124342;
failsafe_flags_s failsafe_flags{};
mode_util::getModeRequirements(state.vehicle_type, failsafe_flags); // Load mode requirements to degrade without valid position estimate
bool user_intended_mode_updated = false;
uint8_t updated_user_intented_mode = failsafe.update(time, state, user_intended_mode_updated, false, failsafe_flags);
// Battery time low -> Hold for the delay
time += 10_ms;
failsafe_flags.battery_low_remaining_time = true;
updated_user_intented_mode = failsafe.update(time, state, user_intended_mode_updated, false, failsafe_flags);
ASSERT_EQ(updated_user_intented_mode, state.user_intended_mode);
ASSERT_EQ(failsafe.selectedAction(), FailsafeBase::Action::Hold);
// Delay over -> RTL
time += 5_s;
failsafe_flags.battery_low_remaining_time = true;
updated_user_intented_mode = failsafe.update(time, state, user_intended_mode_updated, false, failsafe_flags);
ASSERT_EQ(updated_user_intented_mode, state.user_intended_mode);
ASSERT_EQ(failsafe.selectedAction(), FailsafeBase::Action::RTL);
// Global position gets invalid -> Land
time += 10_ms;
failsafe_flags.global_position_invalid = true;
updated_user_intented_mode = failsafe.update(time, state, user_intended_mode_updated, false, failsafe_flags);
ASSERT_EQ(updated_user_intented_mode, state.user_intended_mode);
ASSERT_EQ(failsafe.selectedAction(), FailsafeBase::Action::Land);
// User wants takeover -> Altitude mode + Warning
time += 10_ms;
user_intended_mode_updated = true;
state.user_intended_mode = vehicle_status_s::NAVIGATION_STATE_ALTCTL;
updated_user_intented_mode = failsafe.update(time, state, user_intended_mode_updated, false, failsafe_flags);
ASSERT_EQ(updated_user_intented_mode, state.user_intended_mode);
ASSERT_EQ(failsafe.selectedAction(), FailsafeBase::Action::Warn);
ASSERT_TRUE(failsafe.userTakeoverActive());
}
TEST_F(FailsafeTest, no_immediate_takeover_when_failsafe_on_mode_switch)
{
FailsafeTester failsafe(nullptr);
failsafe_flags_s failsafe_flags{};
FailsafeBase::State state{};
state.armed = true;
state.user_intended_mode = vehicle_status_s::NAVIGATION_STATE_POSCTL;
state.vehicle_type = vehicle_status_s::VEHICLE_TYPE_ROTARY_WING;
hrt_abstime time = 3847124342;
bool user_intended_mode_updated = false;
uint8_t updated_user_intented_mode = failsafe.update(time, state, user_intended_mode_updated, false, failsafe_flags);
// Switch to offboard but no offboard signal -> No immediate user takeover flagged but rather Hold
time += 10_ms;
user_intended_mode_updated = true;
state.user_intended_mode = vehicle_status_s::NAVIGATION_STATE_OFFBOARD;
failsafe_flags.offboard_control_signal_lost = true;
updated_user_intented_mode = failsafe.update(time, state, user_intended_mode_updated, false, failsafe_flags);
ASSERT_EQ(updated_user_intented_mode, state.user_intended_mode);
ASSERT_EQ(failsafe.selectedAction(), FailsafeBase::Action::Hold);
ASSERT_FALSE(failsafe.userTakeoverActive());
}
TEST_F(FailsafeTest, defer)
{
FailsafeTester failsafe(nullptr);
+3 -3
View File
@@ -499,9 +499,9 @@ void FailsafeBase::getSelectedAction(const State &state, const failsafe_flags_s
allow_user_takeover = UserTakeoverAllowed::AlwaysModeSwitchOnly;
}
// User takeover is activated on user intented mode update (w/o action change, so takeover is not immediately
// requested when entering failsafe) or rc stick movements
bool want_user_takeover_mode_switch = user_intended_mode_updated && _selected_action == selected_action;
// User takeover interrupting a failsafe is triggered by a change of the user-intended mode
// (only if a failsafe action is already active otherwise there can be immediate takeover when entering a failsafe) or by stick movement
bool want_user_takeover_mode_switch = user_intended_mode_updated && (_selected_action > Action::Warn);
bool want_user_takeover = want_user_takeover_mode_switch || rc_sticks_takeover_request;
bool takeover_allowed =
(allow_user_takeover == UserTakeoverAllowed::Always && (_user_takeover_active || want_user_takeover))
@@ -59,7 +59,7 @@ ActuatorEffectivenessControlSurfaces::ActuatorEffectivenessControlSurfaces(Modul
_param_handles[i].scale_spoiler = param_find(buffer);
}
_flaps_setpoint_with_slewrate.setSlewRate(kFlapSlewRate);
_flaps_setpoint_with_slewrate.setSlewRate(_param_ca_flap_slew.get());
_spoilers_setpoint_with_slewrate.setSlewRate(kSpoilersSlewRate);
_count_handle = param_find("CA_SV_CS_COUNT");
@@ -75,6 +75,9 @@ void ActuatorEffectivenessControlSurfaces::updateParams()
return;
}
// Update flap slewrates
_flaps_setpoint_with_slewrate.setSlewRate(_param_ca_flap_slew.get());
// Helper to check if a PWM center parameter is enabled, and clamp it to valid range
auto check_pwm_center = [](const char *prefix, int channel) -> bool {
char param_name[20];
@@ -38,7 +38,6 @@
#include <px4_platform_common/module_params.h>
#include <lib/slew_rate/SlewRate.hpp>
static constexpr float kFlapSlewRate = 0.5f; // slew rate for normalized flaps setpoint [1/s]
static constexpr float kSpoilersSlewRate = 0.5f; // slew rate for normalized spoilers setpoint [1/s]
class ActuatorEffectivenessControlSurfaces : public ModuleParams, public ActuatorEffectiveness
@@ -111,4 +110,7 @@ private:
SlewRate<float> _flaps_setpoint_with_slewrate;
SlewRate<float> _spoilers_setpoint_with_slewrate;
DEFINE_PARAMETERS(
(ParamFloat<px4::params::CA_SV_FLAP_SLEW>) _param_ca_flap_slew
)
};
@@ -336,6 +336,15 @@ parameters:
instance_start: 0
default: 0
CA_SV_FLAP_SLEW:
description:
short: Control Surface slew rate for normalized flaps setpoint
type: float
decimal: 1
min: 0.0
max: 5.0
default: 0.5
CA_SV_CS${i}_SPOIL:
description:
short: Control Surface ${i} configuration as spoiler
@@ -141,11 +141,12 @@ void FwLateralLongitudinalControl::Run()
if (_local_pos_sub.update(&_local_pos)) {
const float control_interval = math::constrain((_local_pos.timestamp - _last_time_loop_ran) * 1e-6f,
0.001f, 0.1f);
_last_time_loop_ran = _local_pos.timestamp;
const hrt_abstime now = _local_pos.timestamp_sample;
updateControllerConfiguration();
const float control_interval = math::constrain((now - _last_time_loop_ran) * 1e-6f, 0.001f, 0.1f);
_last_time_loop_ran = now;
updateControllerConfiguration(now);
_tecs.set_speed_weight(_long_configuration.speed_weight);
updateTECSAltitudeTimeConstant(checkLowHeightConditions()
@@ -165,7 +166,7 @@ void FwLateralLongitudinalControl::Run()
_landed = landed.landed;
}
_flight_phase_estimation_pub.get().flight_phase = flight_phase_estimation_s::FLIGHT_PHASE_UNKNOWN;
uint8_t current_flight_phase = flight_phase_estimation_s::FLIGHT_PHASE_UNKNOWN;
_vehicle_status_sub.update();
_control_mode_sub.update();
@@ -176,7 +177,7 @@ void FwLateralLongitudinalControl::Run()
_flaps_setpoint = flaps_setpoint.normalized_setpoint;
}
update_control_state();
update_control_state(now);
if (_control_mode_sub.get().flag_control_manual_enabled && _control_mode_sub.get().flag_control_altitude_enabled
&& _local_pos.z_reset_counter != _z_reset_counter) {
@@ -210,17 +211,18 @@ void FwLateralLongitudinalControl::Run()
// If the both altitude and height rate are set, set altitude setpoint to NAN
const float altitude_sp = PX4_ISFINITE(_long_control_sp.height_rate) ? NAN : _long_control_sp.altitude;
tecs_update_pitch_throttle(control_interval, altitude_sp,
airspeed_sp_eas,
_long_configuration.pitch_min,
_long_configuration.pitch_max,
_long_configuration.throttle_min,
_long_configuration.throttle_max,
_long_configuration.sink_rate_target,
_long_configuration.climb_rate_target,
_long_configuration.disable_underspeed_protection,
_long_control_sp.height_rate
);
current_flight_phase = tecs_update_pitch_throttle(control_interval, altitude_sp,
airspeed_sp_eas,
_long_configuration.pitch_min,
_long_configuration.pitch_max,
_long_configuration.throttle_min,
_long_configuration.throttle_max,
_long_configuration.sink_rate_target,
_long_configuration.climb_rate_target,
_long_configuration.disable_underspeed_protection,
_long_control_sp.height_rate,
now
);
pitch_sp = PX4_ISFINITE(_long_control_sp.pitch_direct) ? _long_control_sp.pitch_direct : _tecs.get_pitch_setpoint();
throttle_sp = PX4_ISFINITE(_long_control_sp.throttle_direct) ? _long_control_sp.throttle_direct :
@@ -279,13 +281,13 @@ void FwLateralLongitudinalControl::Run()
lateral_accel_sp = 0.f; // mitigation if no valid setpoint is received: 0 lateral acceleration
}
lateral_accel_sp = getCorrectedLateralAccelSetpoint(lateral_accel_sp);
lateral_accel_sp = getCorrectedLateralAccelSetpoint(lateral_accel_sp, now);
lateral_accel_sp = math::constrain(lateral_accel_sp, -_lateral_configuration.lateral_accel_max,
_lateral_configuration.lateral_accel_max);
roll_sp = mapLateralAccelerationToRollAngle(lateral_accel_sp);
fixed_wing_lateral_status_s fixed_wing_lateral_status{};
fixed_wing_lateral_status.timestamp = hrt_absolute_time();
fixed_wing_lateral_status.timestamp = now;
fixed_wing_lateral_status.lateral_acceleration_setpoint = lateral_accel_sp;
fixed_wing_lateral_status.can_run_factor = _can_run_factor;
@@ -307,7 +309,7 @@ void FwLateralLongitudinalControl::Run()
// roll slew rate
roll_body = _roll_slew_rate.update(roll_body, control_interval);
_att_sp.timestamp = hrt_absolute_time();
_att_sp.timestamp = now;
const Quatf q(Eulerf(roll_body, pitch_body, yaw_body));
q.copyTo(_att_sp.q_d);
@@ -317,22 +319,32 @@ void FwLateralLongitudinalControl::Run()
}
// Publish flight phase with low rate, but immediately if updated
const bool flight_phase_updated = current_flight_phase != _flight_phase_estimation_pub.get().flight_phase;
const hrt_abstime time_since_last_flightphase_pub = now - _flight_phase_estimation_pub.get().timestamp;
if (flight_phase_updated || time_since_last_flightphase_pub >= 1_s) {
_flight_phase_estimation_pub.get().timestamp = now;
_flight_phase_estimation_pub.get().flight_phase = current_flight_phase;
_flight_phase_estimation_pub.update();
}
_z_reset_counter = _local_pos.z_reset_counter;
}
perf_end(_loop_perf);
}
void FwLateralLongitudinalControl::updateControllerConfiguration()
void FwLateralLongitudinalControl::updateControllerConfiguration(hrt_abstime timestamp)
{
if (_lateral_configuration.timestamp == 0) {
_lateral_configuration.timestamp = _local_pos.timestamp;
_lateral_configuration.timestamp = timestamp;
_lateral_configuration.lateral_accel_max = tanf(radians(_param_fw_r_lim.get())) * CONSTANTS_ONE_G;
}
if (_long_configuration.timestamp == 0) {
setDefaultLongitudinalControlConfiguration();
setDefaultLongitudinalControlConfiguration(timestamp);
}
if (_long_control_configuration_sub.updated() || _parameter_update_sub.updated()) {
@@ -356,12 +368,12 @@ void FwLateralLongitudinalControl::updateControllerConfiguration()
}
}
void
uint8_t
FwLateralLongitudinalControl::tecs_update_pitch_throttle(const float control_interval, float alt_sp, float airspeed_sp,
float pitch_min_rad, float pitch_max_rad, float throttle_min,
float throttle_max, const float desired_max_sinkrate,
const float desired_max_climbrate,
bool disable_underspeed_detection, float hgt_rate_sp)
bool disable_underspeed_detection, float hgt_rate_sp, hrt_abstime now)
{
bool tecs_is_running = true;
@@ -370,8 +382,7 @@ FwLateralLongitudinalControl::tecs_update_pitch_throttle(const float control_int
&& (_vehicle_status_sub.get().vehicle_type == vehicle_status_s::VEHICLE_TYPE_ROTARY_WING
|| _vehicle_status_sub.get().in_transition_mode)) {
tecs_is_running = false;
return;
return flight_phase_estimation_s::FLIGHT_PHASE_UNKNOWN;
}
const float throttle_trim_compensated = _performance_model.getTrimThrottle(throttle_min,
@@ -400,7 +411,7 @@ FwLateralLongitudinalControl::tecs_update_pitch_throttle(const float control_int
_long_control_state.height_rate,
hgt_rate_sp);
tecs_status_publish(alt_sp, airspeed_sp, airspeed_rate_estimate, throttle_trim_compensated);
tecs_status_publish(alt_sp, airspeed_sp, airspeed_rate_estimate, throttle_trim_compensated, now);
if (tecs_is_running && !_vehicle_status_sub.get().in_transition_mode
&& (_vehicle_status_sub.get().vehicle_type == vehicle_status_s::VEHICLE_TYPE_FIXED_WING)) {
@@ -409,25 +420,28 @@ FwLateralLongitudinalControl::tecs_update_pitch_throttle(const float control_int
// Check level flight: the height rate setpoint is not set or set to 0 and we are close to the target altitude and target altitude is not moving
if ((fabsf(tecs_output.height_rate_reference) < MAX_ALT_REF_RATE_FOR_LEVEL_FLIGHT) &&
fabsf(_long_control_state.altitude_msl - tecs_output.altitude_reference) < _param_nav_fw_alt_rad.get()) {
_flight_phase_estimation_pub.get().flight_phase = flight_phase_estimation_s::FLIGHT_PHASE_LEVEL;
return flight_phase_estimation_s::FLIGHT_PHASE_LEVEL;
} else if (((tecs_output.altitude_reference - _long_control_state.altitude_msl) >= _param_nav_fw_alt_rad.get()) ||
(tecs_output.height_rate_reference >= MAX_ALT_REF_RATE_FOR_LEVEL_FLIGHT)) {
_flight_phase_estimation_pub.get().flight_phase = flight_phase_estimation_s::FLIGHT_PHASE_CLIMB;
return flight_phase_estimation_s::FLIGHT_PHASE_CLIMB;
} else if (((_long_control_state.altitude_msl - tecs_output.altitude_reference) >= _param_nav_fw_alt_rad.get()) ||
(tecs_output.height_rate_reference <= -MAX_ALT_REF_RATE_FOR_LEVEL_FLIGHT)) {
_flight_phase_estimation_pub.get().flight_phase = flight_phase_estimation_s::FLIGHT_PHASE_DESCEND;
return flight_phase_estimation_s::FLIGHT_PHASE_DESCEND;
} else {
//We can't infer the flight phase , do nothing, estimation is reset at each step
// We can't infer the flight phase
return flight_phase_estimation_s::FLIGHT_PHASE_UNKNOWN;
}
}
return flight_phase_estimation_s::FLIGHT_PHASE_UNKNOWN;
}
void
FwLateralLongitudinalControl::tecs_status_publish(float alt_sp, float equivalent_airspeed_sp,
float true_airspeed_derivative_raw, float throttle_trim)
float true_airspeed_derivative_raw, float throttle_trim, hrt_abstime timestamp)
{
tecs_status_s tecs_status{};
@@ -458,7 +472,7 @@ FwLateralLongitudinalControl::tecs_status_publish(float alt_sp, float equivalent
tecs_status.underspeed_ratio = _tecs.get_underspeed_ratio();
tecs_status.fast_descend_ratio = debug_output.fast_descend;
tecs_status.timestamp = hrt_absolute_time();
tecs_status.timestamp = timestamp;
_tecs_status_pub.publish(tecs_status);
}
@@ -531,16 +545,16 @@ fw_lat_lon_control computes attitude and throttle setpoints from lateral and lon
return 0;
}
void FwLateralLongitudinalControl::update_control_state() {
void FwLateralLongitudinalControl::update_control_state(hrt_abstime now) {
updateAltitudeAndHeightRate();
updateAirspeed();
updateAttitude();
updateWind();
updateWind(now);
_lateral_control_state.ground_speed = Vector2f(_local_pos.vx, _local_pos.vy);
}
void FwLateralLongitudinalControl::updateWind() {
void FwLateralLongitudinalControl::updateWind(hrt_abstime now) {
if (_wind_sub.updated()) {
wind_s wind{};
_wind_sub.update(&wind);
@@ -549,14 +563,14 @@ void FwLateralLongitudinalControl::updateWind() {
_wind_valid = PX4_ISFINITE(wind.windspeed_north)
&& PX4_ISFINITE(wind.windspeed_east);
_time_wind_last_received = hrt_absolute_time();
_time_wind_last_received = now;
_lateral_control_state.wind_speed(0) = wind.windspeed_north;
_lateral_control_state.wind_speed(1) = wind.windspeed_east;
} else {
// invalidate wind estimate usage (and correspondingly NPFG, if enabled) after subscription timeout
_wind_valid = _wind_valid && (hrt_absolute_time() - _time_wind_last_received) < WIND_EST_TIMEOUT;
_wind_valid = _wind_valid && (now - _time_wind_last_received) < WIND_EST_TIMEOUT;
}
if (!_wind_valid) {
@@ -735,32 +749,30 @@ float FwLateralLongitudinalControl::getGuidanceQualityFactor(const vehicle_local
return flying_forward_factor * low_ground_speed_factor;
}
float FwLateralLongitudinalControl::getCorrectedLateralAccelSetpoint(float lateral_accel_sp)
float FwLateralLongitudinalControl::getCorrectedLateralAccelSetpoint(float lateral_accel_sp, hrt_abstime now)
{
// Scale the npfg output to zero if npfg is not certain for correct output
_can_run_factor = math::constrain(getGuidanceQualityFactor(_local_pos, _wind_valid), 0.f, 1.f);
hrt_abstime now{hrt_absolute_time()};
// Warn the user when the scale is less than 90% for at least 2 seconds (disable in transition)
// If the npfg was not running before, reset the user warning variables.
if ((now - _time_since_last_npfg_call) > ROLL_WARNING_TIMEOUT) {
if ((now - _time_of_last_npfg_call) > ROLL_WARNING_TIMEOUT) {
_need_report_npfg_uncertain_condition = true;
_time_since_first_reduced_roll = 0U;
_time_of_first_reduced_roll = 0U;
}
if (_vehicle_status_sub.get().in_transition_mode || _can_run_factor > ROLL_WARNING_CAN_RUN_THRESHOLD || _landed) {
// NPFG reports a good condition or we are in transition, reset the user warning variables.
_need_report_npfg_uncertain_condition = true;
_time_since_first_reduced_roll = 0U;
_time_of_first_reduced_roll = 0U;
} else if (_need_report_npfg_uncertain_condition) {
if (_time_since_first_reduced_roll == 0U) {
_time_since_first_reduced_roll = now;
if (_time_of_first_reduced_roll == 0U) {
_time_of_first_reduced_roll = now;
}
if ((now - _time_since_first_reduced_roll) > ROLL_WARNING_TIMEOUT) {
if ((now - _time_of_first_reduced_roll) > ROLL_WARNING_TIMEOUT) {
_need_report_npfg_uncertain_condition = false;
events::send(events::ID("npfg_roll_command_uncertain"), events::Log::Warning,
"Roll command reduced due to uncertain velocity/wind estimates!");
@@ -770,7 +782,7 @@ float FwLateralLongitudinalControl::getCorrectedLateralAccelSetpoint(float later
// Nothing to do, already reported.
}
_time_since_last_npfg_call = now;
_time_of_last_npfg_call = now;
return _can_run_factor * (lateral_accel_sp);
}
@@ -778,8 +790,8 @@ float FwLateralLongitudinalControl::mapLateralAccelerationToRollAngle(float late
return atanf(lateral_acceleration_sp / CONSTANTS_ONE_G);
}
void FwLateralLongitudinalControl::setDefaultLongitudinalControlConfiguration() {
_long_configuration.timestamp = hrt_absolute_time();
void FwLateralLongitudinalControl::setDefaultLongitudinalControlConfiguration(hrt_abstime timestamp) {
_long_configuration.timestamp = timestamp;
_long_configuration.pitch_min = radians(_param_fw_p_lim_min.get());
_long_configuration.pitch_max = radians(_param_fw_p_lim_max.get());
_long_configuration.throttle_min = _param_fw_thr_min.get();
@@ -195,8 +195,8 @@ private:
matrix::Vector2f wind_speed;
} _lateral_control_state{};
bool _need_report_npfg_uncertain_condition{false}; ///< boolean if reporting of uncertain npfg output condition is needed
hrt_abstime _time_since_first_reduced_roll{0U}; ///< absolute time since start when entering reduced roll angle for the first time
hrt_abstime _time_since_last_npfg_call{0U}; ///< absolute time since start when the npfg reduced roll angle calculations was last performed
hrt_abstime _time_of_first_reduced_roll{0U}; ///< absolute time when entering reduced roll angle for the first time
hrt_abstime _time_of_last_npfg_call{0U}; ///< absolute time when the npfg reduced roll angle calculations was last performed
vehicle_attitude_setpoint_s _att_sp{};
bool _landed{false};
float _can_run_factor{0.f};
@@ -212,15 +212,16 @@ private:
float _min_airspeed_from_guidance{0.f}; // need to store it bc we only update after running longitudinal controller
void parameters_update();
void update_control_state();
void tecs_update_pitch_throttle(const float control_interval, float alt_sp, float airspeed_sp,
float pitch_min_rad, float pitch_max_rad, float throttle_min,
float throttle_max, const float desired_max_sinkrate,
const float desired_max_climbrate,
bool disable_underspeed_detection, float hgt_rate_sp);
void update_control_state(hrt_abstime now);
uint8_t tecs_update_pitch_throttle(const float control_interval, float alt_sp, float airspeed_sp,
float pitch_min_rad, float pitch_max_rad, float throttle_min,
float throttle_max, const float desired_max_sinkrate,
const float desired_max_climbrate,
bool disable_underspeed_detection, float hgt_rate_sp, hrt_abstime now);
void tecs_status_publish(float alt_sp, float equivalent_airspeed_sp, float true_airspeed_derivative_raw,
float throttle_trim);
float throttle_trim, hrt_abstime now);
void updateAirspeed();
@@ -230,7 +231,7 @@ private:
float mapLateralAccelerationToRollAngle(float lateral_acceleration_sp) const;
void updateWind();
void updateWind(hrt_abstime now);
void updateTECSAltitudeTimeConstant(const bool is_low_height, const float dt);
@@ -238,13 +239,13 @@ private:
float getGuidanceQualityFactor(const vehicle_local_position_s &local_pos, const bool is_wind_valid) const;
float getCorrectedLateralAccelSetpoint(float lateral_accel_sp);
float getCorrectedLateralAccelSetpoint(float lateral_accel_sp, hrt_abstime now);
void setDefaultLongitudinalControlConfiguration();
void setDefaultLongitudinalControlConfiguration(hrt_abstime now);
void updateLongitudinalControlConfiguration(const longitudinal_control_configuration_s &configuration_in);
void updateControllerConfiguration();
void updateControllerConfiguration(hrt_abstime now);
float getLoadFactor() const;
@@ -388,11 +388,9 @@ FixedWingModeManager::set_control_mode_current(const hrt_abstime &now)
}
} else if ((_control_mode.flag_control_auto_enabled && _control_mode.flag_control_position_enabled)
&& (_position_setpoint_current_valid
|| _pos_sp_triplet.current.type == position_setpoint_s::SETPOINT_TYPE_IDLE)) {
&& _position_setpoint_current_valid) {
// Enter this mode only if the current waypoint has valid 3D position setpoints or is of type IDLE.
// A setpoint of type IDLE can be published by Navigator without a valid position, and is handled here in FW_POSCTRL_MODE_AUTO.
// Enter this mode only if the current waypoint has valid 3D position setpoints.
if (doing_backtransition) {
_control_mode_current = FW_POSCTRL_MODE_TRANSITION_TO_HOVER_LINE_FOLLOW;
@@ -433,6 +431,28 @@ FixedWingModeManager::set_control_mode_current(const hrt_abstime &now)
_control_mode_current = FW_POSCTRL_MODE_AUTO;
}
} else if (_control_mode.flag_control_auto_enabled && _control_mode.flag_control_position_enabled
&& (_pos_sp_triplet.current.type == position_setpoint_s::SETPOINT_TYPE_IDLE)) {
// A setpoint of type IDLE can be published by Navigator without a valid position, and is handled here in FW_POSCTRL_MODE_AUTO.
if (doing_backtransition) {
_control_mode_current = FW_POSCTRL_MODE_TRANSITION_TO_HOVER_HEADING_HOLD;
} else {
_control_mode_current = FW_POSCTRL_MODE_AUTO;
}
} else if (_control_mode.flag_control_auto_enabled && _control_mode.flag_control_position_enabled
&& (_pos_sp_triplet.current.type == position_setpoint_s::SETPOINT_TYPE_LAND)) {
if (doing_backtransition) {
_control_mode_current = FW_POSCTRL_MODE_TRANSITION_TO_HOVER_HEADING_HOLD;
} else {
// Only circular landing are supported when LAND is sent without valid position
_control_mode_current = FW_POSCTRL_MODE_AUTO_LANDING_CIRCULAR;
}
} else if (_control_mode.flag_control_auto_enabled
&& _control_mode.flag_control_climb_rate_enabled
&& _control_mode.flag_armed // only enter this modes if armed, as pure failsafe modes
@@ -1150,6 +1170,7 @@ FixedWingModeManager::control_auto_takeoff(const hrt_abstime &now, const float c
fixed_wing_runway_control_s fw_runway_control{};
fw_runway_control.timestamp = now;
fw_runway_control.runway_takeoff_state = _runway_takeoff.getState();
fw_runway_control.wheel_steering_enabled = true;
fw_runway_control.wheel_steering_nudging_rate = _param_rwto_nudge.get() ? _sticks.getYaw() : 0.f;
@@ -1323,6 +1344,7 @@ FixedWingModeManager::control_auto_takeoff_no_nav(const hrt_abstime &now, const
fixed_wing_runway_control_s fw_runway_control{};
fw_runway_control.timestamp = now;
fw_runway_control.runway_takeoff_state = _runway_takeoff.getState();
fw_runway_control.wheel_steering_enabled = true;
fw_runway_control.wheel_steering_nudging_rate = _param_rwto_nudge.get() ? _sticks.getYaw() : 0.f;
@@ -1571,6 +1593,7 @@ FixedWingModeManager::control_auto_landing_straight(const hrt_abstime &now, cons
fixed_wing_runway_control_s fw_runway_control{};
fw_runway_control.timestamp = now;
fw_runway_control.runway_takeoff_state = fixed_wing_runway_control_s::STATE_FLYING; // not in takeoff, use FLYING as default
fw_runway_control.wheel_steering_enabled = true;
fw_runway_control.wheel_steering_nudging_rate = _param_fw_lnd_nudge.get() > LandingNudgingOption::kNudgingDisabled ?
_sticks.getYaw() : 0.f;
@@ -1594,6 +1617,12 @@ void
FixedWingModeManager::control_auto_landing_circular(const hrt_abstime &now, const float control_interval,
const Vector2f &ground_speed, const position_setpoint_s &pos_sp_curr)
{
if (_time_started_landing == 0) {
// save time at which we started landing and reset landing abort status
reset_landing_state();
_time_started_landing = now;
}
const float airspeed_land = (_param_fw_lnd_airspd.get() > FLT_EPSILON) ? _param_fw_lnd_airspd.get() :
_param_fw_airspd_min.get();
@@ -1601,12 +1630,11 @@ FixedWingModeManager::control_auto_landing_circular(const hrt_abstime &now, cons
const Vector2f local_position{_local_pos.x, _local_pos.y};
Vector2f local_landing_orbit_center = _global_local_proj_ref.project(pos_sp_curr.lat, pos_sp_curr.lon);
if (_time_started_landing == 0) {
// save time at which we started landing and reset landing abort status
reset_landing_state();
_time_started_landing = now;
if (!_local_landing_orbit_center.isAllFinite()) {
_local_landing_orbit_center = _position_setpoint_current_valid
? _global_local_proj_ref.project(pos_sp_curr.lat, pos_sp_curr.lon)
: local_position;
}
const bool abort_on_terrain_timeout = checkLandingAbortBitMask(_param_fw_lnd_abort.get(),
@@ -1642,7 +1670,7 @@ FixedWingModeManager::control_auto_landing_circular(const hrt_abstime &now, cons
1.0f);
/* lateral guidance first, because npfg will adjust the airspeed setpoint if necessary */
const DirectionalGuidanceOutput sp = navigateLoiter(local_landing_orbit_center, local_position, loiter_radius,
const DirectionalGuidanceOutput sp = navigateLoiter(_local_landing_orbit_center, local_position, loiter_radius,
loiter_direction_ccw,
ground_speed, _wind_vel);
fixed_wing_lateral_setpoint_s fw_lateral_ctrl_sp{empty_lateral_control_setpoint};
@@ -1700,7 +1728,7 @@ FixedWingModeManager::control_auto_landing_circular(const hrt_abstime &now, cons
} else {
// follow the glide slope
const DirectionalGuidanceOutput sp = navigateLoiter(local_landing_orbit_center, local_position, loiter_radius,
const DirectionalGuidanceOutput sp = navigateLoiter(_local_landing_orbit_center, local_position, loiter_radius,
loiter_direction_ccw,
ground_speed, _wind_vel);
fixed_wing_lateral_setpoint_s fw_lateral_ctrl_sp{empty_lateral_control_setpoint};
@@ -1736,6 +1764,7 @@ FixedWingModeManager::control_auto_landing_circular(const hrt_abstime &now, cons
fixed_wing_runway_control_s fw_runway_control{};
fw_runway_control.timestamp = now;
fw_runway_control.runway_takeoff_state = fixed_wing_runway_control_s::STATE_FLYING; // not in takeoff, use FLYING as default
fw_runway_control.wheel_steering_enabled = true;
fw_runway_control.wheel_steering_nudging_rate = _param_fw_lnd_nudge.get() > LandingNudgingOption::kNudgingDisabled ?
_sticks.getYaw() : 0.f;
@@ -2285,6 +2314,7 @@ FixedWingModeManager::reset_landing_state()
_flare_states = FlareStates{};
_local_landing_orbit_center.setNaN();
_lateral_touchdown_position_offset = 0.0f;
_last_time_terrain_alt_was_valid = 0;
@@ -2299,6 +2329,10 @@ FixedWingModeManager::reset_landing_state()
float FixedWingModeManager::getMaxRollAngleNearGround(const float altitude, const float terrain_altitude) const
{
if (!PX4_ISFINITE(altitude) || !PX4_ISFINITE(terrain_altitude)) {
return math::radians(_param_fw_r_lim.get());
}
// we want the wings level when at the wing height above ground
const float height_above_ground = math::max(altitude - (terrain_altitude + _param_fw_wing_height.get()), 0.0f);
@@ -2424,7 +2458,7 @@ FixedWingModeManager::getLandingTerrainAltitudeEstimate(const hrt_abstime &now,
if (_local_pos.dist_bottom_valid) {
const float terrain_estimate = _local_pos.ref_alt + -_local_pos.z - _local_pos.dist_bottom;
const float terrain_estimate = _reference_altitude + -_local_pos.z - _local_pos.dist_bottom;
_last_valid_terrain_alt_estimate = terrain_estimate;
_last_time_terrain_alt_was_valid = now;

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