Metadata update and fixes to internallinkerrors
Some checks failed
Container build / Set Tags and Variables (push) Has been cancelled
Container build / Build Container (amd64) (push) Has been cancelled
Container build / Build Container (arm64) (push) Has been cancelled
Container build / Deploy To Registry (push) Has been cancelled
Docs - Crowdin - Upload Guide sources (en) / upload-to-crowdin (push) Has been cancelled
Docs - Deploy PX4 User Guide / build (push) Has been cancelled
Docs - Deploy PX4 User Guide / deploy (push) Has been cancelled
Handle stale issues and PRs / stale (push) Has been cancelled
Build all targets / Scan for Board Targets (push) Has been cancelled
Build all targets / Build Group [${{ matrix.group }}][${{ matrix.arch == 'nuttx' && 'x86' || 'arm64' }}] (push) Has been cancelled
Build all targets / Upload Artifacts to S3 (push) Has been cancelled
Build all targets / Create Release and Upload Artifacts (push) Has been cancelled
Checks / build (NO_NINJA_BUILD=1 px4_fmu-v5_default) (push) Has been cancelled
Checks / build (NO_NINJA_BUILD=1 px4_sitl_default) (push) Has been cancelled
Checks / build (check_format) (push) Has been cancelled
Checks / build (check_newlines) (push) Has been cancelled
Checks / build (module_documentation) (push) Has been cancelled
Checks / build (px4_fmu-v2_default stack_check) (push) Has been cancelled
Checks / build (px4_sitl_allyes) (push) Has been cancelled
Checks / build (shellcheck_all) (push) Has been cancelled
Checks / build (tests) (push) Has been cancelled
Checks / build (tests_coverage) (push) Has been cancelled
Checks / build (validate_module_configs) (push) Has been cancelled
Clang Tidy / build (push) Has been cancelled
MacOS build / build (px4_fmu-v5_default) (push) Has been cancelled
MacOS build / build (px4_sitl) (push) Has been cancelled
Ubuntu environment build / Build and Test (ubuntu:22.04) (push) Has been cancelled
Ubuntu environment build / Build and Test (ubuntu:24.04) (push) Has been cancelled
EKF Update Change Indicator / unit_tests (push) Has been cancelled
Failsafe Simulator Build / build (failsafe_web) (push) Has been cancelled
FLASH usage analysis / Analyzing px4_fmu-v5x (push) Has been cancelled
FLASH usage analysis / Analyzing px4_fmu-v6x (push) Has been cancelled
FLASH usage analysis / Publish Results (push) Has been cancelled
ITCM check / Checking nxp_tropic-community (push) Has been cancelled
ITCM check / Checking px4_fmu-v5x (push) Has been cancelled
ITCM check / Checking px4_fmu-v6xrt (push) Has been cancelled
MAVROS Mission Tests / build (map[mission:MC_mission_box vehicle:iris]) (push) Has been cancelled
MAVROS Offboard Tests / build (map[test_file:mavros_posix_tests_offboard_posctl.test vehicle:iris]) (push) Has been cancelled
Nuttx Target with extra env config / build (px4_fmu-v5_default) (push) Has been cancelled
Python CI Checks / build (push) Has been cancelled
ROS Integration Tests / build (push) Has been cancelled
ROS Translation Node Tests / Build and test (map[ros_version:humble ubuntu:jammy]) (push) Has been cancelled
ROS Translation Node Tests / Build and test (map[ros_version:jazzy ubuntu:noble]) (push) Has been cancelled
SITL Tests / Testing PX4 tailsitter (push) Has been cancelled
SITL Tests / Testing PX4 iris (push) Has been cancelled
SITL Tests / Testing PX4 standard_vtol (push) Has been cancelled
Fuzzing / Fuzzing (push) Has been cancelled

This commit is contained in:
Hamish Willee
2025-08-07 09:43:34 +10:00
parent aa15512762
commit 5415aeb9fe
20 changed files with 339 additions and 100 deletions

View File

@@ -618,6 +618,7 @@
- [MountOrientation](msg_docs/MountOrientation.md)
- [NavigatorMissionItem](msg_docs/NavigatorMissionItem.md)
- [NavigatorStatus](msg_docs/NavigatorStatus.md)
- [NeuralControl](msg_docs/NeuralControl.md)
- [NormalizedUnsignedSetpoint](msg_docs/NormalizedUnsignedSetpoint.md)
- [ObstacleDistance](msg_docs/ObstacleDistance.md)
- [OffboardControlMode](msg_docs/OffboardControlMode.md)
@@ -721,6 +722,7 @@
- [EventV0](msg_docs/EventV0.md)
- [HomePositionV0](msg_docs/HomePositionV0.md)
- [VehicleAttitudeSetpointV0](msg_docs/VehicleAttitudeSetpointV0.md)
- [VehicleLocalPositionV0](msg_docs/VehicleLocalPositionV0.md)
- [VehicleStatusV0](msg_docs/VehicleStatusV0.md)
- [MAVLink Messaging](mavlink/index.md)
- [Adding Messages](mavlink/adding_messages.md)

View File

@@ -7,7 +7,7 @@ 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.
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.
@@ -61,7 +61,6 @@ In the [controller diagram](../flight_stack/controller_diagrams.md) you can see
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.

View File

@@ -1,6 +1,6 @@
# Neural Network Module: System Integration
The neural control module ([mc_nn_control](../modules/modules_controller.md#mc_nn_control)) implements an end-to-end controller utilizing neural networks.
The neural control module ([mc_nn_control](../modules/modules_controller.md#mc-nn-control)) implements an end-to-end controller utilizing neural networks.
The parts of the module directly concerned with generating the code for the trained neural network and integrating it into the module are covered in [TensorFlow Lite Micro (TFLM)](../advanced/tflm.md).
This page covers the changes that were made to integrate the module into PX4, both within the module, and in larger system configuration.
@@ -14,7 +14,7 @@ For more information see the developer [Getting Started](../dev_setup/getting_st
## Autostart
A line to autostart the [mc_nn_control](../modules/modules_controller.md#mc_nn_control) module has been added in the [`ROMFS/px4fmu_common/init.d/rc.mc_apps`](https://github.com/PX4/PX4-Autopilot/blob/main/ROMFS/px4fmu_common/init.d/rc.mc_apps) startup script.
A line to autostart the [mc_nn_control](../modules/modules_controller.md#mc-nn-control) module has been added in the [`ROMFS/px4fmu_common/init.d/rc.mc_apps`](https://github.com/PX4/PX4-Autopilot/blob/main/ROMFS/px4fmu_common/init.d/rc.mc_apps) startup script.
It checks whether the module is included by looking for the parameter [MC_NN_EN](../advanced_config/parameter_reference.md#MC_NN_EN).
If this is set to `1` (the default value), the module will be started when booting PX4.

View File

@@ -1,10 +1,10 @@
# 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 [Multicopter Neural Network](advanced/neural_networks.md) module ([mc_nn_control](../modules/modules_controller.md#mc-nn-control)) integrates a neural network that uses the [TensorFlow Lite Micro (TFLM)](https://github.com/tensorflow/tflite-micro) inference library.
This is a mature inference library intended for use on embedded devices, and is hence a suitable choice for PX4.
This guide explains how the TFLM library is integrated into the [mc_nn_control](../modules/modules_controller.md#mc_nn_control) module, and the changes you would have to make to use it for your own neural network.
This guide explains how the TFLM library is integrated into the [mc_nn_control](../modules/modules_controller.md#mc-nn-control) module, and the changes you would have to make to use it for your own neural network.
::: tip
For more information, see the [TFLM guide](https://ai.google.dev/edge/litert/microcontrollers/get_started).

View File

@@ -3,7 +3,7 @@
The _Flight termination_ [failsafe action](../config/safety.md#failsafe-actions) irreversibly turns off controllers and sets PWM values to their parameter configured failsafe values.
::: info
Flight termination differs from the [Kill action](../config/safety.html#kill-switch) in that it is permanent until after reboot.
Flight termination differs from the [Kill action](../config/safety.md#kill-switch) in that it is permanent until after reboot.
:::
::: warning

View File

@@ -14094,6 +14094,7 @@ Sideslip measurement noise of the internal wind estimator(s) of the airspeed sel
Enable checks on airspeed sensors.
Controls which checks are run to check airspeed data for validity. Only applied if ASPD_PRIMARY > 0.
Note: The missing data check (bit 0) is implicitly always enabled when ASPD_DO_CHECKS > 0, even if bit 0 is not explicitly set.
**Bitmask:**
@@ -16397,6 +16398,8 @@ A value of 1 allows joystick control only. RC input handling and the associated
A value of 2 allows either RC Transmitter or Joystick input. The first valid input is used, will fallback to other sources if the input stream becomes invalid.
A value of 3 allows either input from RC or joystick. The first available source is selected and used until reboot.
A value of 4 ignores any stick input.
A value of 5 allows either RC Transmitter or Joystick input. But RC has priority and whenever avaiable is immedietely used.
A value of 6 allows either RC Transmitter or Joystick input. But Joystick has priority and whenever avaiable is immedietely used.
**Values:**
@@ -16405,6 +16408,8 @@ A value of 4 ignores any stick input.
- `2`: RC and Joystick with fallback
- `3`: RC or Joystick keep first
- `4`: Stick input disabled
- `5`: RC priority, Joystick fallback
- `6`: Joystick priority, RC fallback
| Reboot | minValue | maxValue | increment | default | unit |
| ------ | -------- | -------- | --------- | ------- | ---- |
@@ -17428,6 +17433,21 @@ GPS measurement delay relative to IMU measurements.
| ------- | -------- | -------- | --------- | ------- | ---- |
| ✓ | 0 | 300 | | 110 | ms |
### EKF2_GPS_MODE (`INT32`) {#EKF2_GPS_MODE}
Fusion reset mode.
Automatic: reset on fusion timeout if no other source of position is available Dead-reckoning: reset on fusion timeout if no source of velocity is available
**Values:**
- `0`: Automatic
- `1`: Dead-reckoning
| Reboot | minValue | maxValue | increment | default | unit |
| ------ | -------- | -------- | --------- | ------- | ---- |
|   | | | | 0 |
### EKF2_GPS_POS_X (`FLOAT`) {#EKF2_GPS_POS_X}
X position of GPS antenna in body frame.
@@ -34727,7 +34747,7 @@ SBUS RC driver.
| Reboot | minValue | maxValue | increment | default | unit |
| ------- | -------- | -------- | --------- | ------- | ---- |
| ✓ | | | | 300 |
| ✓ | | | | 0 |
### SER_EXT2_BAUD (`INT32`) {#SER_EXT2_BAUD}

View File

@@ -45,28 +45,6 @@ div.frame_variant td, div.frame_variant th {
}
</style>
## 2D Space Robot
### Space Robot
<div class="frame_common">
<img src="../../assets/airframes/types/AirframeUnknown.svg"/>
</div>
<div class="frame_variant">
<table>
<thead>
<tr><th>Name</th><th></th></tr>
</thead>
<tbody>
<tr id="2d_space_robot_space_robot_kth_space_robot">
<td>KTH Space Robot</td>
<td>Maintainer: DISCOWER<p><code>SYS_AUTOSTART</code> = 70000</p></td>
</tr>
</tbody>
</table>
</div>
## Airship
### Airship
@@ -622,7 +600,7 @@ div.frame_variant td, div.frame_variant th {
<td>Maintainer: John Doe &lt;john@example.com&gt;<p><code>SYS_AUTOSTART</code> = 50000</p></td>
</tr>
<tr id="rover_rover_aion_robotics_r1_ugv">
<td><a href="https://www.aionrobotics.com/r1">Aion Robotics R1 UGV</a></td>
<td><a href="https://docs.px4.io/main/en/complete_vehicles_rover/aion_r1.html">Aion Robotics R1 UGV</a></td>
<td>Maintainer: John Doe &lt;john@example.com&gt;<p><code>SYS_AUTOSTART</code> = 50001</p></td>
</tr>
<tr id="rover_rover_generic_rover_ackermann">
@@ -637,13 +615,27 @@ div.frame_variant td, div.frame_variant th {
<td>Generic Rover Mecanum</td>
<td>Maintainer: John Doe &lt;john@example.com&gt;<p><code>SYS_AUTOSTART</code> = 52000</p></td>
</tr>
<tr id="rover_rover_generic_ground_vehicle_(deprecated)">
<td>Generic Ground Vehicle (Deprecated)</td>
<td><p><code>SYS_AUTOSTART</code> = 59000</p><br><b>Specific Outputs:</b><ul><li><b>Motor1</b>: throttle</li><li><b>Servo1</b>: steering</li></ul></td>
</tr>
<tr id="rover_rover_nxp_cup_car:_df_robot_gpx_(deprecated)">
<td>NXP Cup car: DF Robot GPX (Deprecated)</td>
<td>Maintainer: Katrin Moritz<p><code>SYS_AUTOSTART</code> = 59001</p><br><b>Specific Outputs:</b><ul><li><b>Motor1</b>: Speed of left wheels</li><li><b>Servo1</b>: Steering servo</li></ul></td>
</tbody>
</table>
</div>
## Spacecraft
### Free-Flyer
<div class="frame_common">
<img src="../../assets/airframes/types/AirframeUnknown.svg"/>
</div>
<div class="frame_variant">
<table>
<thead>
<tr><th>Name</th><th></th></tr>
</thead>
<tbody>
<tr id="spacecraft_free-flyer_kth-atmos">
<td>KTH-ATMOS</td>
<td>Maintainer: DISCOWER<p><code>SYS_AUTOSTART</code> = 70000</p></td>
</tr>
</tbody>
</table>

View File

@@ -198,7 +198,7 @@ It takes in 15 input values and outputs 4 control actions.
Inputs: [pos_err(3), att(6), vel(3), ang_vel(3)]
Outputs: [Actuator motors(4)]
### Usage {#mc_nn_control_usage}
### Usage {#mc-nn-control_usage}
```
mc_nn_control <command> [arguments...]

View File

@@ -1166,6 +1166,30 @@ rgbled <command> [arguments...]
status print status info
```
## rgbled_aw2023
Source: [drivers/lights/rgbled_aw2023](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/lights/rgbled_aw2023)
### Usage {#rgbled_aw2023_usage}
```
rgbled_aw2023 <command> [arguments...]
Commands:
start
[-I] Internal I2C bus(es)
[-X] External I2C bus(es)
[-b <val>] board-specific bus (default=all) (external SPI: n-th bus
(default=1))
[-f <val>] bus frequency in kHz
[-q] quiet startup (no message if no device found)
[-a <val>] I2C address
default: 69
stop
status print status info
```
## rgbled_is31fl3195
Source: [drivers/lights/rgbled_is31fl3195](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/lights/rgbled_is31fl3195)

View File

@@ -1,5 +1,50 @@
# Modules Reference: Ins (Driver)
## MicroStrain
Source: [drivers/ins/microstrain](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/ins/microstrain)
### Description
MicroStrain by HBK Inertial Sensor Driver.
Currently supports the following sensors:
-[CV7-AR](https://www.hbkworld.com/en/products/transducers/inertial-sensors/vertical-reference-units--vru-/3dm-cv7-ar) -[CV7-AHRS](https://www.hbkworld.com/en/products/transducers/inertial-sensors/attitude-and-heading-reference-systems--ahrs-/3dm-cv7-ahrs) -[CV7-INS](https://www.hbkworld.com/en/products/transducers/inertial-sensors/inertial-navigation-systems--ins-/3dm-cv7-ins) -[CV7-GNSS/INS](https://www.hbkworld.com/en/products/transducers/inertial-sensors/inertial-navigation-systems--ins-/3dm-cv7-gnss-ins)
This driver is not included in the firmware by default.
Include the module in firmware by setting the
[kconfig](../hardware/porting_guide_config.md#px4-board-configuration-kconfig) variables:
`CONFIG_DRIVERS_INS_MICROSTRAIN` or `CONFIG_COMMON_INS`.
### Examples
Attempt to start driver on a specified serial device.
The driver will choose /dev/ttyS4 by default if no port is specified
```
microstrain start -d /dev/ttyS1
```
Stop driver
```
microstrain stop
```
### Usage {#MicroStrain_usage}
```
MicroStrain <command> [arguments...]
Commands:
start Start driver
[-d <val>] Port
values: <file:dev>, default: /dev/ttyS4
stop Stop driver
status Driver status
```
## ilabs
Source: [drivers/ins/ilabs](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/ins/ilabs)
@@ -14,7 +59,7 @@ After that you can use the ILABS_MODE parameter to config outputs:
- Only raw sensor output (the default).
- Sensor output and INS data such as position and velocity estimates.
Setup/usage information: https://docs.px4.io/main/en/sensor/ilabs.html
Setup/usage information: https://docs.px4.io/main/en/sensor/inertiallabs.html
### Examples

View File

@@ -1,27 +1,39 @@
# ActionRequest (UORB message)
Action request for the vehicle's main state
Message represents actions requested by a PX4 internal component towards the main state machine such as a request to arm or switch mode.
It allows mapping triggers from various external interfaces like RC channels or MAVLink to cause an action.
Request are published by `manual_control` and subscribed by the `commander` and `vtol_att_control` modules.
[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActionRequest.msg)
```c
uint64 timestamp # time since system start (microseconds)
# Action request for the vehicle's main state
#
# Message represents actions requested by a PX4 internal component towards the main state machine such as a request to arm or switch mode.
# It allows mapping triggers from various external interfaces like RC channels or MAVLink to cause an action.
# Request are published by `manual_control` and subscribed by the `commander` and `vtol_att_control` modules.
uint8 action # what action is requested
uint8 ACTION_DISARM = 0
uint8 ACTION_ARM = 1
uint8 ACTION_TOGGLE_ARMING = 2
uint8 ACTION_UNKILL = 3
uint8 ACTION_KILL = 4
uint8 ACTION_SWITCH_MODE = 5
uint8 ACTION_VTOL_TRANSITION_TO_MULTICOPTER = 6
uint8 ACTION_VTOL_TRANSITION_TO_FIXEDWING = 7
uint8 ACTION_TERMINATE = 8
uint64 timestamp # [us] Time since system start
uint8 source # how the request was triggered
uint8 SOURCE_STICK_GESTURE = 0
uint8 SOURCE_RC_SWITCH = 1
uint8 SOURCE_RC_BUTTON = 2
uint8 SOURCE_RC_MODE_SLOT = 3
uint8 action # [@enum ACTION] Requested action
uint8 ACTION_DISARM = 0 # Disarm vehicle
uint8 ACTION_ARM = 1 # Arm vehicle
uint8 ACTION_TOGGLE_ARMING = 2 # Toggle arming
uint8 ACTION_UNKILL = 3 # Revert a kill action
uint8 ACTION_KILL = 4 # Kill vehicle (instantly stop the motors)
uint8 ACTION_SWITCH_MODE = 5 # Switch mode. The target mode is set in the `mode` field.
uint8 ACTION_VTOL_TRANSITION_TO_MULTICOPTER = 6 # Transition to hover flight
uint8 ACTION_VTOL_TRANSITION_TO_FIXEDWING = 7 # Transition to fast forward flight
uint8 ACTION_TERMINATION = 8 # Irreversably output failsafe values on all outputs, trigger parachute
uint8 mode # for ACTION_SWITCH_MODE what mode is requested according to vehicle_status_s::NAVIGATION_STATE_*
uint8 source # [@enum SOURCE] Request trigger type, such as a switch, button or gesture
uint8 SOURCE_STICK_GESTURE = 0 # Triggered by holding the sticks in a certain position
uint8 SOURCE_RC_SWITCH = 1 # Triggered by an RC switch moving into a certain position
uint8 SOURCE_RC_BUTTON = 2 # Triggered by a momentary button on the RC being pressed or held
uint8 SOURCE_RC_MODE_SLOT = 3 # Mode change through the RC mode selection mechanism
uint8 mode # Requested mode. Only applies when `action` is `ACTION_SWITCH_MODE`. Values for this field are defined by the `vehicle_status_s::NAVIGATION_STATE_*` enumeration.
```

View File

@@ -1,7 +1,5 @@
# ActuatorArmed (UORB message)
[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorArmed.msg)
```c
@@ -11,8 +9,8 @@ bool armed # Set to true if system is armed
bool prearmed # Set to true if the actuator safety is disabled but motors are not armed
bool ready_to_arm # Set to true if system is ready to be armed
bool lockdown # Set to true if actuators are forced to being disabled (due to emergency or HIL)
bool manual_lockdown # Set to true if manual throttle kill switch is engaged
bool force_failsafe # Set to true if the actuators are forced to the failsafe position
bool kill # Set to true if manual throttle kill switch is engaged
bool termination # Send out failsafe (by default same as disarmed) output
bool in_esc_calibration_mode # IO/FMU should ignore messages from the actuator controls topics
```

View File

@@ -1,35 +1,49 @@
# AirspeedWind (UORB message)
Wind estimate (from airspeed_selector)
Contains wind estimation and airspeed innovation information estimated by the WindEstimator
in the airspeed selector module.
This message is published by the airspeed selector for debugging purposes, and is not
subscribed to by any other modules.
[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/AirspeedWind.msg)
```c
uint64 timestamp # time since system start (microseconds)
uint64 timestamp_sample # the timestamp of the raw data (microseconds)
# Wind estimate (from airspeed_selector)
#
# Contains wind estimation and airspeed innovation information estimated by the WindEstimator
# in the airspeed selector module.
#
# This message is published by the airspeed selector for debugging purposes, and is not
# subscribed to by any other modules.
float32 windspeed_north # Wind component in north / X direction (m/sec)
float32 windspeed_east # Wind component in east / Y direction (m/sec)
uint64 timestamp # [us] Time since system start
uint64 timestamp_sample # [us] Timestamp of the raw data
float32 variance_north # Wind estimate error variance in north / X direction (m/sec)**2 - set to zero (no uncertainty) if not estimated
float32 variance_east # Wind estimate error variance in east / Y direction (m/sec)**2 - set to zero (no uncertainty) if not estimated
float32 windspeed_north # [m/s] Wind component in north / X direction
float32 windspeed_east # [m/s] Wind component in east / Y direction
float32 tas_innov # True airspeed innovation
float32 tas_innov_var # True airspeed innovation variance
float32 variance_north # [(m/s)^2] [@invalid 0 if not estimated] Wind estimate error variance in north / X direction
float32 variance_east # [(m/s)^2] [@invalid 0 if not estimated] Wind estimate error variance in east / Y direction
float32 tas_scale_raw # Estimated true airspeed scale factor (not validated)
float32 tas_scale_raw_var # True airspeed scale factor variance
float32 tas_innov # [m/s] True airspeed innovation
float32 tas_innov_var # [m/s] True airspeed innovation variance
float32 tas_scale_validated # Estimated true airspeed scale factor after validation
float32 tas_scale_raw # Estimated true airspeed scale factor (not validated)
float32 tas_scale_raw_var # True airspeed scale factor variance
float32 beta_innov # Sideslip measurement innovation
float32 beta_innov_var # Sideslip measurement innovation variance
float32 tas_scale_validated # Estimated true airspeed scale factor after validation
uint8 source # source of wind estimate
float32 beta_innov # [rad] Sideslip measurement innovation
float32 beta_innov_var # [rad^2] Sideslip measurement innovation variance
uint8 SOURCE_AS_BETA_ONLY = 0 # wind estimate only based on synthetic sideslip fusion
uint8 SOURCE_AS_SENSOR_1 = 1 # combined synthetic sideslip and airspeed fusion (data from first airspeed sensor)
uint8 SOURCE_AS_SENSOR_2 = 2 # combined synthetic sideslip and airspeed fusion (data from second airspeed sensor)
uint8 SOURCE_AS_SENSOR_3 = 3 # combined synthetic sideslip and airspeed fusion (data from third airspeed sensor)
uint8 source # source of wind estimate
uint8 SOURCE_AS_BETA_ONLY = 0 # Wind estimate only based on synthetic sideslip fusion
uint8 SOURCE_AS_SENSOR_1 = 1 # Combined synthetic sideslip and airspeed fusion (data from first airspeed sensor)
uint8 SOURCE_AS_SENSOR_2 = 2 # Combined synthetic sideslip and airspeed fusion (data from second airspeed sensor)
uint8 SOURCE_AS_SENSOR_3 = 3 # Combined synthetic sideslip and airspeed fusion (data from third airspeed sensor)
```

View File

@@ -0,0 +1,26 @@
# NeuralControl (UORB message)
Neural control
Debugging topic for the Neural controller, logs the inputs and output vectors of the neural network, and the time it takes to run
Publisher: mc_nn_control
Subscriber: logger
[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/NeuralControl.msg)
```c
# Neural control
#
# Debugging topic for the Neural controller, logs the inputs and output vectors of the neural network, and the time it takes to run
# Publisher: mc_nn_control
# Subscriber: logger
uint64 timestamp # [us] Time since system start
float32[15] observation # Observation vector (pos error (3), att (6d), lin vel (3), ang vel (3))
float32[4] network_output # Output from neural network
int32 controller_time # [us] Time spent from input to output
int32 inference_time # [us] Time spent for NN inference
```

View File

@@ -31,10 +31,10 @@ float64 lon # longitude, in deg
float32 alt # altitude AMSL, in m
float32 yaw # yaw (only in hover), in rad [-PI..PI), NaN = leave to flight task
float32 loiter_radius # loiter major axis radius in m
float32 loiter_minor_radius # loiter minor axis radius (used for non-circular loiter shapes) in m
float32 loiter_radius # [m] [@range 0, INF] loiter major axis radius
float32 loiter_minor_radius # [m] [@range 0, INF] loiter minor axis radius (used for non-circular loiter shapes)
bool loiter_direction_counter_clockwise # loiter direction is clockwise by default and can be changed using this field
float32 loiter_orientation # Orientation of the major axis with respect to true north in rad [-pi,pi)
float32 loiter_orientation # [rad] [@range -pi, pi] orientation of the major axis with respect to true north
uint8 loiter_pattern # loitern pattern to follow
float32 acceptance_radius # horizontal acceptance_radius (meters)

View File

@@ -1,7 +1,5 @@
# Px4ioStatus (UORB message)
[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/Px4ioStatus.msg)
```c
@@ -36,7 +34,7 @@ bool alarm_rc_lost
bool arming_failsafe_custom
bool arming_fmu_armed
bool arming_fmu_prearmed
bool arming_force_failsafe
bool arming_termination
bool arming_io_arm_ok
bool arming_lockdown
bool arming_termination_failsafe

View File

@@ -9,7 +9,7 @@ The coordinate system origin is the vehicle position at the time when the EKF2-m
# Fused local position in NED.
# The coordinate system origin is the vehicle position at the time when the EKF2-module was started.
uint32 MESSAGE_VERSION = 0
uint32 MESSAGE_VERSION = 1
uint64 timestamp # time since system start (microseconds)
uint64 timestamp_sample # the timestamp of the raw data (microseconds)

View File

@@ -0,0 +1,96 @@
# VehicleLocalPositionV0 (UORB message)
Fused local position in NED.
The coordinate system origin is the vehicle position at the time when the EKF2-module was started.
[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/px4_msgs_old/msg/VehicleLocalPositionV0.msg)
```c
# Fused local position in NED.
# The coordinate system origin is the vehicle position at the time when the EKF2-module was started.
uint32 MESSAGE_VERSION = 0
uint64 timestamp # time since system start (microseconds)
uint64 timestamp_sample # the timestamp of the raw data (microseconds)
bool xy_valid # true if x and y are valid
bool z_valid # true if z is valid
bool v_xy_valid # true if vx and vy are valid
bool v_z_valid # true if vz is valid
# Position in local NED frame
float32 x # North position in NED earth-fixed frame, (metres)
float32 y # East position in NED earth-fixed frame, (metres)
float32 z # Down position (negative altitude) in NED earth-fixed frame, (metres)
# Position reset delta
float32[2] delta_xy # Amount of lateral shift of position estimate in latest reset (in x and y) [m]
uint8 xy_reset_counter # Index of latest lateral position estimate reset
float32 delta_z # Amount of vertical shift of position estimate in latest reset [m]
uint8 z_reset_counter # Index of latest vertical position estimate reset
# Velocity in NED frame
float32 vx # North velocity in NED earth-fixed frame, (metres/sec)
float32 vy # East velocity in NED earth-fixed frame, (metres/sec)
float32 vz # Down velocity in NED earth-fixed frame, (metres/sec)
float32 z_deriv # Down position time derivative in NED earth-fixed frame, (metres/sec)
# Velocity reset delta
float32[2] delta_vxy # Amount of lateral shift of velocity estimate in latest reset (in x and y) [m/s]
uint8 vxy_reset_counter # Index of latest vertical velocity estimate reset
float32 delta_vz # Amount of vertical shift of velocity estimate in latest reset [m/s]
uint8 vz_reset_counter # Index of latest vertical velocity estimate reset
# Acceleration in NED frame
float32 ax # North velocity derivative in NED earth-fixed frame, (metres/sec^2)
float32 ay # East velocity derivative in NED earth-fixed frame, (metres/sec^2)
float32 az # Down velocity derivative in NED earth-fixed frame, (metres/sec^2)
float32 heading # Euler yaw angle transforming the tangent plane relative to NED earth-fixed frame, -PI..+PI, (radians)
float32 heading_var
float32 unaided_heading # Same as heading but generated by integrating corrected gyro data only
float32 delta_heading # Heading delta caused by latest heading reset [rad]
uint8 heading_reset_counter # Index of latest heading reset
bool heading_good_for_control
float32 tilt_var
# Position of reference point (local NED frame origin) in global (GPS / WGS84) frame
bool xy_global # true if position (x, y) has a valid global reference (ref_lat, ref_lon)
bool z_global # true if z has a valid global reference (ref_alt)
uint64 ref_timestamp # Time when reference position was set since system start, (microseconds)
float64 ref_lat # Reference point latitude, (degrees)
float64 ref_lon # Reference point longitude, (degrees)
float32 ref_alt # Reference altitude AMSL, (metres)
# Distance to surface
bool dist_bottom_valid # true if distance to bottom surface is valid
float32 dist_bottom # Distance from from bottom surface to ground, (metres)
float32 dist_bottom_var # terrain estimate variance (m^2)
float32 delta_dist_bottom # Amount of vertical shift of dist bottom estimate in latest reset [m]
uint8 dist_bottom_reset_counter # Index of latest dist bottom estimate reset
uint8 dist_bottom_sensor_bitfield # bitfield indicating what type of sensor is used to estimate dist_bottom
uint8 DIST_BOTTOM_SENSOR_NONE = 0
uint8 DIST_BOTTOM_SENSOR_RANGE = 1 # (1 << 0) a range sensor is used to estimate dist_bottom field
uint8 DIST_BOTTOM_SENSOR_FLOW = 2 # (1 << 1) a flow sensor is used to estimate dist_bottom field (mostly fixed-wing use case)
float32 eph # Standard deviation of horizontal position error, (metres)
float32 epv # Standard deviation of vertical position error, (metres)
float32 evh # Standard deviation of horizontal velocity error, (metres/sec)
float32 evv # Standard deviation of vertical velocity error, (metres/sec)
bool dead_reckoning # True if this position is estimated through dead-reckoning
# estimator specified vehicle limits
float32 vxy_max # maximum horizontal speed - set to 0 when limiting not required (meters/sec)
float32 vz_max # maximum vertical speed - set to 0 when limiting not required (meters/sec)
float32 hagl_min # minimum height above ground level - set to 0 when limiting not required (meters)
float32 hagl_max # maximum height above ground level - set to 0 when limiting not required (meters)
# TOPICS vehicle_local_position vehicle_local_position_groundtruth external_ins_local_position
# TOPICS estimator_local_position
```

View File

@@ -1,24 +1,34 @@
# Wind (UORB message)
Wind estimate (from EKF2)
Contains the system-wide estimate of horizontal wind velocity and its variance.
Published by the navigation filter (EKF2) for use by other flight modules and libraries.
[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/Wind.msg)
[source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/Wind.msg)
```c
uint64 timestamp # time since system start (microseconds)
uint64 timestamp_sample # the timestamp of the raw data (microseconds)
# Wind estimate (from EKF2)
#
# Contains the system-wide estimate of horizontal wind velocity and its variance.
# Published by the navigation filter (EKF2) for use by other flight modules and libraries.
float32 windspeed_north # Wind component in north / X direction (m/sec)
float32 windspeed_east # Wind component in east / Y direction (m/sec)
uint32 MESSAGE_VERSION = 0
float32 variance_north # Wind estimate error variance in north / X direction (m/sec)**2 - set to zero (no uncertainty) if not estimated
float32 variance_east # Wind estimate error variance in east / Y direction (m/sec)**2 - set to zero (no uncertainty) if not estimated
uint64 timestamp # [us] Time since system start
uint64 timestamp_sample # [us] Timestamp of the raw data
float32 tas_innov # True airspeed innovation
float32 tas_innov_var # True airspeed innovation variance
float32 windspeed_north # [m/s] Wind component in north / X direction
float32 windspeed_east # [m/s] Wind component in east / Y direction
float32 beta_innov # Sideslip measurement innovation
float32 beta_innov_var # Sideslip measurement innovation variance
float32 variance_north # [(m/s)^2] [@invalid 0 if not estimated] Wind estimate error variance in north / X direction
float32 variance_east # [(m/s)^2] [@invalid 0 if not estimated] Wind estimate error variance in east / Y direction
float32 tas_innov # [m/s] True airspeed innovation
float32 tas_innov_var # [(m/s)^2] True airspeed innovation variance
float32 beta_innov # [rad] Sideslip measurement innovation
float32 beta_innov_var # [rad^2] Sideslip measurement innovation variance
# TOPICS wind estimator_wind

View File

@@ -74,10 +74,11 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m
- [VehicleRatesSetpoint](VehicleRatesSetpoint.md)
- [VehicleStatus](VehicleStatus.md) — Encodes the system state of the vehicle published by commander
- [VtolVehicleStatus](VtolVehicleStatus.md) — VEHICLE_VTOL_STATE, should match 1:1 MAVLinks's MAV_VTOL_STATE
- [Wind](Wind.md) — Wind estimate (from EKF2)
## Unversioned Messages
- [ActionRequest](ActionRequest.md)
- [ActionRequest](ActionRequest.md) — Action request for the vehicle's main state
- [ActuatorArmed](ActuatorArmed.md)
- [ActuatorControlsStatus](ActuatorControlsStatus.md)
- [ActuatorOutputs](ActuatorOutputs.md)
@@ -85,7 +86,7 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m
- [ActuatorTest](ActuatorTest.md)
- [AdcReport](AdcReport.md)
- [Airspeed](Airspeed.md) — Airspeed data from sensors
- [AirspeedWind](AirspeedWind.md)
- [AirspeedWind](AirspeedWind.md) — Wind estimate (from airspeed_selector)
- [AutotuneAttitudeControlStatus](AutotuneAttitudeControlStatus.md)
- [BatteryInfo](BatteryInfo.md) — Battery information
- [ButtonEvent](ButtonEvent.md)
@@ -187,6 +188,7 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m
- [NavigatorMissionItem](NavigatorMissionItem.md)
- [NavigatorStatus](NavigatorStatus.md) — Current status of a Navigator mode
The possible values of nav_state are defined in the VehicleStatus msg.
- [NeuralControl](NeuralControl.md) — Neural control
- [NormalizedUnsignedSetpoint](NormalizedUnsignedSetpoint.md)
- [ObstacleDistance](ObstacleDistance.md) — Obstacle distances in front of the sensor.
- [OffboardControlMode](OffboardControlMode.md) — Off-board control mode
@@ -296,7 +298,6 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m
- [VehicleTorqueSetpoint](VehicleTorqueSetpoint.md)
- [VelocityLimits](VelocityLimits.md) — Velocity and yaw rate limits for a multicopter position slow mode only
- [WheelEncoders](WheelEncoders.md)
- [Wind](Wind.md)
- [YawEstimatorStatus](YawEstimatorStatus.md)
- [AirspeedValidatedV0](AirspeedValidatedV0.md)
- [ArmingCheckReplyV0](ArmingCheckReplyV0.md)
@@ -305,4 +306,6 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m
Events interface
- [HomePositionV0](HomePositionV0.md) — GPS home position in WGS84 coordinates.
- [VehicleAttitudeSetpointV0](VehicleAttitudeSetpointV0.md)
- [VehicleLocalPositionV0](VehicleLocalPositionV0.md) — Fused local position in NED.
The coordinate system origin is the vehicle position at the time when the EKF2-module was started.
- [VehicleStatusV0](VehicleStatusV0.md) — Encodes the system state of the vehicle published by commander