Compare commits

..

3 Commits

Author SHA1 Message Date
Balduin 4bbaff0131 fix(sensor_airspeed_sim): match SimulatorMavlink rounding 2026-04-09 16:14:15 +02:00
Balduin 1762c2db0b feat(sensor_airspeed_sim): Implement off, stuck, and wrong airspeed failure
- wrong and off equal to simulator_mavlink implementation
     - but wrong is over timescale of 10s rather than 1s by default to
       make it harder for innovation check to flag (closer to icing)
 - stuck will just keep the last value before injecting the failure
2026-04-08 16:38:12 +02:00
Balduin 06556f4828 refactor(sensor_airspeed_sim): remove previous airspeed failure implementation 2026-04-08 16:02:02 +02:00
71 changed files with 508 additions and 1860 deletions
@@ -1,21 +0,0 @@
name: Build Gazebo Classic SITL
description: Build PX4 firmware and Gazebo Classic plugins with ccache stats
runs:
using: composite
steps:
- name: Build - PX4 Firmware (SITL)
shell: bash
run: make px4_sitl_default
- name: Cache - Stats after PX4 Firmware
shell: bash
run: ccache -s
- name: Build - Gazebo Classic Plugins
shell: bash
run: make px4_sitl_default sitl_gazebo-classic
- name: Cache - Stats after Gazebo Plugins
shell: bash
run: ccache -s
-22
View File
@@ -1,22 +0,0 @@
name: Save ccache
description: Print ccache stats and save to cache
inputs:
cache-primary-key:
description: Primary cache key from setup-ccache output
required: true
runs:
using: composite
steps:
- name: Cache - Stats
if: always()
shell: bash
run: ccache -s
- name: Cache - Save ccache
if: always()
uses: actions/cache/save@v4
with:
path: ~/.ccache
key: ${{ inputs.cache-primary-key }}
-56
View File
@@ -1,56 +0,0 @@
name: Setup ccache
description: Restore ccache from cache and configure ccache.conf
inputs:
cache-key-prefix:
description: Cache key prefix (e.g. ccache-sitl)
required: true
max-size:
description: Max ccache size (e.g. 300M)
required: false
default: '300M'
base-dir:
description: ccache base_dir value
required: false
default: '${GITHUB_WORKSPACE}'
install-ccache:
description: Install ccache via apt before configuring
required: false
default: 'false'
outputs:
cache-primary-key:
description: Primary cache key (pass to save-ccache)
value: ${{ steps.restore.outputs.cache-primary-key }}
runs:
using: composite
steps:
- name: Cache - Install ccache
if: inputs.install-ccache == 'true'
shell: bash
run: apt-get update && apt-get install -y ccache
- name: Cache - Restore ccache
id: restore
uses: actions/cache/restore@v4
with:
path: ~/.ccache
key: ${{ inputs.cache-key-prefix }}-${{ github.ref_name }}-${{ github.sha }}
restore-keys: |
${{ inputs.cache-key-prefix }}-${{ github.ref_name }}-
${{ inputs.cache-key-prefix }}-${{ github.base_ref || 'main' }}-
${{ inputs.cache-key-prefix }}-
- name: Cache - Configure ccache
shell: bash
run: |
mkdir -p ~/.ccache
echo "base_dir = ${{ inputs.base-dir }}" > ~/.ccache/ccache.conf
echo "compression = true" >> ~/.ccache/ccache.conf
echo "compression_level = 6" >> ~/.ccache/ccache.conf
echo "max_size = ${{ inputs.max-size }}" >> ~/.ccache/ccache.conf
echo "hash_dir = false" >> ~/.ccache/ccache.conf
echo "compiler_check = content" >> ~/.ccache/ccache.conf
ccache -s
ccache -z
+10 -16
View File
@@ -98,10 +98,6 @@ jobs:
fetch-depth: 0
fetch-tags: true
- name: Use AWS regional apt mirror
if: startsWith(runner.name, 'runs-on--')
run: ./Tools/ci/use_aws_apt_mirror.sh
- name: Cache apt packages
uses: actions/cache@v4
with:
@@ -130,10 +126,10 @@ jobs:
fail-fast: false
matrix:
include:
- { image: sih, repo: px4-sitl, target: sih, arch: amd64, runner: x64, platform: "linux/amd64", dockerfile: Dockerfile.sih }
- { image: sih, repo: px4-sitl, target: sih, arch: arm64, runner: arm64, platform: "linux/arm64", dockerfile: Dockerfile.sih }
- { image: gazebo, repo: px4-sitl-gazebo, target: default, arch: amd64, runner: x64, platform: "linux/amd64", dockerfile: Dockerfile.gazebo }
- { image: gazebo, repo: px4-sitl-gazebo, target: default, arch: arm64, runner: arm64, platform: "linux/arm64", dockerfile: Dockerfile.gazebo }
- { image: sih, target: sih, arch: amd64, runner: x64, platform: "linux/amd64", dockerfile: Dockerfile.sih }
- { image: sih, target: sih, arch: arm64, runner: arm64, platform: "linux/arm64", dockerfile: Dockerfile.sih }
- { image: gazebo, target: default, arch: amd64, runner: x64, platform: "linux/amd64", dockerfile: Dockerfile.gazebo }
- { image: gazebo, target: default, arch: arm64, runner: arm64, platform: "linux/arm64", dockerfile: Dockerfile.gazebo }
steps:
- uses: runs-on/action@v2
- uses: actions/checkout@v4
@@ -168,10 +164,10 @@ jobs:
context: docker-context
file: Tools/packaging/${{ matrix.dockerfile }}
tags: |
px4io/${{ matrix.repo }}:${{ needs.setup.outputs.px4_version }}-${{ matrix.arch }}
px4io/${{ matrix.repo }}:latest-${{ matrix.arch }}
ghcr.io/px4/${{ matrix.repo }}:${{ needs.setup.outputs.px4_version }}-${{ matrix.arch }}
ghcr.io/px4/${{ matrix.repo }}:latest-${{ matrix.arch }}
px4io/px4-sitl-${{ matrix.image }}:${{ needs.setup.outputs.px4_version }}-${{ matrix.arch }}
px4io/px4-sitl-${{ matrix.image }}:latest-${{ matrix.arch }}
ghcr.io/px4/px4-sitl-${{ matrix.image }}:${{ needs.setup.outputs.px4_version }}-${{ matrix.arch }}
ghcr.io/px4/px4-sitl-${{ matrix.image }}:latest-${{ matrix.arch }}
platforms: ${{ matrix.platform }}
load: false
push: ${{ needs.setup.outputs.should_push == 'true' }}
@@ -189,9 +185,7 @@ jobs:
runs-on: [runs-on,"runner=1cpu-linux-x64","image=ubuntu24-full-x64","run-id=${{ github.run_id }}",extras=s3-cache,spot=false]
strategy:
matrix:
include:
- { image: sih, repo: px4-sitl }
- { image: gazebo, repo: px4-sitl-gazebo }
image: [sih, gazebo]
steps:
- uses: runs-on/action@v2
@@ -205,7 +199,7 @@ jobs:
VERSION="${{ needs.setup.outputs.px4_version }}"
for REGISTRY in px4io ghcr.io/px4; do
IMAGE="${REGISTRY}/${{ matrix.repo }}"
IMAGE="${REGISTRY}/px4-sitl-${{ matrix.image }}"
for TAG in ${VERSION} latest; do
docker manifest create ${IMAGE}:${TAG} \
-4
View File
@@ -49,10 +49,6 @@ jobs:
- uses: actions/checkout@v4
- name: Use AWS regional apt mirror
if: startsWith(runner.name, 'runs-on--')
run: ./Tools/ci/use_aws_apt_mirror.sh
- name: Install Deps, Build, and Make Quick Check
run: |
# we need to install dependencies and build on the same step
+19 -30
View File
@@ -24,11 +24,6 @@ on:
description: 'Container tag (e.g. v1.16.0)'
required: true
type: string
build_ref:
description: 'Git ref to build from (branch, tag, or SHA). Leave empty to build from the dispatch ref.'
required: false
type: string
default: ''
deploy_to_registry:
description: 'Whether to push built images to the registry'
required: false
@@ -50,10 +45,9 @@ jobs:
meta_tags: ${{ steps.meta.outputs.tags }}
meta_labels: ${{ steps.meta.outputs.labels }}
steps:
- uses: runs-on/action@v2
- uses: actions/checkout@v5
- uses: runs-on/action@v1
- uses: actions/checkout@v4
with:
ref: ${{ github.event.inputs.build_ref || github.ref }}
fetch-tags: true
submodules: false
fetch-depth: 0
@@ -70,7 +64,7 @@ jobs:
- name: Extract metadata (tags, labels) for Docker
id: meta
uses: docker/metadata-action@v6
uses: docker/metadata-action@v5
with:
images: |
ghcr.io/PX4/px4-dev
@@ -95,23 +89,22 @@ jobs:
runner: x64
runs-on: [runs-on,"runner=4cpu-linux-${{ matrix.runner }}","image=ubuntu24-full-${{ matrix.runner }}","run-id=${{ github.run_id }}",extras=s3-cache,spot=false]
steps:
- uses: runs-on/action@v2
- uses: actions/checkout@v5
- uses: runs-on/action@v1
- uses: actions/checkout@v4
with:
ref: ${{ github.event.inputs.build_ref || github.ref }}
fetch-tags: true
submodules: false
fetch-depth: 0
- name: Login to Docker Hub
uses: docker/login-action@v4
uses: docker/login-action@v3
if: ${{ startsWith(github.ref, 'refs/tags/') || (github.event_name == 'workflow_dispatch' && github.event.inputs.deploy_to_registry) }}
with:
username: ${{ secrets.DOCKERHUB_USERNAME }}
password: ${{ secrets.DOCKERHUB_TOKEN }}
- name: Login to GitHub Container Registry
uses: docker/login-action@v4
uses: docker/login-action@v3
if: ${{ startsWith(github.ref, 'refs/tags/') || (github.event_name == 'workflow_dispatch' && github.event.inputs.deploy_to_registry) }}
with:
registry: ghcr.io
@@ -119,13 +112,13 @@ jobs:
password: ${{ secrets.GITHUB_TOKEN }}
- name: Set up Docker Buildx
uses: docker/setup-buildx-action@v4
uses: docker/setup-buildx-action@v3
with:
driver: docker-container
platforms: ${{ matrix.platform }}
- name: Build and Load Container Image
uses: docker/build-push-action@v7
uses: docker/build-push-action@v6
id: docker
with:
context: Tools/setup
@@ -138,7 +131,7 @@ jobs:
push: ${{ startsWith(github.ref, 'refs/tags/') || (github.event_name == 'workflow_dispatch' && github.event.inputs.deploy_to_registry) }}
provenance: false
cache-from: type=gha,scope=${{ matrix.arch }}
cache-to: type=gha,mode=max,scope=${{ matrix.arch }},ignore-error=true
cache-to: type=gha,mode=max,scope=${{ matrix.arch }}
deploy:
name: Deploy To Registry
@@ -147,27 +140,23 @@ jobs:
packages: write
runs-on: [runs-on,"runner=4cpu-linux-x64","image=ubuntu24-full-x64","run-id=${{ github.run_id }}",extras=s3-cache,spot=false]
needs: [build, setup]
if: |
!cancelled() &&
needs.setup.result == 'success' &&
(startsWith(github.ref, 'refs/tags/') || (github.event_name == 'workflow_dispatch' && github.event.inputs.deploy_to_registry == 'true'))
if: ${{ startsWith(github.ref, 'refs/tags/') || (github.event_name == 'workflow_dispatch' && github.event.inputs.deploy_to_registry) }}
steps:
- uses: runs-on/action@v2
- uses: actions/checkout@v5
- uses: runs-on/action@v1
- uses: actions/checkout@v4
with:
ref: ${{ github.event.inputs.build_ref || github.ref }}
fetch-tags: true
submodules: false
fetch-depth: 0
- name: Login to Docker Hub
uses: docker/login-action@v4
uses: docker/login-action@v3
with:
username: ${{ secrets.DOCKERHUB_USERNAME }}
password: ${{ secrets.DOCKERHUB_TOKEN }}
- name: Login to GitHub Container Registry
uses: docker/login-action@v4
uses: docker/login-action@v3
with:
registry: ghcr.io
username: ${{ github.actor }}
@@ -175,10 +164,10 @@ jobs:
- name: Verify Images Exist Before Creating Manifest
run: |
docker manifest inspect px4io/px4-dev:${{ needs.setup.outputs.px4_version }}-arm64
docker manifest inspect px4io/px4-dev:${{ needs.setup.outputs.px4_version }}-amd64
docker manifest inspect ghcr.io/px4/px4-dev:${{ needs.setup.outputs.px4_version }}-arm64
docker manifest inspect ghcr.io/px4/px4-dev:${{ needs.setup.outputs.px4_version }}-amd64
docker manifest inspect px4io/px4-dev:${{ needs.setup.outputs.px4_version }}-arm64 || echo "⚠️ Warning: No ARM64 image found!"
docker manifest inspect px4io/px4-dev:${{ needs.setup.outputs.px4_version }}-amd64 || echo "⚠️ Warning: No AMD64 image found!"
docker manifest inspect ghcr.io/px4/px4-dev:${{ needs.setup.outputs.px4_version }}-arm64 || echo "⚠️ Warning: No ARM64 image found!"
docker manifest inspect ghcr.io/px4/px4-dev:${{ needs.setup.outputs.px4_version }}-amd64 || echo "⚠️ Warning: No AMD64 image found!"
- name: Create and Push Multi-Arch Manifest for Docker Hub
run: |
+2 -4
View File
@@ -89,9 +89,7 @@ jobs:
. /opt/ros/galactic/setup.bash
mkdir -p /opt/px4_ws/src
cd /opt/px4_ws/src
# On a PR, target the branch we're merging into (main or release/X.Y).
# On a direct push, fall back to the branch we're running on.
BRANCH="${GITHUB_BASE_REF:-$GITHUB_REF_NAME}"
BRANCH="${GITHUB_HEAD_REF:-$GITHUB_REF_NAME}"
REPO_URL="https://github.com/Auterion/px4-ros2-interface-lib.git"
if git ls-remote --heads "$REPO_URL" "$BRANCH" | grep -q "$BRANCH"; then
echo "Cloning px4-ros2-interface-lib with matching branch: $BRANCH"
@@ -132,7 +130,7 @@ jobs:
run: |
. /opt/px4_ws/install/setup.bash
/opt/Micro-XRCE-DDS-Agent/build/MicroXRCEAgent udp4 localhost -p 8888 -v 0 &
test/ros_test_runner.py --verbose --model iris --force-color
test/ros_test_runner.py --verbose --model iris --upload --force-color
timeout-minutes: 45
- name: Upload failed logs
+2 -24
View File
@@ -173,35 +173,13 @@ set(config_module_list)
set(config_kernel_list)
# Find Python
#
# Force FindPython3 to prefer the interpreter on PATH (and any activated
# virtualenv/conda/pyenv environment) so downstream tooling runs under
# the same Python the developer invoked the build with. On Linux these
# are already the CMake defaults; the settings exist to normalize
# behavior on macOS and Windows:
#
# - FIND_FRAMEWORK=LAST prevents FindPython3 from preferring a macOS
# Python.framework install (e.g. Homebrew's
# /opt/homebrew/Frameworks/Python.framework/...) over a pyenv shim
# or venv on PATH, which would otherwise pick an interpreter that
# lacks PX4's Python deps (kconfiglib, empy, jinja2, etc.).
# - FIND_REGISTRY=NEVER skips the Windows registry lookup for the
# same reason.
# - FIND_STRATEGY and FIND_VIRTUALENV are set explicitly to make the
# intent obvious and insulate us from future default changes.
set(Python3_FIND_STRATEGY LOCATION)
set(Python3_FIND_VIRTUALENV FIRST)
set(Python3_FIND_FRAMEWORK LAST)
set(Python3_FIND_REGISTRY NEVER)
find_package(Python3 COMPONENTS Interpreter)
find_package(PythonInterp 3)
# We have a custom error message to tell users how to install python3.
if(NOT Python3_Interpreter_FOUND)
if(NOT PYTHONINTERP_FOUND)
message(FATAL_ERROR "Python 3 not found. Please install Python 3:\n"
" Ubuntu: sudo apt install python3 python3-dev python3-pip\n"
" macOS: brew install python")
endif()
# Alias to the legacy variable so downstream CMakeLists keep working.
set(PYTHON_EXECUTABLE ${Python3_EXECUTABLE})
option(PYTHON_COVERAGE "Python code coverage" OFF)
if(PYTHON_COVERAGE)
+20 -57
View File
@@ -2,82 +2,45 @@
## Our Pledge
We as members, contributors, and leaders pledge to make participation in our community a harassment-free experience for everyone, regardless of age, body size, visible or invisible disability, ethnicity, sex characteristics, gender identity and expression, level of experience, education, socio-economic status, nationality, personal appearance, race, caste, color, religion, or sexual identity and orientation.
We pledge to act and interact in ways that contribute to an open, welcoming, diverse, inclusive, and healthy community.
In the interest of fostering an open and welcoming environment, we as contributors and maintainers pledge to making participation in our project and our community a harassment-free experience for everyone, regardless of age, body size, disability, ethnicity, gender identity and expression, level of experience, nationality, personal appearance, race, religion, or sexual identity and orientation.
## Our Standards
Examples of behavior that contributes to a positive environment for our community include:
Examples of behavior that contributes to creating a positive environment include:
* Demonstrating empathy and kindness toward other people
* Being respectful of differing opinions, viewpoints, and experiences
* Giving and gracefully accepting constructive feedback
* Accepting responsibility and apologizing to those affected by our mistakes, and learning from the experience
* Focusing on what is best not just for us as individuals, but for the overall community
* Using welcoming and inclusive language
* Being respectful of differing viewpoints and experiences
* Gracefully accepting constructive criticism
* Focusing on what is best for the community
* Showing empathy towards other community members
Examples of unacceptable behavior include:
Examples of unacceptable behavior by participants include:
* The use of sexualized language or imagery, and sexual attention or advances of any kind
* Trolling, insulting or derogatory comments, and personal or political attacks
* The use of sexualized language or imagery and unwelcome sexual attention or advances
* Trolling, insulting/derogatory comments, and personal or political attacks
* Public or private harassment
* Publishing others' private information, such as a physical or email address, without their explicit permission
* Publishing others' private information, such as a physical or electronic address, without explicit permission
* Other conduct which could reasonably be considered inappropriate in a professional setting
## Enforcement Responsibilities
## Our Responsibilities
Community leaders are responsible for clarifying and enforcing our standards of acceptable behavior and will take appropriate and fair corrective action in response to any behavior that they deem inappropriate, threatening, offensive, or harmful.
Project maintainers are responsible for clarifying the standards of acceptable behavior and are expected to take appropriate and fair corrective action in response to any instances of unacceptable behavior.
Community leaders have the right and responsibility to remove, edit, or reject comments, commits, code, wiki edits, issues, and other contributions that are not aligned to this Code of Conduct, and will communicate reasons for moderation decisions when appropriate.
Project maintainers have the right and responsibility to remove, edit, or reject comments, commits, code, wiki edits, issues, and other contributions that are not aligned to this Code of Conduct, or to ban temporarily or permanently any contributor for other behaviors that they deem inappropriate, threatening, offensive, or harmful.
## Scope
This Code of Conduct applies within all community spaces, and also applies when an individual is officially representing the community in public spaces. Examples of representing our community include using an official e-mail address, posting via an official social media account, or acting as an appointed representative at an online or offline event.
This Code of Conduct applies both within project spaces and in public spaces when an individual is representing the project or its community. Examples of representing a project or community include using an official project e-mail address, posting via an official social media account, or acting as an appointed representative at an online or offline event. Representation of a project may be further defined and clarified by project maintainers.
## Enforcement
Instances of abusive, harassing, or otherwise unacceptable behavior may be reported to the community leaders responsible for enforcement at coc@dronecode.org. All complaints will be reviewed and investigated promptly and fairly.
Instances of abusive, harassing, or otherwise unacceptable behavior may be reported by contacting the project team at lorenz@px4.io. The project team will review and investigate all complaints, and will respond in a way that it deems appropriate to the circumstances. The project team is obligated to maintain confidentiality with regard to the reporter of an incident. Further details of specific enforcement policies may be posted separately.
All community leaders are obligated to respect the privacy and security of the reporter of any incident.
## Enforcement Guidelines
Community leaders will follow these Community Impact Guidelines in determining the consequences for any action they deem in violation of this Code of Conduct:
### 1. Correction
**Community Impact**: Use of inappropriate language or other behavior deemed unprofessional or unwelcome in the community.
**Consequence**: A private, written warning from community leaders, providing clarity around the nature of the violation and an explanation of why the behavior was inappropriate. A public apology may be requested.
### 2. Warning
**Community Impact**: A violation through a single incident or series of actions.
**Consequence**: A warning with consequences for continued behavior. No interaction with the people involved, including unsolicited interaction with those enforcing the Code of Conduct, for a specified period of time. This includes avoiding interactions in community spaces as well as external channels like social media. Violating these terms may lead to a temporary or permanent ban.
### 3. Temporary Ban
**Community Impact**: A serious violation of community standards, including sustained inappropriate behavior.
**Consequence**: A temporary ban from any sort of interaction or public communication with the community for a specified period of time. No public or private interaction with the people involved, including unsolicited interaction with those enforcing the Code of Conduct, is allowed during this period. Violating these terms may lead to a permanent ban.
### 4. Permanent Ban
**Community Impact**: Demonstrating a pattern of violation of community standards, including sustained inappropriate behavior, harassment of an individual, or aggression toward or disparagement of classes of individuals.
**Consequence**: A permanent ban from any sort of public interaction within the community.
Project maintainers who do not follow or enforce the Code of Conduct in good faith may face temporary or permanent repercussions as determined by other members of the project's leadership.
## Attribution
This Code of Conduct is adapted from the [Contributor Covenant][homepage], version 2.1, available at [https://www.contributor-covenant.org/version/2/1/code_of_conduct.html][v2.1].
This Code of Conduct is adapted from the [Contributor Covenant][homepage], version 1.4, available at [http://contributor-covenant.org/version/1/4][version]
Community Impact Guidelines were inspired by [Mozilla's code of conduct enforcement ladder][Mozilla CoC].
For answers to common questions about this code of conduct, see the FAQ at [https://www.contributor-covenant.org/faq][FAQ]. Translations are available at [https://www.contributor-covenant.org/translations][translations].
[homepage]: https://www.contributor-covenant.org
[v2.1]: https://www.contributor-covenant.org/version/2/1/code_of_conduct.html
[Mozilla CoC]: https://github.com/mozilla/diversity
[FAQ]: https://www.contributor-covenant.org/faq
[translations]: https://www.contributor-covenant.org/translations
[homepage]: http://contributor-covenant.org
[version]: http://contributor-covenant.org/version/1/4/
+2 -13
View File
@@ -1,11 +1,9 @@
Maintainers
===========
PX4 is maintained by a group of contributors trusted to steward the project. All maintainers listed below are members of the @PX4/dev-team, have write access, and participate in maintainer decisions. We recognize two types: **Code Owners**, responsible for specific components, and **Reviewers**, who help across the project without a fixed component.
See [the documentation on Maintainers](https://docs.px4.io/main/en/contribute/maintainers.html) to learn about the role of the maintainers and the process to become one.
See [the documentation on Maintainers](https://docs.px4.io/main/en/contribute/maintainers) to learn about the role of the maintainers and the process to become one.
**Code Owners**
**Active Maintainers**
| Name | Sector | GitHub | Chat | email
|-------------------------|--------|--------|------|----------------
@@ -25,15 +23,6 @@ See [the documentation on Maintainers](https://docs.px4.io/main/en/contribute/ma
| Jacob Dahl | Simulation | [@dakejahl](https://github.com/dakejahl) | dakejahl | <dahl.jakejacob@gmail.com>
**Reviewers**
Reviewers help maintain PX4 across the project without ownership of a specific component.
| Name | GitHub | Chat | email
|------|--------|------|----------------------
| _No reviewers yet._ | | |
**Documentation Maintainers**
| Name | GitHub | Chat | email
+4 -25
View File
@@ -9,16 +9,11 @@
</p>
<p align="center">
<a href="https://github.com/PX4/PX4-Autopilot/releases"><img src="https://img.shields.io/github/release/PX4/PX4-Autopilot.svg" alt="Release"></a>
<a href="https://zenodo.org/badge/latestdoi/22634/PX4/PX4-Autopilot"><img src="https://zenodo.org/badge/22634/PX4/PX4-Autopilot.svg" alt="DOI"></a>
<a href="https://discord.gg/dronecode"><img src="https://img.shields.io/discord/1022170275984457759?label=discord&logo=discord&logoColor=white&color=5865F2" alt="Discord"></a>
</p>
<p align="center">
<a href="https://github.com/PX4/PX4-Autopilot/releases"><img src="https://img.shields.io/github/release/PX4/PX4-Autopilot.svg" alt="Releases"></a>
<a href="https://www.bestpractices.dev/projects/6520"><img src="https://www.bestpractices.dev/projects/6520/badge" alt="OpenSSF Best Practices"></a>
<a href="https://insights.linuxfoundation.org/project/px4"><img src="https://insights.linuxfoundation.org/api/badge/health-score?project=px4" alt="LFX Health Score"></a>
<a href="https://insights.linuxfoundation.org/project/px4"><img src="https://insights.linuxfoundation.org/api/badge/contributors?project=px4" alt="LFX Contributors"></a>
<a href="https://insights.linuxfoundation.org/project/px4"><img src="https://insights.linuxfoundation.org/api/badge/active-contributors?project=px4" alt="LFX Active Contributors"></a>
<a href="https://zenodo.org/badge/latestdoi/22634/PX4/PX4-Autopilot"><img src="https://zenodo.org/badge/22634/PX4/PX4-Autopilot.svg" alt="DOI"></a>
<a href="https://github.com/PX4/PX4-Autopilot/actions/workflows/build_all_targets.yml"><img src="https://github.com/PX4/PX4-Autopilot/actions/workflows/build_all_targets.yml/badge.svg?branch=main" alt="Build Targets"></a>
<a href="https://discord.gg/dronecode"><img src="https://discordapp.com/api/guilds/1022170275984457759/widget.png?style=shield" alt="Discord"></a>
</p>
---
@@ -104,22 +99,6 @@ make px4_sitl
We welcome contributions of all kinds — bug reports, documentation, new features, and code reviews. Please read the [Contribution Guide](https://docs.px4.io/main/en/contribute/) to get started.
## Citation
If you use PX4 in academic work, please cite it. BibTeX:
```bibtex
@software{px4_autopilot,
author = {Meier, Lorenz and {The PX4 Contributors}},
title = {{PX4 Autopilot}},
publisher = {Zenodo},
doi = {10.5281/zenodo.595432},
url = {https://px4.io}
}
```
The DOI above is a Zenodo concept DOI that always resolves to the latest release. For a version-pinned citation, see the [Zenodo record](https://doi.org/10.5281/zenodo.595432) or our [`CITATION.cff`](CITATION.cff).
## Governance
The PX4 Autopilot project is hosted by the [Dronecode Foundation](https://www.dronecode.org/), a [Linux Foundation](https://www.linuxfoundation.org/) Collaborative Project. Dronecode holds all PX4 trademarks and serves as the project's legal guardian, ensuring vendor-neutral stewardship — no single company owns the name or controls the roadmap. The source code is licensed under the [BSD 3-Clause](LICENSE) license, so you are free to use, modify, and distribute it in your own projects.
@@ -14,7 +14,6 @@
param set UAVCAN_ENABLE 0
param set-default CA_AIRFRAME 1
param set-default CA_ROTOR_COUNT 1
param set-default CA_ROTOR0_PX 0.3
@@ -39,6 +38,7 @@ param set-default SYS_HITL 2
# - without real battery
param set-default CBRK_SUPPLY_CHK 894281
param set SIH_T_MAX 6
param set SIH_MASS 0.3
param set SIH_IXX 0.00402
param set SIH_IYY 0.0144
@@ -48,21 +48,3 @@ param set SIH_KDV 0.2
param set SIH_VEHICLE_TYPE 1 # sih as fixed wing
param set RWTO_TKOFF 1 # enable takeoff from runway (as opposed to launched)
# pusher propeller model with advance ratio, model from UIUC APC 8x6"
param set SIH_F_T_MAX 6
param set SIH_F_Q_MAX 0.03
# if SIH_F_CT0 > 0, SIH_F_T_MAX and SIH_F_Q_MAX will be overridden
param set SIH_F_CT0 0.131
param set SIH_F_CT1 0.004
param set SIH_F_CT2 -0.146
param set SIH_F_CP0 0.0777
param set SIH_F_CP1 0.0498
param set SIH_F_CP2 -0.11
param set SIH_F_DIA_INCH 8
param set SIH_F_RPM_MAX 9000
param set-default FW_AIRSPD_MIN 7
param set-default FW_AIRSPD_TRIM 10
param set-default FW_AIRSPD_MAX 12
param set-default FW_PSP_OFF 0.5
@@ -28,7 +28,6 @@ param set-default VT_FW_DIFTHR_EN 1
param set-default VT_FW_DIFTHR_S_Y 0.3
param set-default MPC_MAN_Y_MAX 60
param set-default MC_PITCH_P 5
param set-default FW_PSP_OFF 5
param set-default CA_AIRFRAME 4
param set-default CA_ROTOR_COUNT 2
@@ -57,6 +56,7 @@ param set-default HIL_ACT_REV 32
param set-default MAV_TYPE 19
# set SYS_HITL to 2 to start the SIH and avoid sensors startup
param set-default SYS_HITL 2
@@ -66,9 +66,8 @@ param set-default CBRK_SUPPLY_CHK 894281
param set-default SENS_DPRES_OFF 0.001
# tailsitter is equipped with two forward propellers
param set SIH_F_T_MAX 2
param set SIH_F_Q_MAX 0.0165
param set SIH_T_MAX 2.0
param set SIH_Q_MAX 0.0165
param set SIH_MASS 0.2
# IXX and IZZ are inverted from the thesis as the body frame is pitched by 90 deg
param set SIH_IXX 0.00354
@@ -78,19 +77,6 @@ param set SIH_IXZ 0
param set SIH_KDV 0.2
param set SIH_L_ROLL 0.145
# propeller diameter, rpm, and coeffs coming from the thesis
# Modeling and control of a flying wing tailsitter unmanned aerial vehicle."
# Chiappinelli, Romain, supervised by Nahon, Meyer, McGill University, Masters thesis, 2018.
# if SIH_F_CT0 > 0, SIH_F_T_MAX and SIH_F_Q_MAX will be overridden
param set SIH_F_CT0 0.1342
param set SIH_F_CT1 -0.1196
param set SIH_F_CT2 -0.1281
param set SIH_F_CP0 0.0522
param set SIH_F_CP1 -0.0146
param set SIH_F_CP2 -0.0602
param set SIH_F_DIA_INCH 5
param set SIH_F_RPM_MAX 14000
# sih as tailsitter
param set SIH_VEHICLE_TYPE 2
@@ -56,7 +56,6 @@ param set-default CA_SV_CS2_TYPE 4 # rudder
param set-default FW_AIRSPD_MIN 7
param set-default FW_AIRSPD_TRIM 10
param set-default FW_AIRSPD_MAX 12
param set-default VT_FWD_THRUST_EN 1
param set-default HIL_ACT_FUNC1 101
param set-default HIL_ACT_FUNC2 102
@@ -78,7 +77,6 @@ param set-default CBRK_SUPPLY_CHK 894281
param set-default SENS_DPRES_OFF 0.001
# quadrotor propellers
param set SIH_T_MAX 2.0
param set SIH_Q_MAX 0.0165
param set SIH_MASS 0.2
@@ -90,18 +88,5 @@ param set SIH_IXZ 0
param set SIH_KDV 0.2
param set SIH_L_ROLL 0.2
# pusher propeller model with advance ratio, model from UIUC APC 8x6"
param set SIH_F_T_MAX 6
param set SIH_F_Q_MAX 0.03
# if SIH_F_CT0 > 0, SIH_F_T_MAX and SIH_F_Q_MAX will be overridden
param set SIH_F_CT0 0.131
param set SIH_F_CT1 0.004
param set SIH_F_CT2 -0.146
param set SIH_F_CP0 0.0777
param set SIH_F_CP1 0.0498
param set SIH_F_CP2 -0.11
param set SIH_F_DIA_INCH 8
param set SIH_F_RPM_MAX 9000
# sih as standard vtol
param set SIH_VEHICLE_TYPE 3
@@ -1,49 +0,0 @@
#!/bin/sh
#
# @name SIH Hexacopter X
#
# @type Simulation
# @class Copter
#
# @maintainer Romain Chiappinelli <romain.chiap@gmail.com>
#
# @board px4_fmu-v2 exclude
#
. ${R}etc/init.d/rc.mc_defaults
param set UAVCAN_ENABLE 0
# set SYS_HITL to 2 to start the SIH and avoid sensors startup
param set SYS_HITL 2
# disable some checks to allow to fly:
# - without real battery
param set-default CBRK_SUPPLY_CHK 894281
param set SIH_VEHICLE_TYPE 4
# Symmetric hexacopter X clockwise motor numbering
param set-default CA_ROTOR_COUNT 6
param set-default CA_ROTOR0_PX 0.866
param set-default CA_ROTOR0_PY 0.5
param set-default CA_ROTOR1_PX 0
param set-default CA_ROTOR1_PY 1
param set-default CA_ROTOR1_KM -0.05
param set-default CA_ROTOR2_PX -0.866
param set-default CA_ROTOR2_PY 0.5
param set-default CA_ROTOR3_PX -0.866
param set-default CA_ROTOR3_PY -0.5
param set-default CA_ROTOR3_KM -0.05
param set-default CA_ROTOR4_PX 0
param set-default CA_ROTOR4_PY -1
param set-default CA_ROTOR5_PX 0.866
param set-default CA_ROTOR5_PY -0.5
param set-default CA_ROTOR5_KM -0.05
param set-default HIL_ACT_FUNC1 101
param set-default HIL_ACT_FUNC2 102
param set-default HIL_ACT_FUNC3 103
param set-default HIL_ACT_FUNC4 104
param set-default HIL_ACT_FUNC5 105
param set-default HIL_ACT_FUNC6 106
@@ -49,7 +49,6 @@ if(CONFIG_MODULES_SIMULATION_PWM_OUT_SIM)
1101_rc_plane_sih.hil
1102_tailsitter_duo_sih.hil
1103_standard_vtol_sih.hil
1105_rc_hexa_x_sih.hil
)
if(CONFIG_MODULES_ROVER_ACKERMANN)
px4_add_romfs_files(
-147
View File
@@ -1,147 +0,0 @@
#!/usr/bin/env python3
"""
Run clang-tidy incrementally on files changed in a PR.
Usage: run-clang-tidy-pr.py <base-ref>
base-ref: e.g. origin/main
Computes the set of translation units (TUs) affected by the PR diff,
then invokes Tools/run-clang-tidy.py on that subset only.
Exits 0 silently when no C++ files were changed.
"""
import argparse
import json
import os
import subprocess
import sys
EXTENSIONS_CPP = {'.cpp', '.c'}
EXTENSIONS_HDR = {'.hpp', '.h'}
# Manual exclusions from Makefile:508
EXCLUDE_EXTRA = '|'.join([
'src/systemcmds/tests',
'src/examples',
'src/modules/gyro_fft/CMSIS_5',
'src/lib/drivers/smbus',
'src/drivers/gpio',
r'src/modules/commander/failsafe/emscripten',
r'failsafe_test\.dir',
])
def repo_root():
try:
return subprocess.check_output(
['git', 'rev-parse', '--show-toplevel'], text=True).strip()
except subprocess.CalledProcessError:
print('error: not inside a git repository', file=sys.stderr)
sys.exit(1)
def changed_files(base_ref, root):
try:
out = subprocess.check_output(
['git', 'diff', '--name-only', f'{base_ref}...HEAD',
'--', '*.cpp', '*.hpp', '*.h', '*.c'],
text=True, cwd=root).strip()
return out.splitlines() if out else []
except subprocess.CalledProcessError:
print(f'error: could not diff against "{base_ref}"'
'is the ref valid and fetched?', file=sys.stderr)
sys.exit(1)
def submodule_paths(root):
# Returns [] if .gitmodules is absent or has no paths — both valid
try:
out = subprocess.check_output(
['git', 'config', '--file', '.gitmodules',
'--get-regexp', 'path'],
text=True, cwd=root).strip()
return [line.split()[1] for line in out.splitlines()]
except subprocess.CalledProcessError:
return []
def build_exclude(root):
submodules = '|'.join(submodule_paths(root))
return f'{submodules}|{EXCLUDE_EXTRA}' if submodules else EXCLUDE_EXTRA
def load_db(build_dir):
db_path = os.path.join(build_dir, 'compile_commands.json')
if not os.path.isfile(db_path):
print(f'error: {db_path} not found', file=sys.stderr)
print('Run "make px4_sitl_default-clang" first to generate '
'the compilation database', file=sys.stderr)
sys.exit(1)
try:
with open(db_path) as f:
return json.load(f)
except json.JSONDecodeError as e:
print(f'error: compile_commands.json is malformed: {e}', file=sys.stderr)
sys.exit(1)
def find_tus(changed, db, root):
db_files = {e['file'] for e in db}
result = set()
for f in changed:
abs_path = os.path.join(root, f)
ext = os.path.splitext(f)[1]
if ext in EXTENSIONS_CPP:
if abs_path in db_files:
result.add(abs_path)
elif ext in EXTENSIONS_HDR:
hdr = os.path.basename(f)
for e in db:
try:
if hdr in open(e['file']).read():
result.add(e['file'])
except OSError:
pass # file deleted in PR — skip
return sorted(result)
def main():
parser = argparse.ArgumentParser(description=__doc__,
formatter_class=argparse.RawDescriptionHelpFormatter)
parser.add_argument('base_ref',
help='Git ref to diff against, e.g. origin/main')
args = parser.parse_args()
root = repo_root()
build_dir = os.path.join(root, 'build', 'px4_sitl_default-clang')
run_tidy = os.path.join(root, 'Tools', 'run-clang-tidy.py')
if not os.path.isfile(run_tidy):
print(f'error: {run_tidy} not found', file=sys.stderr)
sys.exit(1)
changed = changed_files(args.base_ref, root)
if not changed:
print('No C++ files changed — skipping clang-tidy')
sys.exit(0)
db = load_db(build_dir)
tus = find_tus(changed, db, root)
if not tus:
print('No matching TUs in compile_commands.json — skipping clang-tidy')
sys.exit(0)
print(f'Running clang-tidy on {len(tus)} translation unit(s)')
result = subprocess.run(
[sys.executable, run_tidy,
'-header-filter=.*\\.hpp',
'-j0',
f'-exclude={build_exclude(root)}',
'-p', build_dir] + tus
)
sys.exit(result.returncode)
if __name__ == '__main__':
main()
-42
View File
@@ -1,42 +0,0 @@
#!/bin/sh
# Rewrite the container's apt sources to point at the AWS regional Ubuntu
# mirror that is local to the runs-on instance.
#
# The default archive.ubuntu.com round-robin sometimes serves out-of-sync
# index files mid-sync, breaking apt-get update with errors like:
# File has unexpected size (25378 != 25381). Mirror sync in progress?
# The Canonical-operated EC2 mirrors are region-local and sync aggressively,
# eliminating that failure mode.
#
# This script is a no-op outside runs-on, so it is safe to call from any CI
# job (forks, self-hosted runners, local docker runs, etc.) without changing
# behavior there.
#
# Usage (from a workflow step running inside the container):
# ./Tools/ci/use_aws_apt_mirror.sh
set -e
if [ -z "$RUNS_ON_AWS_REGION" ]; then
echo "use_aws_apt_mirror: not running on runs-on (RUNS_ON_AWS_REGION unset), skipping"
exit 0
fi
MIRROR="http://${RUNS_ON_AWS_REGION}.ec2.archive.ubuntu.com/ubuntu"
echo "use_aws_apt_mirror: rewriting apt sources to ${MIRROR}"
# Noble (24.04+) uses the deb822 format at /etc/apt/sources.list.d/ubuntu.sources
if [ -f /etc/apt/sources.list.d/ubuntu.sources ]; then
sed -i \
-e "s|http://archive.ubuntu.com/ubuntu|${MIRROR}|g" \
-e "s|http://security.ubuntu.com/ubuntu|${MIRROR}|g" \
/etc/apt/sources.list.d/ubuntu.sources
fi
# Jammy (22.04) and earlier use the legacy /etc/apt/sources.list
if [ -f /etc/apt/sources.list ]; then
sed -i \
-e "s|http://archive.ubuntu.com/ubuntu|${MIRROR}|g" \
-e "s|http://security.ubuntu.com/ubuntu|${MIRROR}|g" \
/etc/apt/sources.list
fi
+3 -3
View File
@@ -4,13 +4,13 @@
#
# Build:
# make px4_sitl_sih && cd build/px4_sitl_sih && cpack -G DEB && cd ../..
# docker build -f Tools/packaging/Dockerfile.sih -t px4io/px4-sitl:v1.17.0 build/px4_sitl_sih/
# docker build -f Tools/packaging/Dockerfile.sih -t px4io/px4-sitl-sih:v1.17.0 build/px4_sitl_sih/
#
# Run (Linux):
# docker run --rm -it --network host px4io/px4-sitl:v1.17.0
# docker run --rm -it --network host px4io/px4-sitl-sih:v1.17.0
#
# Run (macOS / Windows):
# docker run --rm -it -p 14550:14550/udp -p 14540:14540/udp -p 19410:19410/udp -p 8888:8888/udp px4io/px4-sitl:v1.17.0
# docker run --rm -it -p 14550:14550/udp -p 14540:14540/udp -p 19410:19410/udp -p 8888:8888/udp px4io/px4-sitl-sih:v1.17.0
FROM ubuntu:24.04 AS build
COPY px4_*.deb /tmp/
+2 -5
View File
@@ -17,12 +17,9 @@ else
PX4_PREFIX=/opt/px4
fi
# Resolve host.docker.internal to an IPv4 address. mavlink and uxrce_dds_client
# only parse IPv4, and on Docker Desktop for Windows the default `getent hosts`
# lookup can return an IPv6 ULA first, which both modules then reject.
DOCKER_HOST_IP=$(getent ahostsv4 host.docker.internal 2>/dev/null | awk '/STREAM/ {print $1; exit}')
if getent hosts host.docker.internal >/dev/null 2>&1; then
DOCKER_HOST_IP=$(getent hosts host.docker.internal | awk '{print $1}')
if [ -n "$DOCKER_HOST_IP" ]; then
# MAVLink: replace default target (127.0.0.1) with the Docker host IP
sed -i "s/mavlink start -x -u/mavlink start -x -t $DOCKER_HOST_IP -u/g" \
"$PX4_PREFIX/etc/init.d-posix/px4-rc.mavlink"
+1 -1
View File
@@ -7,7 +7,7 @@ Validates that the SIH Docker container works end-to-end with MAVSDK.
Prerequisites:
- Docker container running:
docker run --rm --network host px4io/px4-sitl:v1.17.0-alpha1
docker run --rm --network host px4io/px4-sitl-sih:v1.17.0-alpha1
- pip install mavsdk
- mavsim-viewer running (optional):
/path/to/mavsim-viewer -n 1
-1
View File
@@ -13,7 +13,6 @@ CONFIG_MODULES_NAVIGATOR=n
CONFIG_MODULES_UXRCE_DDS_CLIENT=n
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=n
CONFIG_SYSTEMCMDS_BSONDUMP=n
CONFIG_SYSTEMCMDS_I2CDETECT=y
CONFIG_SYSTEMCMDS_PERF=n
CONFIG_SYSTEMCMDS_TOPIC_LISTENER=n
CONFIG_SYSTEMCMDS_VER=n
@@ -287,8 +287,8 @@
/* AUX */
#define GPIO_LPUART4_RX (GPIO_LPUART4_RX_1 | LPUART_IOMUX) /* GPIO_B1_01 */
#define GPIO_LPUART4_TX (GPIO_LPUART4_TX_1 | LPUART_IOMUX) /* GPIO_B1_00 */
#define GPIO_LPUART4_RX (GPIO_LPUART4_RX_3 | LPUART_IOMUX) /* GPIO_B1_01 */
#define GPIO_LPUART4_TX (GPIO_LPUART4_TX_3 | LPUART_IOMUX) /* GPIO_B1_00 */
/* GPS 1 */
Binary file not shown.

Before

Width:  |  Height:  |  Size: 24 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 119 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 203 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 270 KiB

-1
View File
@@ -323,7 +323,6 @@
- [RFD900 (SiK) Telemetry Radio](telemetry/rfd900_telemetry.md)
- [ThunderFly TFSIK01 Telemetry Radio](telemetry/tfsik_telemetry.md)
- [HolyBro (SIK) Telemetry Radio](telemetry/holybro_sik_radio.md)
- [HolyBro SiK Long Range Telemetry Radio](telemetry/holybro_sik_longrange.md)
- [Telemetry Wifi](telemetry/telemetry_wifi.md)
- [ESP8266 WiFi Module](telemetry/esp8266_wifi_module.md)
- [ESP32 WiFi Module](telemetry/esp32_wifi_module.md)
+9 -111
View File
@@ -127,7 +127,7 @@ Configure the emitter type of the vehicle.
| Reboot | minValue | maxValue | increment | default | unit |
| ------- | -------- | -------- | --------- | ------- | ---- |
| &check; | 0 | 19 | | 14 | |
| &check; | 0 | 15 | | 14 | |
### ADSB_GPS_OFF_LAT (`INT32`) {#ADSB_GPS_OFF_LAT}
@@ -18498,7 +18498,7 @@ parameters.
| Reboot | minValue | maxValue | increment | default | unit |
| ------ | -------- | -------- | --------- | ------- | ---- |
| &nbsp; | 0 | 4 | | 0 | |
| &nbsp; | 0 | 3 | | 0 | |
### COM_ARMABLE (`INT32`) {#COM_ARMABLE}
@@ -23916,7 +23916,7 @@ Mode 6 is intended for use with a ground control station (not necessarily an RTK
| Reboot | minValue | maxValue | increment | default | unit |
| ------- | -------- | -------- | --------- | ------- | ---- |
| &check; | 0 | 6 | | 0 | |
| &check; | 0 | 1 | | 0 | |
### GPS_UBX_PPK (`INT32`) {#GPS_UBX_PPK}
@@ -28571,7 +28571,7 @@ MAVLink airframe type.
| Reboot | minValue | maxValue | increment | default | unit |
| ------ | -------- | -------- | --------- | ------- | ---- |
| &nbsp; | 0 | 23 | | 0 | |
| &nbsp; | 0 | 22 | | 0 | |
### MAV_USEHILGPS (`INT32`) {#MAV_USEHILGPS}
@@ -28828,7 +28828,7 @@ Heading behavior in autonomous modes.
| Reboot | minValue | maxValue | increment | default | unit |
| ------ | -------- | -------- | --------- | ------- | ---- |
| &nbsp; | 0 | 5 | | 0 | |
| &nbsp; | 0 | 4 | | 0 | |
### NAV_ACC_RAD (`FLOAT`) {#NAV_ACC_RAD}
@@ -37782,7 +37782,7 @@ TeraRanger Rangefinder (i2c).
| Reboot | minValue | maxValue | increment | default | unit |
| ------- | -------- | -------- | --------- | ------- | ---- |
| &check; | 0 | 5 | | 0 | |
| &check; | 0 | 3 | | 0 | |
### SENS_EN_VL53L0X (`INT32`) {#SENS_EN_VL53L0X}
@@ -40004,104 +40004,6 @@ Absolute value superior to 10000 will disable distance sensor
| ------ | -------- | -------- | --------- | ------- | ---- |
| &nbsp; | | | | -1.0 | m |
### SIH_F_CP0 (`FLOAT`) {#SIH_F_CP0}
Forward thruster static power coefficient.
| Reboot | minValue | maxValue | increment | default | unit |
| ------ | -------- | -------- | --------- | ------- | ---- |
| &nbsp; | 0.0 | | | 0.0 | |
### SIH_F_CP1 (`FLOAT`) {#SIH_F_CP1}
Forward thruster power coefficient 1.
CP(J) = CP0 + CP1*J + CP2*J^2
| Reboot | minValue | maxValue | increment | default | unit |
| ------ | -------- | -------- | --------- | ------- | ---- |
| &nbsp; | | | | 0.0 | |
### SIH_F_CP2 (`FLOAT`) {#SIH_F_CP2}
Forward thruster power coefficient 2.
CP(J) = CP0 + CP1*J + CP2*J^2
| Reboot | minValue | maxValue | increment | default | unit |
| ------ | -------- | -------- | --------- | ------- | ---- |
| &nbsp; | | 0.0 | | 0.0 | |
### SIH_F_CT0 (`FLOAT`) {#SIH_F_CT0}
Forward thruster static thrust coefficient.
| Reboot | minValue | maxValue | increment | default | unit |
| ------ | -------- | -------- | --------- | ------- | ---- |
| &nbsp; | 0.0 | | | 0.0 | |
### SIH_F_CT1 (`FLOAT`) {#SIH_F_CT1}
Forward thruster thrust coefficient 1.
CT(J) = CT0 + CT1*J + CT2*J^2
| Reboot | minValue | maxValue | increment | default | unit |
| ------ | -------- | -------- | --------- | ------- | ---- |
| &nbsp; | | | | 0.0 | |
### SIH_F_CT2 (`FLOAT`) {#SIH_F_CT2}
Forward thruster thrust coefficient 2.
CT(J) = CT0 + CT1*J + CT2*J^2
| Reboot | minValue | maxValue | increment | default | unit |
| ------ | -------- | -------- | --------- | ------- | ---- |
| &nbsp; | | 0.0 | | 0.0 | |
### SIH_F_DIA_INCH (`FLOAT`) {#SIH_F_DIA_INCH}
Forward thruster propeller diameter in inches.
| Reboot | minValue | maxValue | increment | default | unit |
| ------ | -------- | -------- | --------- | ------- | ---- |
| &nbsp; | 0.1 | | | 0.1 | |
### SIH_F_Q_MAX (`FLOAT`) {#SIH_F_Q_MAX}
Forward thruster max torque (Nm).
This is used for the Fixed-Wing, Tailsitter, or pusher of the Standard VTOL
if SIH_F_CP0 <= 0.
If SIH_F_CP0 > 0, propeller model with advance ratio J is used
and this parameter value is overridden at simulation startup.
| Reboot | minValue | maxValue | increment | default | unit |
| ------ | -------- | -------- | --------- | ------- | ---- |
| &nbsp; | 0.0 | | | 0.0165 | Nm |
### SIH_F_RPM_MAX (`FLOAT`) {#SIH_F_RPM_MAX}
Forward thruster max RPM.
| Reboot | minValue | maxValue | increment | default | unit |
| ------ | -------- | -------- | --------- | ------- | ---- |
| &nbsp; | 0.1 | | | 6000.0 | |
### SIH_F_T_MAX (`FLOAT`) {#SIH_F_T_MAX}
Forward thruster max thrust (N).
This is used for the Fixed-Wing, Tailsitter, or pusher of the Standard VTOL
if SIH_F_CT0 <= 0.
If SIH_F_CT0 > 0, propeller model with advance ratio J is used
and this parameter value is overridden at simulation startup.
| Reboot | minValue | maxValue | increment | default | unit |
| ------ | -------- | -------- | --------- | ------- | ---- |
| &nbsp; | 0.0 | | | 2.0 | N |
### SIH_IXX (`FLOAT`) {#SIH_IXX}
Vehicle inertia about X axis.
@@ -40276,15 +40178,13 @@ This value can be measured by weighting the quad on a scale.
### SIH_Q_MAX (`FLOAT`) {#SIH_Q_MAX}
Max multicopter propeller torque.
Max propeller torque.
This is the maximum torque delivered by one propeller
when the motor is running at full speed.
This value is usually about few percent of the maximum thrust force.
Refer to SIH_F_Q_MAX for the propeller torque for FW, Tailsitter, and VTOL pusher.
| Reboot | minValue | maxValue | increment | default | unit |
| ------ | -------- | -------- | --------- | ------- | ---- |
| &nbsp; | 0.0 | | 0.05 | 0.1 | Nm |
@@ -40301,15 +40201,13 @@ Gaussian noise added to simulated ranging beacon measurements. Set to 0 to disab
### SIH_T_MAX (`FLOAT`) {#SIH_T_MAX}
Max multicopter propeller thrust force.
Max propeller thrust force.
This is the maximum force delivered by one propeller
when the motor is running at full speed.
This value is usually about 5 times the mass of the quadrotor.
Refer to SIH_F_T_MAX for the thrust for FW, Tailsitter, and VTOL pusher.
| Reboot | minValue | maxValue | increment | default | unit |
| ------ | -------- | -------- | --------- | ------- | ---- |
| &nbsp; | 0.0 | | 0.5 | 5.0 | N |
@@ -44074,7 +43972,7 @@ Selects what type of mode is enabled, if any
| Reboot | minValue | maxValue | increment | default | unit |
| ------- | -------- | -------- | --------- | ------- | ---- |
| &check; | 0 | 3 | | 0 | |
| &check; | 0 | 2 | | 0 | |
### VOXL_ESC_PUB_BST (`INT32`) {#VOXL_ESC_PUB_BST}
-4
View File
@@ -457,10 +457,6 @@ div.frame_variant td, div.frame_variant th {
<td>SIH Quadcopter X</td>
<td>Maintainer: Romain Chiappinelli &lt;romain.chiap@gmail.com&gt;<p><code>SYS_AUTOSTART</code> = 1100</p></td>
</tr>
<tr id="copter_simulation_sih_hexacopter_x">
<td>SIH Hexacopter X</td>
<td>Maintainer: Romain Chiappinelli &lt;romain.chiap@gmail.com&gt;<p><code>SYS_AUTOSTART</code> = 1105</p></td>
</tr>
</tbody>
</table>
</div>
+3 -3
View File
@@ -7,7 +7,7 @@ const { site } = useData();
<div v-if="site.title !== 'PX4 Guide (main)'">
<div class="custom-block danger">
<p class="custom-block-title">This page may be out of date. <a href="/en/contribute/dev_call.md">See the latest version</a>.</p>
<p class="custom-block-title">This page may be out of date. <a href="https://docs.px4.io/main/en/contribute/dev_call">See the latest version</a>.</p>
</div>
</div>
@@ -15,8 +15,8 @@ The PX4 dev team and community come together to discuss any topic of interest to
## Who should attend?
- Code Owners
- Reviewers
- Core project maintainers
- Component maintainers
- Test team lead
- Dronecode members
- Community members (you!)
+1 -1
View File
@@ -20,7 +20,7 @@ We pledge to adhere to the [PX4 code of conduct](https://github.com/PX4/PX4-Auto
This section contains information about how you can meet with the community and contribute to PX4:
- [Dev Call](../contribute/dev_call.md) - Discuss architecture, pull requests, impacting issues with the dev team
- [Maintainers](./maintainers.md) - Maintainer roles, types, and how to become one
- [Maintainers](./maintainers.md) - Maintainers of PX4 Subsystems and Ecosystem
- [Support](../contribute/support.md) - Get help and raise issues
- [Source Code Management](../contribute/code.md) - Work with PX4 code
- [Documentation](../contribute/docs.md) - Improve the docs
+12 -41
View File
@@ -1,86 +1,57 @@
# Maintainer Role
Dronecode maintainers provide technical leadership for PX4 and for other ecosystem components such as MAVLink, MAVSDK, QGroundControl, and others. Some maintainers take responsibility for specific areas of the project, while others help across the project more broadly.
Dronecode maintainers have technical leadership and responsibility for specific areas of PX4, and for other ecosystem components such as MAVLink, MAVSDK, QGroundControl, and others.
The maintainer role is defined by the community with help and supervision from the [Dronecode Foundation](https://dronecode.org/).
To find the most up-to-date maintainers list, see [`MAINTAINERS.md`](https://github.com/PX4/PX4-Autopilot/blob/main/MAINTAINERS.md) in the PX4-Autopilot repository.
## Maintainer Types
PX4 recognizes two types of maintainers. Both are full members of the maintainer team, have write access via the [`Dev Team`](https://github.com/orgs/PX4/teams/dev-team) GitHub team, and participate in maintainer decisions.
- **Code Owners** are responsible for a specific category of the project (for example, State Estimation, Multirotor, or CI). They have final say on changes to their area, are the primary reviewers for that code, and help shape its roadmap. This is the role described in detail below.
- **Reviewers** help maintain PX4 across the project without ownership of a specific category. They review, triage, and contribute wherever their interests and time allow. Reviewers have the same access and voting rights as Code Owners, but no on-call responsibility for any specific area of the codebase.
The Reviewer role is a good fit for contributors who want to help steward the project without committing to a specific component up front. A Reviewer may later become a Code Owner for a category by mutual agreement with the existing Code Owners of that category and sign-off from the maintainer team.
To find the most up-to-date maintainers list, visit [PX4-Autopilot README](https://github.com/PX4/PX4-Autopilot#maintenance-team).
## Recruitment Process
If you would like to join the PX4 maintainers team or if you want to nominate someone else follow the steps below:
1. Read the [role description](#dronecode-maintainer-role-description), and make sure you understand the responsibilities of the role.
2. To nominate yourself, reach out to one of the maintainers (see the complete list in [`MAINTAINERS.md`](https://github.com/PX4/PX4-Autopilot/blob/main/MAINTAINERS.md)), and seek their sponsorship.
3. Express your interest in becoming a maintainer, and specify whether you are applying as a **Code Owner** (for a specific category) or as a **Reviewer** (helping across the project without a fixed category).
2. To nominate yourself, reach out to one of the maintainers (see the complete list in the [PX4-Autopilot README](https://github.com/PX4/PX4-Autopilot#maintenance-team)), and seek their sponsorship.
3. Express your interest in becoming a maintainer, and specify which area you would like to maintain.
4. The sponsoring maintainer needs to bring this up for discussion in one of the [weekly developer calls](dev_call.md).
The maintainer team will vote on the call to determine whether to accept you as a maintainer.
A Reviewer may later transition to a Code Owner role for a specific category. This requires agreement from the existing Code Owners of that category and sign-off from the maintainer team, following the same discussion and vote on the weekly developer call.
### Adding a new maintainer
Once the maintainer team has agreed to add a new maintainer, the change is landed via a pull request to [`MAINTAINERS.md`](https://github.com/PX4/PX4-Autopilot/blob/main/MAINTAINERS.md). The process is intentionally simple:
1. A current maintainer opens a PR adding the new maintainer to the appropriate table (**Code Owners** with a category, or **Reviewers**).
2. The PR must be approved by at least one other current maintainer.
3. If the new maintainer is being added as a Code Owner or sub-owner of a specific component, the existing Code Owner of that component must be among the approvers.
Once the PR is merged, the new maintainer proceeds through the [Onboarding Process](#onboarding-process) below.
## Onboarding Process
Once accepted every maintainers will go through the following process:
1. **Discord** server admin will grant you the `dev team` role, which gives you:
1. Basic admin privileges on discord.
2. Access to the private `#maintainers` channel for internal maintainer discussion.
2. Access to the `#maintainers` channel.
2. You will be given access to the GitHub team: "[`Dev Team`](https://github.com/orgs/PX4/teams/dev-team)" which grants you:
1. Permission to merge the PR of any of PX4 workspace repositories after it's approved
2. Permission to trigger GitHub actions when a new contributor opens a PR.
3. Permission to edit Issue/PR contents.
3. **Add your info to official PX4 channels**:
1. Add your information to the internal Dronecode database of maintainers to keep you in sync.
2. Community introduction to the new maintainer in the form of a forum post, which is promoted through ever growing official channels
1. Include your information on the PX4 [README](https://github.com/PX4/PX4-Autopilot/blob/main/README.md) next to the rest of the team
2. Listed on the [Maintainers section](https://px4.io/community/maintainers/) of the PX4 website.
3. Add your information to the internal Dronecode database of maintainers to keep you in sync.
4. Community introduction to the new maintainer in the form of a forum post, which is promoted through ever growing official channels
## Dronecode Maintainer Role Description
The responsibilities and qualifications below describe the **Code Owner** role in detail. **Reviewers** share the same spirit of technical stewardship, community guidance, and participation in maintainer meetings, without being tied to a specific category. Reviewers are expected to review and triage across the project where their expertise and interest apply.
### Summary
Maintainers lead/manage the development of a **specific category (referred to as category below)** of any Open Source Projects hosted within the Dronecode Foundation, such as the PX4 Autopilot.
### Responsibilities (Code Owner)
### Responsibilities
1. Take charge of overseeing the development in their category.
2. Provide guidance/advice on community members in their category.
3. Review relevant pull requests and issues from the community on GitHub.
4. Coordinate with the maintainer group.
5. Keep regular attendance on [weekly meetings](dev_call.md).
5. Keep regular attendance on [weekly meetings ](dev_call.md).
6. Help create and maintain a roadmap for the project your represent.
7. Uphold the [Code of Conduct](https://github.com/Dronecode/foundation/blob/main/CODE-OF-CONDUCT.md) of our community.
### Responsibilities (Reviewer)
1. Review relevant pull requests and issues across the project where your expertise applies.
2. Help triage issues and guide community contributors.
3. Coordinate with the maintainer group.
4. Keep regular attendance on [weekly meetings](dev_call.md).
5. Uphold the [Code of Conduct](https://github.com/Dronecode/foundation/blob/main/CODE-OF-CONDUCT.md) of our community.
### Qualifications
1. Proven track record of valuable contributions.
2. Domain expertise in the category field (for Code Owners) or broad working knowledge of the project (for Reviewers).
2. Domain expertise in the category field.
3. Good overview of the project you are applying to.
4. You need to manage approval from your employer when relevant.
+17 -64
View File
@@ -2,29 +2,17 @@
<img src="../../assets/site/position_fixed.svg" title="Position fix required (e.g. GPS)" width="30px" />
:::: warning
Offboard control with ROS 2 requires _significant care_ to ensure that it is used safely.
Please read [ROS 2 Offboard Control](#ros-2-offboard-control) carefully to fully understand the risks involved when using it.
A good understanding of [PX4 controller diagrams](../flight_stack/controller_diagrams.md) is advised.
::: tip
[PX4 ROS 2 Interface Library](../ros2/px4_ros2_interface_lib.md) provides a safer alternative.
:::
::::
The vehicle obeys position, velocity, acceleration, attitude, attitude rates or thrust/torque setpoints provided by some source that is external to the flight stack, such as a companion computer.
The setpoints may be provided using MAVLink (or a MAVLink API such as [MAVSDK](https://mavsdk.mavlink.io/)) or by [ROS 2](../ros2/index.md).
PX4 requires that the external controller provides a continuous 2Hz "proof of life" signal, by streaming any of the supported MAVLink setpoint messages or the ROS 2 [OffboardControlMode](../msg_docs/OffboardControlMode.md) message.
PX4 enables switching to offboard control mode only after receiving the signal for more than a second, and will failsafe (controlled by [COM_OBL_RC_ACT](../advanced_config/parameter_reference.md#COM_OBL_RC_ACT)) if the signal stops.
PX4 enables offboard control only after receiving the signal for more than a second, and will regain control if the signal stops.
::: info
- This mode requires position or pose/attitude information - e.g. GPS, optical flow, visual-inertial odometry, mocap, etc. depending on the type of offboard setpoints that the external controller sends.
- This mode requires position or pose/attitude information - e.g. GPS, optical flow, visual-inertial odometry, mocap, etc.
- Manual control is disabled except to change modes (you can also fly without any manual controller at all by setting the parameter [COM_RC_IN_MODE](../advanced_config/parameter_reference.md#COM_RC_IN_MODE) to `4: Disable manual control`).
- The vehicle must already be receiving a stream of MAVLink setpoint messages or ROS 2 [OffboardControlMode](../msg_docs/OffboardControlMode.md) messages before arming in offboard mode or switching to offboard mode when flying.
- The vehicle must be already be receiving a stream of MAVLink setpoint messages or ROS 2 [OffboardControlMode](../msg_docs/OffboardControlMode.md) messages before arming in offboard mode or switching to offboard mode when flying.
- The vehicle will exit offboard mode if MAVLink setpoint messages or `OffboardControlMode` are not received at a rate of > 2Hz.
- Not all coordinate frames and field values allowed by MAVLink are supported for all setpoint messages and vehicles.
Read the sections below _carefully_ to ensure only supported values are used.
@@ -50,37 +38,13 @@ Note that offboard mode only supports a very limited set of MAVLink commands and
Operations, like taking off, landing, return to launch, may be best handled using the appropriate modes.
Operations like uploading, downloading missions can be performed in any mode.
## ROS 2 Offboard Control
This section describes how to perform offboard control through one of the direct ROS 2 interfaces: UXRCE-DDS or Zenoh.
When using direct ROS 2 offboard control, PX4 setpoint messages generated by external controllers are injected into the [PX4 control pipeline](../flight_stack/controller_diagrams.md).
Because messages from internal and external controllers are indistinguishable within PX4, precise synchronization is required in order to avoid the controllers writing conflicting messages to the same topic.
In Offboard mode (only), an external system can use [`OffboardControlMode`](#the-offboardcontrolmode-px4-message) to specify which setpoint topics PX4 should publish/not publish, allowing them to be written safely by an external controller.
::: warning
PX4 has no means of filtering and distinguishing ROS 2 messages from internal messages, in any mode.
In order to interwork safely, the external controller must:
- Publish PX4 setpoint messages **ONLY** in Offboard mode.
- Specify which setpoints it will write using the `OffboardControlMode` topic.
- Stream the `OffboardControlMode` topic as a keep-alive signal.
- Stream the setpoints it wants: unlike with MAVLink, PX4 won't trigger a failsafe if setpoints aren't sent regularly.
If external setpoints are sent in any other flight mode, or they overwrite topics that have not been disabled by PX4 when in offboard mode, collisions are likely.
This will result in unexpected, and possibly catastrophic, behaviour.
:::
### The `OffboardControlMode` PX4 message
## ROS 2 Messages
The following ROS 2 messages and their particular fields and field values are allowed for the specified frames.
In addition to providing heartbeat functionality, `OffboardControlMode` has two other main purposes:
1. Controls which internal PX4 control modules of the [PX4 control architecture](../flight_stack/controller_diagrams.md) shall remain active and which ones shall be disabled when the vehicle is in Offboard Mode.
2. Determines which valid estimates (position, velocity, etc.) are required.
1. Controls the level of the [PX4 control architecture](../flight_stack/controller_diagrams.md) at which offboard setpoints must be injected, and disables the bypassed controllers.
2. Determines which valid estimates (position or velocity) are required, and also which setpoint messages should be used.
The `OffboardControlMode` message is defined as shown.
@@ -105,46 +69,33 @@ For rovers see the [rover section](#rover).
The fields are ordered in terms of priority such that `position` takes precedence over `velocity` and later fields, `velocity` takes precedence over `acceleration`, and so on.
The first field that has a non-zero value (from top to bottom) defines what valid estimate is required in order to use offboard mode, and the setpoint message(s) that can be used.
For example, if the `acceleration` field is the first non-zero value, then PX4 requires a valid `attitude estimate`, and the setpoint must be specified using the `TrajectorySetpoint` message.
For example, if the `acceleration` field is the first non-zero value, then PX4 requires a valid `velocity estimate`, and the setpoint must be specified using the `TrajectorySetpoint` message.
| desired control quantity | position field | velocity field | acceleration field | attitude field | body_rate field | thrust_and_torque field | direct_actuator field | required estimate | required message |
| ------------------------ | -------------- | -------------- | ------------------ | -------------- | --------------- | ----------------------- | --------------------- | ----------------- | ------------------------------------------------------------------------------------------------------------------------------- |
| position (NED) | ✓ | - | - | - | - | - | - | position | [TrajectorySetpoint](../msg_docs/TrajectorySetpoint.md) |
| velocity (NED) | ✗ | ✓ | - | - | - | - | - | velocity | [TrajectorySetpoint](../msg_docs/TrajectorySetpoint.md) |
| acceleration (NED) | ✗ | ✗ | ✓ | - | - | - | - | attitude | [TrajectorySetpoint](../msg_docs/TrajectorySetpoint.md) |
| attitude (FRD) | ✗ | ✗ | ✗ | ✓ | - | - | - | attitude | [VehicleAttitudeSetpoint](../msg_docs/VehicleAttitudeSetpoint.md) |
| body_rate (FRD) | ✗ | ✗ | ✗ | ✗ | ✓ | - | - | angular velocity | [VehicleRatesSetpoint](../msg_docs/VehicleRatesSetpoint.md) |
| acceleration (NED) | ✗ | ✗ | ✓ | - | - | - | - | velocity | [TrajectorySetpoint](../msg_docs/TrajectorySetpoint.md) |
| attitude (FRD) | ✗ | ✗ | ✗ | ✓ | - | - | - | none | [VehicleAttitudeSetpoint](../msg_docs/VehicleAttitudeSetpoint.md) |
| body_rate (FRD) | ✗ | ✗ | ✗ | ✗ | ✓ | - | - | none | [VehicleRatesSetpoint](../msg_docs/VehicleRatesSetpoint.md) |
| thrust and torque (FRD) | ✗ | ✗ | ✗ | ✗ | ✗ | ✓ | - | none | [VehicleThrustSetpoint](../msg_docs/VehicleThrustSetpoint.md) and [VehicleTorqueSetpoint](../msg_docs/VehicleTorqueSetpoint.md) |
| direct motors and servos | ✗ | ✗ | ✗ | ✗ | ✗ | ✗ | ✓ | none | [ActuatorMotors](../msg_docs/ActuatorMotors.md) and [ActuatorServos](../msg_docs/ActuatorServos.md) |
where ✓ means that the bit is set, ✘ means that the bit is not set and `-` means that the bit value is irrelevant.
where ✓ means that the bit is set, ✘ means that the bit is not set and `-` means that the bit is value is irrelevant.
::: info
Before using offboard mode with ROS 2, please spend a few minutes understanding the different [frame conventions](../ros2/user_guide.md#ros-2-px4-frame-conventions) that PX4 and ROS 2 use.
:::
In the following, the different setpoint messages for the main supported airframes are explained.
For fixed-wing offboard control, please refer to the [PX4 ROS 2 Interface Library](../ros2/px4_ros2_interface_lib.md).
### Multicopters
### Copter
- [px4_msgs::msg::TrajectorySetpoint](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/TrajectorySetpoint.msg)
- The following input combinations are supported:
- Position setpoint (`position` different from `NaN`). Non-`NaN` values of velocity and acceleration are used as feedforward terms for the inner loop controllers.
- Velocity setpoint (`velocity` different from `NaN` and `position` set to `NaN`). Non-`NaN` values of acceleration are used as feedforward terms for the inner loop controllers.
- Velocity setpoint (`velocity` different from `NaN` and `position` set to `NaN`). Non-`NaN` values acceleration are used as feedforward terms for the inner loop controllers.
- Acceleration setpoint (`acceleration` different from `NaN` and `position` and `velocity` set to `NaN`)
- All values are interpreted in NED (North, East, Down) coordinate system and the units are `[m]`, `[m/s]` and `[m/s^2]` for position, velocity and acceleration, respectively.
::: warning
Position, velocity and acceleration control for multicopters are all handled by the `mc_pos_control` module.
This module is enabled if any of `position`, `velocity` and `acceleration` fields are set to true.
However, only the content of the `TrajectorySetpoint` messages determines which of the three controllers shall run.
This means that even if `OffboardControlMode` messages carry the intention of velocity control (only `velocity` field is set) but non-`NaN` position values are sent in the `TrajectorySetpoint` messages, then PX4 will keep running the position controller.
:::
- All values are interpreted in NED (Nord, East, Down) coordinate system and the units are `[m]`, `[m/s]` and `[m/s^2]` for position, velocity and acceleration, respectively.
- [px4_msgs::msg::VehicleAttitudeSetpoint](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/VehicleAttitudeSetpoint.msg)
- The following input combination is supported:
@@ -243,11 +194,13 @@ The following offboard control modes bypass all internal PX4 control loops and s
- [px4_msgs::msg::ActuatorMotors](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/ActuatorMotors.msg) + [px4_msgs::msg::ActuatorServos](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/ActuatorServos.msg)
- You directly control the motor outputs and/or servo outputs.
- Currently works at lower level than then `control_allocator` module.
Do not publish these messages when not in offboard mode.
- All the values normalized in `[-1, 1]`.
For outputs that do not support negative values, negative entries map to `NaN`.
- `NaN` maps to disarmed.
## MAVLink Offboard Control
## MAVLink Messages
The following MAVLink messages and their particular fields and field values are allowed for the specified vehicle frames.
+197 -197
View File
@@ -95,207 +95,207 @@ They are not build into the module, and hence are neither published or subscribe
::: details See messages
- [GpsInjectData](../msg_docs/GpsInjectData.md)
- [GimbalManagerSetAttitude](../msg_docs/GimbalManagerSetAttitude.md)
- [RoverSpeedStatus](../msg_docs/RoverSpeedStatus.md)
- [SystemPower](../msg_docs/SystemPower.md)
- [EstimatorStatus](../msg_docs/EstimatorStatus.md)
- [GpioRequest](../msg_docs/GpioRequest.md)
- [HealthReport](../msg_docs/HealthReport.md)
- [OrbitStatus](../msg_docs/OrbitStatus.md)
- [ParameterSetValueRequest](../msg_docs/ParameterSetValueRequest.md)
- [VehicleConstraints](../msg_docs/VehicleConstraints.md)
- [VehicleAirData](../msg_docs/VehicleAirData.md)
- [MountOrientation](../msg_docs/MountOrientation.md)
- [SensorGyroFft](../msg_docs/SensorGyroFft.md)
- [IrlockReport](../msg_docs/IrlockReport.md)
- [ManualControlSwitches](../msg_docs/ManualControlSwitches.md)
- [OpenDroneIdOperatorId](../msg_docs/OpenDroneIdOperatorId.md)
- [FixedWingLateralStatus](../msg_docs/FixedWingLateralStatus.md)
- [DebugKeyValue](../msg_docs/DebugKeyValue.md)
- [VehicleAngularAccelerationSetpoint](../msg_docs/VehicleAngularAccelerationSetpoint.md)
- [VehicleGlobalPositionV0](../msg_docs/VehicleGlobalPositionV0.md)
- [DeviceInformation](../msg_docs/DeviceInformation.md)
- [HoverThrustEstimate](../msg_docs/HoverThrustEstimate.md)
- [VehicleLocalPositionV0](../msg_docs/VehicleLocalPositionV0.md)
- [EventV0](../msg_docs/EventV0.md)
- [RcChannels](../msg_docs/RcChannels.md)
- [ArmingCheckReplyV0](../msg_docs/ArmingCheckReplyV0.md)
- [DatamanRequest](../msg_docs/DatamanRequest.md)
- [SensorAirflow](../msg_docs/SensorAirflow.md)
- [InputRc](../msg_docs/InputRc.md)
- [EstimatorAidSource1d](../msg_docs/EstimatorAidSource1d.md)
- [SensorGnssStatus](../msg_docs/SensorGnssStatus.md)
- [OpenDroneIdSelfId](../msg_docs/OpenDroneIdSelfId.md)
- [Ekf2Timestamps](../msg_docs/Ekf2Timestamps.md)
- [FixedWingLateralGuidanceStatus](../msg_docs/FixedWingLateralGuidanceStatus.md)
- [GeneratorStatus](../msg_docs/GeneratorStatus.md)
- [VehicleAngularVelocity](../msg_docs/VehicleAngularVelocity.md)
- [AdcReport](../msg_docs/AdcReport.md)
- [FollowTarget](../msg_docs/FollowTarget.md)
- [RoverAttitudeStatus](../msg_docs/RoverAttitudeStatus.md)
- [VehicleAcceleration](../msg_docs/VehicleAcceleration.md)
- [ActuatorOutputs](../msg_docs/ActuatorOutputs.md)
- [EscEepromWrite](../msg_docs/EscEepromWrite.md)
- [EstimatorAidSource2d](../msg_docs/EstimatorAidSource2d.md)
- [RateCtrlStatus](../msg_docs/RateCtrlStatus.md)
- [RaptorStatus](../msg_docs/RaptorStatus.md)
- [GimbalManagerStatus](../msg_docs/GimbalManagerStatus.md)
- [DifferentialPressure](../msg_docs/DifferentialPressure.md)
- [RangingBeacon](../msg_docs/RangingBeacon.md)
- [PwmInput](../msg_docs/PwmInput.md)
- [LaunchDetectionStatus](../msg_docs/LaunchDetectionStatus.md)
- [DronecanNodeStatus](../msg_docs/DronecanNodeStatus.md)
- [SensorsStatusImu](../msg_docs/SensorsStatusImu.md)
- [DatamanResponse](../msg_docs/DatamanResponse.md)
- [VehicleImu](../msg_docs/VehicleImu.md)
- [EstimatorSensorBias](../msg_docs/EstimatorSensorBias.md)
- [MagWorkerData](../msg_docs/MagWorkerData.md)
- [CellularStatus](../msg_docs/CellularStatus.md)
- [GpsDump](../msg_docs/GpsDump.md)
- [ParameterResetRequest](../msg_docs/ParameterResetRequest.md)
- [EstimatorEventFlags](../msg_docs/EstimatorEventFlags.md)
- [InternalCombustionEngineControl](../msg_docs/InternalCombustionEngineControl.md)
- [InternalCombustionEngineStatus](../msg_docs/InternalCombustionEngineStatus.md)
- [GimbalManagerSetManualControl](../msg_docs/GimbalManagerSetManualControl.md)
- [FixedWingRunwayControl](../msg_docs/FixedWingRunwayControl.md)
- [ActionRequest](../msg_docs/ActionRequest.md)
- [EstimatorGpsStatus](../msg_docs/EstimatorGpsStatus.md)
- [NormalizedUnsignedSetpoint](../msg_docs/NormalizedUnsignedSetpoint.md)
- [RoverRateStatus](../msg_docs/RoverRateStatus.md)
- [GimbalDeviceInformation](../msg_docs/GimbalDeviceInformation.md)
- [Vtx](../msg_docs/Vtx.md)
- [OrbTestMedium](../msg_docs/OrbTestMedium.md)
- [EscEepromRead](../msg_docs/EscEepromRead.md)
- [Px4ioStatus](../msg_docs/Px4ioStatus.md)
- [OrbTestLarge](../msg_docs/OrbTestLarge.md)
- [CameraCapture](../msg_docs/CameraCapture.md)
- [Airspeed](../msg_docs/Airspeed.md)
- [CanInterfaceStatus](../msg_docs/CanInterfaceStatus.md)
- [DebugArray](../msg_docs/DebugArray.md)
- [SatelliteInfo](../msg_docs/SatelliteInfo.md)
- [Cpuload](../msg_docs/Cpuload.md)
- [EstimatorInnovations](../msg_docs/EstimatorInnovations.md)
- [EstimatorStates](../msg_docs/EstimatorStates.md)
- [EstimatorSelectorStatus](../msg_docs/EstimatorSelectorStatus.md)
- [FailureDetectorStatus](../msg_docs/FailureDetectorStatus.md)
- [LoggerStatus](../msg_docs/LoggerStatus.md)
- [RegisterExtComponentRequestV0](../msg_docs/RegisterExtComponentRequestV0.md)
- [GimbalControls](../msg_docs/GimbalControls.md)
- [LogMessage](../msg_docs/LogMessage.md)
- [PowerMonitor](../msg_docs/PowerMonitor.md)
- [VehicleAttitudeSetpointV0](../msg_docs/VehicleAttitudeSetpointV0.md)
- [BatteryInfo](../msg_docs/BatteryInfo.md)
- [DistanceSensorModeChangeRequest](../msg_docs/DistanceSensorModeChangeRequest.md)
- [ParameterSetValueResponse](../msg_docs/ParameterSetValueResponse.md)
- [GpioConfig](../msg_docs/GpioConfig.md)
- [LandingGearWheel](../msg_docs/LandingGearWheel.md)
- [CameraTrigger](../msg_docs/CameraTrigger.md)
- [MissionResult](../msg_docs/MissionResult.md)
- [SensorUwb](../msg_docs/SensorUwb.md)
- [TecsStatus](../msg_docs/TecsStatus.md)
- [TrajectorySetpoint6dof](../msg_docs/TrajectorySetpoint6dof.md)
- [LedControl](../msg_docs/LedControl.md)
- [ActuatorArmed](../msg_docs/ActuatorArmed.md)
- [ButtonEvent](../msg_docs/ButtonEvent.md)
- [RegisterExtComponentReplyV0](../msg_docs/RegisterExtComponentReplyV0.md)
- [ControlAllocatorStatus](../msg_docs/ControlAllocatorStatus.md)
- [NavigatorMissionItem](../msg_docs/NavigatorMissionItem.md)
- [QshellReq](../msg_docs/QshellReq.md)
- [EstimatorFusionControl](../msg_docs/EstimatorFusionControl.md)
- [SensorGyro](../msg_docs/SensorGyro.md)
- [PurePursuitStatus](../msg_docs/PurePursuitStatus.md)
- [EstimatorAidSource3d](../msg_docs/EstimatorAidSource3d.md)
- [Mission](../msg_docs/Mission.md)
- [RtlStatus](../msg_docs/RtlStatus.md)
- [BatteryStatusV0](../msg_docs/BatteryStatusV0.md)
- [FigureEightStatus](../msg_docs/FigureEightStatus.md)
- [PositionControllerLandingStatus](../msg_docs/PositionControllerLandingStatus.md)
- [ActuatorTest](../msg_docs/ActuatorTest.md)
- [TuneControl](../msg_docs/TuneControl.md)
- [EscStatus](../msg_docs/EscStatus.md)
- [VehicleOpticalFlowVel](../msg_docs/VehicleOpticalFlowVel.md)
- [NeuralControl](../msg_docs/NeuralControl.md)
- [VehicleOpticalFlow](../msg_docs/VehicleOpticalFlow.md)
- [VehicleStatusV1](../msg_docs/VehicleStatusV1.md)
- [SensorCorrection](../msg_docs/SensorCorrection.md)
- [AutotuneAttitudeControlStatus](../msg_docs/AutotuneAttitudeControlStatus.md)
- [FollowTargetEstimator](../msg_docs/FollowTargetEstimator.md)
- [SensorBaro](../msg_docs/SensorBaro.md)
- [OpenDroneIdSystem](../msg_docs/OpenDroneIdSystem.md)
- [GpioIn](../msg_docs/GpioIn.md)
- [FlightPhaseEstimation](../msg_docs/FlightPhaseEstimation.md)
- [DebugValue](../msg_docs/DebugValue.md)
- [EstimatorBias3d](../msg_docs/EstimatorBias3d.md)
- [Gripper](../msg_docs/Gripper.md)
- [TakeoffStatus](../msg_docs/TakeoffStatus.md)
- [Event](../msg_docs/Event.md)
- [VehicleRoi](../msg_docs/VehicleRoi.md)
- [HomePositionV0](../msg_docs/HomePositionV0.md)
- [ActuatorControlsStatus](../msg_docs/ActuatorControlsStatus.md)
- [LandingTargetPose](../msg_docs/LandingTargetPose.md)
- [PowerButtonState](../msg_docs/PowerButtonState.md)
- [OrbTest](../msg_docs/OrbTest.md)
- [SensorMag](../msg_docs/SensorMag.md)
- [SensorAccel](../msg_docs/SensorAccel.md)
- [AirspeedValidatedV0](../msg_docs/AirspeedValidatedV0.md)
- [NavigatorStatus](../msg_docs/NavigatorStatus.md)
- [ParameterUpdate](../msg_docs/ParameterUpdate.md)
- [VehicleImuStatus](../msg_docs/VehicleImuStatus.md)
- [TaskStackInfo](../msg_docs/TaskStackInfo.md)
- [RadioStatus](../msg_docs/RadioStatus.md)
- [ArmingCheckRequestV0](../msg_docs/ArmingCheckRequestV0.md)
- [FollowTargetStatus](../msg_docs/FollowTargetStatus.md)
- [VehicleLocalPositionSetpoint](../msg_docs/VehicleLocalPositionSetpoint.md)
- [GpioOut](../msg_docs/GpioOut.md)
- [QshellRetval](../msg_docs/QshellRetval.md)
- [SensorHygrometer](../msg_docs/SensorHygrometer.md)
- [MavlinkLog](../msg_docs/MavlinkLog.md)
- [PositionSetpoint](../msg_docs/PositionSetpoint.md)
- [SensorGnssRelative](../msg_docs/SensorGnssRelative.md)
- [SensorSelection](../msg_docs/SensorSelection.md)
- [VelocityLimits](../msg_docs/VelocityLimits.md)
- [OpenDroneIdOperatorId](../msg_docs/OpenDroneIdOperatorId.md)
- [VehicleCommandAckV0](../msg_docs/VehicleCommandAckV0.md)
- [TiltrotorExtraControls](../msg_docs/TiltrotorExtraControls.md)
- [SensorAccelFifo](../msg_docs/SensorAccelFifo.md)
- [WheelEncoders](../msg_docs/WheelEncoders.md)
- [PpsCapture](../msg_docs/PpsCapture.md)
- [RcParameterMap](../msg_docs/RcParameterMap.md)
- [RtlTimeEstimate](../msg_docs/RtlTimeEstimate.md)
- [GimbalManagerInformation](../msg_docs/GimbalManagerInformation.md)
- [IridiumsbdStatus](../msg_docs/IridiumsbdStatus.md)
- [MavlinkTunnel](../msg_docs/MavlinkTunnel.md)
- [ActuatorServosTrim](../msg_docs/ActuatorServosTrim.md)
- [VehicleStatusV2](../msg_docs/VehicleStatusV2.md)
- [EscReport](../msg_docs/EscReport.md)
- [EstimatorBias](../msg_docs/EstimatorBias.md)
- [GeofenceStatus](../msg_docs/GeofenceStatus.md)
- [GeofenceResult](../msg_docs/GeofenceResult.md)
- [UavcanParameterRequest](../msg_docs/UavcanParameterRequest.md)
- [ParameterSetUsedRequest](../msg_docs/ParameterSetUsedRequest.md)
- [VehicleStatusV0](../msg_docs/VehicleStatusV0.md)
- [DebugVect](../msg_docs/DebugVect.md)
- [SensorTemp](../msg_docs/SensorTemp.md)
- [UlogStream](../msg_docs/UlogStream.md)
- [MagnetometerBiasEstimate](../msg_docs/MagnetometerBiasEstimate.md)
- [Ping](../msg_docs/Ping.md)
- [YawEstimatorStatus](../msg_docs/YawEstimatorStatus.md)
- [VehicleMagnetometer](../msg_docs/VehicleMagnetometer.md)
- [GimbalDeviceSetAttitude](../msg_docs/GimbalDeviceSetAttitude.md)
- [UlogStreamAck](../msg_docs/UlogStreamAck.md)
- [AirspeedWind](../msg_docs/AirspeedWind.md)
- [RoverSpeedStatus](../msg_docs/RoverSpeedStatus.md)
- [EscEepromRead](../msg_docs/EscEepromRead.md)
- [NormalizedUnsignedSetpoint](../msg_docs/NormalizedUnsignedSetpoint.md)
- [SensorAirflow](../msg_docs/SensorAirflow.md)
- [CellularStatus](../msg_docs/CellularStatus.md)
- [NavigatorStatus](../msg_docs/NavigatorStatus.md)
- [AirspeedValidatedV0](../msg_docs/AirspeedValidatedV0.md)
- [ParameterSetValueResponse](../msg_docs/ParameterSetValueResponse.md)
- [TuneControl](../msg_docs/TuneControl.md)
- [HealthReport](../msg_docs/HealthReport.md)
- [MavlinkLog](../msg_docs/MavlinkLog.md)
- [FixedWingLateralGuidanceStatus](../msg_docs/FixedWingLateralGuidanceStatus.md)
- [TakeoffStatus](../msg_docs/TakeoffStatus.md)
- [FollowTargetStatus](../msg_docs/FollowTargetStatus.md)
- [TecsStatus](../msg_docs/TecsStatus.md)
- [PositionControllerStatus](../msg_docs/PositionControllerStatus.md)
- [CameraStatus](../msg_docs/CameraStatus.md)
- [SensorsStatus](../msg_docs/SensorsStatus.md)
- [EventV0](../msg_docs/EventV0.md)
- [ManualControlSwitches](../msg_docs/ManualControlSwitches.md)
- [VelocityLimits](../msg_docs/VelocityLimits.md)
- [RegisterExtComponentRequestV0](../msg_docs/RegisterExtComponentRequestV0.md)
- [SensorHygrometer](../msg_docs/SensorHygrometer.md)
- [AirspeedWind](../msg_docs/AirspeedWind.md)
- [SensorPreflightMag](../msg_docs/SensorPreflightMag.md)
- [SensorGyroFifo](../msg_docs/SensorGyroFifo.md)
- [ConfigOverridesV0](../msg_docs/ConfigOverridesV0.md)
- [LandingTargetInnovations](../msg_docs/LandingTargetInnovations.md)
- [UavcanParameterValue](../msg_docs/UavcanParameterValue.md)
- [PositionControllerLandingStatus](../msg_docs/PositionControllerLandingStatus.md)
- [SensorAccelFifo](../msg_docs/SensorAccelFifo.md)
- [BatteryStatusV0](../msg_docs/BatteryStatusV0.md)
- [VehicleImu](../msg_docs/VehicleImu.md)
- [FuelTankStatus](../msg_docs/FuelTankStatus.md)
- [OpenDroneIdArmStatus](../msg_docs/OpenDroneIdArmStatus.md)
- [GainCompression](../msg_docs/GainCompression.md)
- [HeaterStatus](../msg_docs/HeaterStatus.md)
- [Rpm](../msg_docs/Rpm.md)
- [GimbalDeviceSetAttitude](../msg_docs/GimbalDeviceSetAttitude.md)
- [IridiumsbdStatus](../msg_docs/IridiumsbdStatus.md)
- [RoverRateStatus](../msg_docs/RoverRateStatus.md)
- [YawEstimatorStatus](../msg_docs/YawEstimatorStatus.md)
- [RaptorInput](../msg_docs/RaptorInput.md)
- [EstimatorAidSource1d](../msg_docs/EstimatorAidSource1d.md)
- [RangingBeacon](../msg_docs/RangingBeacon.md)
- [DifferentialPressure](../msg_docs/DifferentialPressure.md)
- [CameraStatus](../msg_docs/CameraStatus.md)
- [Mission](../msg_docs/Mission.md)
- [ArmingCheckRequestV0](../msg_docs/ArmingCheckRequestV0.md)
- [RadioStatus](../msg_docs/RadioStatus.md)
- [DistanceSensorModeChangeRequest](../msg_docs/DistanceSensorModeChangeRequest.md)
- [EstimatorStatus](../msg_docs/EstimatorStatus.md)
- [Ping](../msg_docs/Ping.md)
- [FollowTargetEstimator](../msg_docs/FollowTargetEstimator.md)
- [TiltrotorExtraControls](../msg_docs/TiltrotorExtraControls.md)
- [MountOrientation](../msg_docs/MountOrientation.md)
- [EstimatorSelectorStatus](../msg_docs/EstimatorSelectorStatus.md)
- [GpioRequest](../msg_docs/GpioRequest.md)
- [ActuatorArmed](../msg_docs/ActuatorArmed.md)
- [HeaterStatus](../msg_docs/HeaterStatus.md)
- [GimbalManagerSetAttitude](../msg_docs/GimbalManagerSetAttitude.md)
- [GimbalControls](../msg_docs/GimbalControls.md)
- [FlightPhaseEstimation](../msg_docs/FlightPhaseEstimation.md)
- [DatamanRequest](../msg_docs/DatamanRequest.md)
- [PwmInput](../msg_docs/PwmInput.md)
- [LedControl](../msg_docs/LedControl.md)
- [EstimatorStates](../msg_docs/EstimatorStates.md)
- [OpenDroneIdSystem](../msg_docs/OpenDroneIdSystem.md)
- [VehicleLocalPositionV0](../msg_docs/VehicleLocalPositionV0.md)
- [VehicleGlobalPositionV0](../msg_docs/VehicleGlobalPositionV0.md)
- [EstimatorAidSource2d](../msg_docs/EstimatorAidSource2d.md)
- [RcParameterMap](../msg_docs/RcParameterMap.md)
- [SensorBaro](../msg_docs/SensorBaro.md)
- [UlogStream](../msg_docs/UlogStream.md)
- [LandingGearWheel](../msg_docs/LandingGearWheel.md)
- [VehicleStatusV1](../msg_docs/VehicleStatusV1.md)
- [RcChannels](../msg_docs/RcChannels.md)
- [Px4ioStatus](../msg_docs/Px4ioStatus.md)
- [EstimatorFusionControl](../msg_docs/EstimatorFusionControl.md)
- [VehicleImuStatus](../msg_docs/VehicleImuStatus.md)
- [SensorGyro](../msg_docs/SensorGyro.md)
- [LoggerStatus](../msg_docs/LoggerStatus.md)
- [RtlStatus](../msg_docs/RtlStatus.md)
- [ActuatorOutputs](../msg_docs/ActuatorOutputs.md)
- [ParameterUpdate](../msg_docs/ParameterUpdate.md)
- [EstimatorEventFlags](../msg_docs/EstimatorEventFlags.md)
- [VehicleRoi](../msg_docs/VehicleRoi.md)
- [LogMessage](../msg_docs/LogMessage.md)
- [VehicleConstraints](../msg_docs/VehicleConstraints.md)
- [Ekf2Timestamps](../msg_docs/Ekf2Timestamps.md)
- [AdcReport](../msg_docs/AdcReport.md)
- [TrajectorySetpoint6dof](../msg_docs/TrajectorySetpoint6dof.md)
- [LandingTargetPose](../msg_docs/LandingTargetPose.md)
- [GpioIn](../msg_docs/GpioIn.md)
- [GeofenceResult](../msg_docs/GeofenceResult.md)
- [SensorSelection](../msg_docs/SensorSelection.md)
- [RtlTimeEstimate](../msg_docs/RtlTimeEstimate.md)
- [MagWorkerData](../msg_docs/MagWorkerData.md)
- [OrbTest](../msg_docs/OrbTest.md)
- [GpsDump](../msg_docs/GpsDump.md)
- [ArmingCheckReplyV0](../msg_docs/ArmingCheckReplyV0.md)
- [Cpuload](../msg_docs/Cpuload.md)
- [LandingTargetInnovations](../msg_docs/LandingTargetInnovations.md)
- [SensorGyroFifo](../msg_docs/SensorGyroFifo.md)
- [Vtx](../msg_docs/Vtx.md)
- [DebugVect](../msg_docs/DebugVect.md)
- [ParameterSetUsedRequest](../msg_docs/ParameterSetUsedRequest.md)
- [VehicleAttitudeSetpointV0](../msg_docs/VehicleAttitudeSetpointV0.md)
- [RateCtrlStatus](../msg_docs/RateCtrlStatus.md)
- [EstimatorSensorBias](../msg_docs/EstimatorSensorBias.md)
- [ParameterResetRequest](../msg_docs/ParameterResetRequest.md)
- [GpsInjectData](../msg_docs/GpsInjectData.md)
- [DronecanNodeStatus](../msg_docs/DronecanNodeStatus.md)
- [Rpm](../msg_docs/Rpm.md)
- [ConfigOverridesV0](../msg_docs/ConfigOverridesV0.md)
- [SystemPower](../msg_docs/SystemPower.md)
- [FixedWingRunwayControl](../msg_docs/FixedWingRunwayControl.md)
- [ActuatorTest](../msg_docs/ActuatorTest.md)
- [GimbalDeviceInformation](../msg_docs/GimbalDeviceInformation.md)
- [OpenDroneIdSelfId](../msg_docs/OpenDroneIdSelfId.md)
- [GimbalManagerStatus](../msg_docs/GimbalManagerStatus.md)
- [InputRc](../msg_docs/InputRc.md)
- [EscEepromWrite](../msg_docs/EscEepromWrite.md)
- [SensorCorrection](../msg_docs/SensorCorrection.md)
- [SensorMag](../msg_docs/SensorMag.md)
- [FixedWingLateralStatus](../msg_docs/FixedWingLateralStatus.md)
- [Airspeed](../msg_docs/Airspeed.md)
- [VehicleAcceleration](../msg_docs/VehicleAcceleration.md)
- [DatamanResponse](../msg_docs/DatamanResponse.md)
- [GpioOut](../msg_docs/GpioOut.md)
- [MagnetometerBiasEstimate](../msg_docs/MagnetometerBiasEstimate.md)
- [FollowTarget](../msg_docs/FollowTarget.md)
- [Gripper](../msg_docs/Gripper.md)
- [VehicleAirData](../msg_docs/VehicleAirData.md)
- [PowerMonitor](../msg_docs/PowerMonitor.md)
- [ControlAllocatorStatus](../msg_docs/ControlAllocatorStatus.md)
- [ActuatorServosTrim](../msg_docs/ActuatorServosTrim.md)
- [TaskStackInfo](../msg_docs/TaskStackInfo.md)
- [GimbalManagerSetManualControl](../msg_docs/GimbalManagerSetManualControl.md)
- [SensorGnssRelative](../msg_docs/SensorGnssRelative.md)
- [UavcanParameterValue](../msg_docs/UavcanParameterValue.md)
- [EscReport](../msg_docs/EscReport.md)
- [HoverThrustEstimate](../msg_docs/HoverThrustEstimate.md)
- [ParameterSetValueRequest](../msg_docs/ParameterSetValueRequest.md)
- [OrbTestLarge](../msg_docs/OrbTestLarge.md)
- [InternalCombustionEngineControl](../msg_docs/InternalCombustionEngineControl.md)
- [UlogStreamAck](../msg_docs/UlogStreamAck.md)
- [ActuatorControlsStatus](../msg_docs/ActuatorControlsStatus.md)
- [OrbitStatus](../msg_docs/OrbitStatus.md)
- [SensorAccel](../msg_docs/SensorAccel.md)
- [EstimatorAidSource3d](../msg_docs/EstimatorAidSource3d.md)
- [CameraTrigger](../msg_docs/CameraTrigger.md)
- [GainCompression](../msg_docs/GainCompression.md)
- [CameraCapture](../msg_docs/CameraCapture.md)
- [PowerButtonState](../msg_docs/PowerButtonState.md)
- [LaunchDetectionStatus](../msg_docs/LaunchDetectionStatus.md)
- [VehicleStatusV0](../msg_docs/VehicleStatusV0.md)
- [PositionSetpoint](../msg_docs/PositionSetpoint.md)
- [GeneratorStatus](../msg_docs/GeneratorStatus.md)
- [VehicleAngularAccelerationSetpoint](../msg_docs/VehicleAngularAccelerationSetpoint.md)
- [DebugKeyValue](../msg_docs/DebugKeyValue.md)
- [EstimatorInnovations](../msg_docs/EstimatorInnovations.md)
- [SensorsStatusImu](../msg_docs/SensorsStatusImu.md)
- [DebugValue](../msg_docs/DebugValue.md)
- [ActionRequest](../msg_docs/ActionRequest.md)
- [ButtonEvent](../msg_docs/ButtonEvent.md)
- [VehicleOpticalFlow](../msg_docs/VehicleOpticalFlow.md)
- [MissionResult](../msg_docs/MissionResult.md)
- [SatelliteInfo](../msg_docs/SatelliteInfo.md)
- [FailureDetectorStatus](../msg_docs/FailureDetectorStatus.md)
- [NeuralControl](../msg_docs/NeuralControl.md)
- [GeofenceStatus](../msg_docs/GeofenceStatus.md)
- [QshellRetval](../msg_docs/QshellRetval.md)
- [EstimatorGpsStatus](../msg_docs/EstimatorGpsStatus.md)
- [OrbTestMedium](../msg_docs/OrbTestMedium.md)
- [BatteryInfo](../msg_docs/BatteryInfo.md)
- [NavigatorMissionItem](../msg_docs/NavigatorMissionItem.md)
- [SensorGyroFft](../msg_docs/SensorGyroFft.md)
- [FigureEightStatus](../msg_docs/FigureEightStatus.md)
- [RegisterExtComponentReplyV0](../msg_docs/RegisterExtComponentReplyV0.md)
- [HomePositionV0](../msg_docs/HomePositionV0.md)
- [GimbalManagerInformation](../msg_docs/GimbalManagerInformation.md)
- [UavcanParameterRequest](../msg_docs/UavcanParameterRequest.md)
- [DeviceInformation](../msg_docs/DeviceInformation.md)
- [IrlockReport](../msg_docs/IrlockReport.md)
- [InternalCombustionEngineStatus](../msg_docs/InternalCombustionEngineStatus.md)
- [WheelEncoders](../msg_docs/WheelEncoders.md)
- [VehicleOpticalFlowVel](../msg_docs/VehicleOpticalFlowVel.md)
- [VehicleMagnetometer](../msg_docs/VehicleMagnetometer.md)
- [SensorUwb](../msg_docs/SensorUwb.md)
- [EstimatorBias](../msg_docs/EstimatorBias.md)
- [VehicleStatusV2](../msg_docs/VehicleStatusV2.md)
- [GpioConfig](../msg_docs/GpioConfig.md)
- [QshellReq](../msg_docs/QshellReq.md)
- [CanInterfaceStatus](../msg_docs/CanInterfaceStatus.md)
- [PurePursuitStatus](../msg_docs/PurePursuitStatus.md)
- [SensorTemp](../msg_docs/SensorTemp.md)
- [PpsCapture](../msg_docs/PpsCapture.md)
- [SensorsStatus](../msg_docs/SensorsStatus.md)
- [VehicleLocalPositionSetpoint](../msg_docs/VehicleLocalPositionSetpoint.md)
- [RaptorStatus](../msg_docs/RaptorStatus.md)
- [DebugArray](../msg_docs/DebugArray.md)
- [EscStatus](../msg_docs/EscStatus.md)
- [VehicleAngularVelocity](../msg_docs/VehicleAngularVelocity.md)
- [RoverAttitudeStatus](../msg_docs/RoverAttitudeStatus.md)
- [AutotuneAttitudeControlStatus](../msg_docs/AutotuneAttitudeControlStatus.md)
- [EstimatorBias3d](../msg_docs/EstimatorBias3d.md)
- [OpenDroneIdArmStatus](../msg_docs/OpenDroneIdArmStatus.md)
- [MavlinkTunnel](../msg_docs/MavlinkTunnel.md)
- [Event](../msg_docs/Event.md)
:::
-100
View File
@@ -1,100 +0,0 @@
# Holybro SiK Telemetry Radio - Long Range
This Holybro SiK Long Range Telemetry Radio is a small, light, and inexpensive open-source radio platform with an extended range (~20km) compared to the standard model.
This radio is plug-and-play, ready for all Pixhawk Standard and other similar flight controllers, providing the easiest way to set up a telemetry connection between your controller and a ground station.
It uses open-source firmware that has been specially designed to work well with MAVLink packets and to be integrated with PX4, ArduPilot, Mission Planner and QGroundControl.
The radios are available in 915 MHz or 433 MHz versions.
Please purchase the model that is appropriate for your country/region.
![Sik Telemetry Radio - Long Range](../../assets/hardware/telemetry/holybro_sik_longrange/holybro_sik_longrange.jpg)
## Where to Buy
- [Holybro SiK Telemetry Radio - Long Range](https://holybro.com/collections/telemetry-radios/products/sik-telemetry-radio-1w)
## Features
- 1W maximum RF output and up to 20km range (compared to 100mW/300m for the short range version).
- Open-source SIK firmware
- Plug-n-play for Pixhawk Standard Flight Controllers
- The Easiest way to connect your controller and Ground Station
- Interchangeable air and ground radio
- 6-position JST-GH connector
## Specification
- 1 W maximum output power (adjustable) -117 dBm receive sensitivity
- RP-SMA connector
- 2-way full-duplex communication through adaptive TDM UART interface
- Transparent serial link
- MAVLink protocol framing
- Frequency Hopping Spread Spectrum (FHSS) Configurable duty cycle
- Error correction corrects up to 25% of bit errors Open-source SIK firmware
- Configurable through Mission Planner & APM Planner
- FT230X USB to BASIC UART IC
- USB Type C connector
- XT30 power connector for 7~28V DC input
## LEDs Indicators Status
The radios have four status LEDs.
The USB `RX` and `TX` LEDs indicate the status of reception and transmission of the USB port.
The `RADIO` and `ACT` two LED lights indicate the status of the RF circuit.
- USB-TX LED (orange):
- Blinking: USB port has data transmission
- Off: USB port has no data transmission
- USB-RX LED (orange):
- Blinking: USB port has data reception
- Off: USB port has no data reception
- Radio LED (Green)
- Blinking: Searching for another radio
- Solid: Link is established with another radio
- ACT LED (Red)
- Flashing: Transmitting data
- Solid: In firmware update mode
![Holybro SiK LongRange LED Indicators](../../assets/hardware/telemetry/holybro_sik_longrange/holybro_sik_longrange_label.png)
## Connecting to Flight Controller
Supply the power (7~28V) to the radio via the XT30 connector.
Use the 6-pin JST-GH connector that comes with the radio to connect the radio to your flight controller's `TELEM1` port.
Note that `TELEM2` can also be used, but you may need to [configure the telemetry port](../peripherals/mavlink_peripherals.md) on some flight controllers.
## Connecting to a PC or Ground Station
First, power the module with a 7~28V DC source.
Then, connect the radio to your Windows PC or Ground Station using a Type-C USB cable.
The necessary drivers should be installed automatically, and the radio will appear as a new “USB Serial Port” in the Windows Device Manager under Ports (COM & LPT).
The Mission Planner's COM Port selection drop-down should also include the newly added COM port.
## Packages Include
### Single Radio
- 1W Radio modules with antennas (1)
- High-gain omnidirectional antenna (1)
- Male Type-C to male Type-C USB cable (1)
- Male XT30 to female XT30 adapter cable (1)
- Male XT30 to female XT60 adapter cable (1)
- JST-GH-6P to JST-GH-6P cable (1) (for Pixhawk Standard FC)
- Rubber damping grommet (3)
![Sik Telemetry Radio - LongRange Package1](../../assets/hardware/telemetry/holybro_sik_longrange/holybro_sik_longrange_include1.png)
### Pair Radios
- 1W Radio modules with antennas (2)
- High-gain omnidirectional antenna (2)
- Male Type-C to male Type-C USB cable (1)
- Male XT30 to female XT30 adapter cable (1)
- Male XT30 to female XT60 adapter cable (1)
- JST-GH-6P to JST-GH-6P cable (1) (for Pixhawk Standard FC)
- Rubber damping grommet (3)
![Sik Telemetry Radio - LongRange Package2](../../assets/hardware/telemetry/holybro_sik_longrange/holybro_sik_longrange_include2.png)
-1
View File
@@ -6,7 +6,6 @@ PX4 supports a number of types of telemetry radios:
- [SiK Radio](../telemetry/sik_radio.md) based firmware (more generally, any radio with a UART interface should work).
- [HolyBro SiK Telemetry Radio](../telemetry/holybro_sik_radio.md)
- [HolyBro SiK Long Range](../telemetry/holybro_sik_longrange.md)
- [RFD900 Telemetry Radio](../telemetry/rfd900_telemetry.md)
- [ThunderFly TFSIK01 Telemetry Radio](../telemetry/tfsik_telemetry.md)
- <del>_HKPilot Telemetry Radio_</del> (Discontinued)
-1
View File
@@ -14,7 +14,6 @@ Hardware for the SiK radio can be obtained from various manufacturers/stores in
## Vendors
- [Holybro Telemetry Radio](../telemetry/holybro_sik_radio.md)
- [HolyBro SiK Long Range](../telemetry/holybro_sik_longrange.md)
- [RFD900 Telemetry Radio](../telemetry/rfd900_telemetry.md)
- [ThunderFly TFSIK01 Telemetry Radio](../telemetry/tfsik_telemetry.md)
- <del>_HKPilot Telemetry Radio_</del> (Discontinued)
File diff suppressed because one or more lines are too long
Binary file not shown.
File diff suppressed because one or more lines are too long
+1 -1
View File
@@ -193,7 +193,7 @@ config WQ_HP_DEFAULT_PRIORITY
config WQ_UAVCAN_STACKSIZE
int "Stack size for uavcan"
default 3754
default 3624
range 1000 10000
help
Sets the stack size for the uavcan work queue.
+1 -30
View File
@@ -31,33 +31,4 @@
*
****************************************************************************/
#pragma once
#include <stdint.h>
#include <board_config.h>
#if defined(CONFIG_I2C)
__BEGIN_DECLS
struct i2c_master_s;
struct i2c_msg_s {
uint32_t frequency;
uint16_t addr;
uint16_t flags;
uint8_t *buffer;
int length;
};
#define I2C_M_READ 0x0001
#define I2C_TRANSFER(dev, msgs, count) px4_qurt_i2c_transfer(dev, msgs, count)
struct i2c_master_s *px4_i2cbus_initialize(int bus);
int px4_i2cbus_uninitialize(struct i2c_master_s *dev);
int px4_qurt_i2c_transfer(struct i2c_master_s *dev, struct i2c_msg_s *msgs, unsigned count);
__END_DECLS
#endif /* CONFIG_I2C */
// Placeholder
-2
View File
@@ -40,7 +40,6 @@ set(QURT_LAYER_SRCS
main.cpp
qurt_log.cpp
SerialImpl.cpp
px4_i2c.cpp
)
add_library(px4_layer
@@ -49,4 +48,3 @@ add_library(px4_layer
target_link_libraries(px4_layer PRIVATE work_queue)
target_link_libraries(px4_layer PRIVATE drivers_board)
target_link_libraries(px4_layer PRIVATE drivers__device)
-164
View File
@@ -1,164 +0,0 @@
/****************************************************************************
*
* Copyright (C) 2022 ModalAI, Inc. 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 px4_i2c.cpp
*
* NuttX-compatible I2C API shim for QuRT/SLPI.
* Implements px4_i2cbus_initialize/uninitialize and I2C_TRANSFER
* on top of the QuRT device::I2C callback infrastructure by deriving
* from device::I2C to access its protected transfer methods.
*/
#include <px4_platform_common/px4_config.h>
#include <px4_platform_common/log.h>
#include <px4_arch/micro_hal.h>
#if defined(CONFIG_I2C)
#include <lib/drivers/device/qurt/I2C.hpp>
/**
* Minimal derived class that exposes the protected I2C::transfer()
* and I2C::set_device_address() for use by the compatibility shim.
*/
class I2CShim : public device::I2C
{
public:
I2CShim(int bus) :
I2C(0, "i2c_shim", bus, 0x01, 100000)
{}
int do_transfer(uint8_t addr, const uint8_t *send, unsigned send_len,
uint8_t *recv, unsigned recv_len)
{
set_device_address(addr, false);
return transfer(send, send_len, recv, recv_len);
}
};
struct i2c_master_s {
I2CShim *shim;
};
struct i2c_master_s *px4_i2cbus_initialize(int bus)
{
auto *shim = new I2CShim(bus);
if (shim == nullptr) {
return nullptr;
}
if (shim->init() != PX4_OK) {
delete shim;
return nullptr;
}
auto *dev = new i2c_master_s;
if (dev == nullptr) {
delete shim;
return nullptr;
}
dev->shim = shim;
return dev;
}
int px4_i2cbus_uninitialize(struct i2c_master_s *dev)
{
if (dev != nullptr) {
delete dev->shim;
delete dev;
}
return PX4_OK;
}
int px4_qurt_i2c_transfer(struct i2c_master_s *dev, struct i2c_msg_s *msgs, unsigned count)
{
if (dev == nullptr || dev->shim == nullptr || msgs == nullptr || count == 0) {
return PX4_ERROR;
}
unsigned i = 0;
while (i < count) {
struct i2c_msg_s *msg = &msgs[i];
// Check for write+read pair to the same address (common i2cdetect pattern)
if ((i + 1 < count) &&
!(msg->flags & I2C_M_READ) &&
(msgs[i + 1].flags & I2C_M_READ) &&
(msg->addr == msgs[i + 1].addr)) {
int ret = dev->shim->do_transfer(msg->addr,
msg->buffer, msg->length,
msgs[i + 1].buffer, msgs[i + 1].length);
if (ret != PX4_OK) {
return ret;
}
i += 2;
} else if (msg->flags & I2C_M_READ) {
// Single read
int ret = dev->shim->do_transfer(msg->addr,
nullptr, 0,
msg->buffer, msg->length);
if (ret != PX4_OK) {
return ret;
}
i++;
} else {
// Single write
int ret = dev->shim->do_transfer(msg->addr,
msg->buffer, msg->length,
nullptr, 0);
if (ret != PX4_OK) {
return ret;
}
i++;
}
}
return PX4_OK;
}
#endif /* CONFIG_I2C */
@@ -49,7 +49,7 @@ parameters:
default: 0
reboot_required: true
min: 0
max: 3
max: 2
VOXL_ESC_SDIR1:
description:
short: UART ESC ID 1 Spin Direction Flag
@@ -16,4 +16,4 @@ parameters:
default: 0
reboot_required: true
min: 0
max: 5
max: 3
+1 -1
View File
@@ -126,7 +126,7 @@ parameters:
6: Ground Control Station (UART2 outputs NMEA)
default: 0
min: 0
max: 6
max: 1
reboot_required: true
GPS_UBX_BAUD2:
description:
+1 -1
View File
@@ -93,7 +93,7 @@ parameters:
default: 14
reboot_required: true
min: 0
max: 19
max: 15
ADSB_MAX_SPEED:
description:
short: ADSB-Out Vehicle Max Speed
+2 -4
View File
@@ -158,12 +158,10 @@ out:
}
void
I2C::set_device_address(int address, bool log)
I2C::set_device_address(int address)
{
if ((_i2c_fd != PX4_ERROR) && (_set_i2c_address != NULL)) {
if (log) {
PX4_INFO("Set i2c address 0x%x, fd %d", address, _i2c_fd);
}
PX4_INFO("Set i2c address 0x%x, fd %d", address, _i2c_fd);
pthread_mutex_lock(_mutex);
_set_i2c_address(_i2c_fd, address);
+1 -1
View File
@@ -103,7 +103,7 @@ protected:
*/
virtual int probe() { return PX4_OK; }
virtual void set_device_address(int address, bool log = true);
virtual void set_device_address(int address);
/**
* Perform an I2C transaction to the device.
@@ -141,6 +141,17 @@ void ModeChecks::checkAndReport(const Context &context, Report &reporter)
reporter.clearCanRunBits((NavModes)reporter.failsafeFlags().mode_req_mission);
}
if (reporter.failsafeFlags().offboard_control_signal_lost && reporter.failsafeFlags().mode_req_offboard_signal != 0) {
/* EVENT
* @description
* The offboard component is not sending setpoints or the required estimate (e.g. position) is missing.
*/
reporter.armingCheckFailure((NavModes)reporter.failsafeFlags().mode_req_offboard_signal, health_component_t::system,
events::ID("check_modes_offboard_signal"),
events::Log::Error, "No offboard signal");
reporter.clearCanRunBits((NavModes)reporter.failsafeFlags().mode_req_offboard_signal);
}
if (reporter.failsafeFlags().home_position_invalid && reporter.failsafeFlags().mode_req_home_position != 0) {
/* EVENT
*/
@@ -40,9 +40,6 @@ void OffboardChecks::checkAndReport(const Context &context, Report &reporter)
reporter.failsafeFlags().offboard_control_signal_lost = true;
offboard_control_mode_s offboard_control_mode;
const NavModes affected_modes = (NavModes)reporter.failsafeFlags().mode_req_offboard_signal;
const bool has_affected_modes = affected_modes != NavModes::None;
bool has_specific_reason = false;
if (_offboard_control_mode_sub.copy(&offboard_control_mode)) {
@@ -55,63 +52,16 @@ void OffboardChecks::checkAndReport(const Context &context, Report &reporter)
if (offboard_control_mode.position && reporter.failsafeFlags().local_position_invalid) {
offboard_available = false;
has_specific_reason = true;
if (has_affected_modes) {
/* EVENT
* @description
* Offboard position control requires a valid local position estimate.
*/
reporter.armingCheckFailure(affected_modes, health_component_t::system,
events::ID("check_modes_offboard_no_local_position"),
events::Log::Error, "Offboard requires local position");
reporter.clearCanRunBits(affected_modes);
}
} else if (offboard_control_mode.velocity && reporter.failsafeFlags().local_velocity_invalid) {
offboard_available = false;
has_specific_reason = true;
if (has_affected_modes) {
/* EVENT
* @description
* Offboard velocity control requires a valid local velocity estimate.
*/
reporter.armingCheckFailure(affected_modes, health_component_t::system,
events::ID("check_modes_offboard_no_local_velocity"),
events::Log::Error, "Offboard requires local velocity");
reporter.clearCanRunBits(affected_modes);
}
} else if ((offboard_control_mode.acceleration || offboard_control_mode.attitude)
&& reporter.failsafeFlags().attitude_invalid) {
} else if (offboard_control_mode.acceleration && reporter.failsafeFlags().attitude_invalid) {
// OFFBOARD acceleration handled by position controller
offboard_available = false;
has_specific_reason = true;
if (has_affected_modes) {
/* EVENT
* @description
* Offboard acceleration and attitude control require a valid attitude estimate.
*/
reporter.armingCheckFailure(affected_modes, health_component_t::system,
events::ID("check_modes_offboard_no_attitude"),
events::Log::Error, "Offboard requires attitude estimate");
reporter.clearCanRunBits(affected_modes);
}
}
// This is a mode requirement, no need to report
reporter.failsafeFlags().offboard_control_signal_lost = !offboard_available;
}
if (reporter.failsafeFlags().offboard_control_signal_lost && !has_specific_reason && has_affected_modes) {
/* EVENT
* @description
* The offboard component is not sending recent setpoints.
*/
reporter.armingCheckFailure(affected_modes, health_component_t::system,
events::ID("check_modes_offboard_signal_lost"),
events::Log::Error, "No offboard signal");
reporter.clearCanRunBits(affected_modes);
}
}
+1 -1
View File
@@ -507,7 +507,7 @@ parameters:
4: Terminate
default: 0
min: 0
max: 4
max: 3
COM_PARACHUTE:
description:
short: Require MAVLink parachute system to be present and healthy
@@ -186,15 +186,8 @@ private:
int _num_actuators[(int)ActuatorType::COUNT] {};
// Inputs
//
// Torque and thrust setpoints are usually published together.
// Only torque drives the callback so control allocation runs once, then Run() reads the latest thrust.
// Refs:
// - https://github.com/PX4/PX4-Autopilot/pull/24955
// - https://github.com/PX4/PX4-Autopilot/issues/24230
// - https://github.com/PX4/PX4-Autopilot/issues/26971
uORB::SubscriptionCallbackWorkItem _vehicle_torque_setpoint_sub{this, ORB_ID(vehicle_torque_setpoint)}; /**< vehicle torque setpoint subscription */
uORB::Subscription _vehicle_thrust_setpoint_sub{ORB_ID(vehicle_thrust_setpoint)}; /**< vehicle thrust setpoint subscription, polled when torque is triggered*/
uORB::Subscription _vehicle_thrust_setpoint_sub{ORB_ID(vehicle_thrust_setpoint)}; /**< vehicle thrust setpoint subscription */
uORB::Subscription _vehicle_torque_setpoint1_sub{ORB_ID(vehicle_torque_setpoint), 1}; /**< vehicle torque setpoint subscription (2. instance) */
uORB::Subscription _vehicle_thrust_setpoint1_sub{ORB_ID(vehicle_thrust_setpoint), 1}; /**< vehicle thrust setpoint subscription (2. instance) */
@@ -105,7 +105,7 @@ FixedwingAttitudeControl::vehicle_manual_poll(const float yaw_body)
pitch_body = constrain(pitch_body,
-radians(_param_fw_man_p_max.get()), radians(_param_fw_man_p_max.get()));
const Quatf q_sp_rp = Eulerf(roll_body, pitch_body, 0.f);
const Quatf q_sp_rp = AxisAnglef(roll_body, pitch_body, 0.f);
const Quatf q_sp_yaw(cosf(yaw_body / 2.f), 0.f, 0.f, sinf(yaw_body / 2.f));
Quatf q = q_sp_yaw * q_sp_rp;
+1 -1
View File
@@ -72,7 +72,7 @@ parameters:
23: VTOL Tailsitter
default: 0
min: 0
max: 23
max: 22
MAV_USEHILGPS:
description:
short: Use/Accept HIL GPS message even if not in HIL mode
+12 -14
View File
@@ -1054,18 +1054,6 @@ MavlinkReceiver::handle_message_att_pos_mocap(mavlink_message_t *msg)
_mocap_odometry_pub.publish(odom);
}
offboard_control_mode_s
MavlinkReceiver::fill_offboard_control_mode(const trajectory_setpoint_s &setpoint)
{
offboard_control_mode_s ocm{};
ocm.position = !matrix::Vector3f(setpoint.position).isAllNan();
ocm.velocity = !matrix::Vector3f(setpoint.velocity).isAllNan();
ocm.acceleration = !matrix::Vector3f(setpoint.acceleration).isAllNan();
ocm.attitude = PX4_ISFINITE(setpoint.yaw);
ocm.body_rate = PX4_ISFINITE(setpoint.yawspeed);
return ocm;
}
void
MavlinkReceiver::handle_message_set_position_target_local_ned(mavlink_message_t *msg)
{
@@ -1152,7 +1140,12 @@ MavlinkReceiver::handle_message_set_position_target_local_ned(mavlink_message_t
setpoint.yawspeed = (type_mask & POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE) ? (float)NAN : target_local_ned.yaw_rate;
offboard_control_mode_s ocm = fill_offboard_control_mode(setpoint);
offboard_control_mode_s ocm{};
ocm.position = !matrix::Vector3f(setpoint.position).isAllNan();
ocm.velocity = !matrix::Vector3f(setpoint.velocity).isAllNan();
ocm.acceleration = !matrix::Vector3f(setpoint.acceleration).isAllNan();
ocm.attitude = PX4_ISFINITE(setpoint.yaw);
ocm.body_rate = PX4_ISFINITE(setpoint.yawspeed);
if (ocm.acceleration && (type_mask & POSITION_TARGET_TYPEMASK_FORCE_SET)) {
mavlink_log_critical(&_mavlink_log_pub, "SET_POSITION_TARGET_LOCAL_NED force not supported\t");
@@ -1271,7 +1264,12 @@ MavlinkReceiver::handle_message_set_position_target_global_int(mavlink_message_t
setpoint.yawspeed = (type_mask & POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE) ? (float)NAN : target_global_int.yaw_rate;
offboard_control_mode_s ocm = fill_offboard_control_mode(setpoint);
offboard_control_mode_s ocm{};
ocm.position = !matrix::Vector3f(setpoint.position).isAllNan();
ocm.velocity = !matrix::Vector3f(setpoint.velocity).isAllNan();
ocm.acceleration = !matrix::Vector3f(setpoint.acceleration).isAllNan();
ocm.attitude = PX4_ISFINITE(setpoint.yaw);
ocm.body_rate = PX4_ISFINITE(setpoint.yawspeed);
if (ocm.acceleration && (type_mask & POSITION_TARGET_TYPEMASK_FORCE_SET)) {
mavlink_log_critical(&_mavlink_log_pub, "SET_POSITION_TARGET_GLOBAL_INT force not supported\t");
-2
View File
@@ -248,8 +248,6 @@ private:
void fill_thrust(float *thrust_body_array, uint8_t vehicle_type, float thrust);
static offboard_control_mode_s fill_offboard_control_mode(const trajectory_setpoint_s &setpoint);
void schedule_tune(const char *tune);
void update_message_statistics(const mavlink_message_t &message);
@@ -15,7 +15,7 @@ parameters:
5: yaw fixed
default: 0
min: 0
max: 5
max: 4
- group: Multicopter Attitude Control
definitions:
MPC_YAWRAUTO_MAX:
@@ -108,9 +108,12 @@ void SensorAirspeedSim::Run()
updateParams();
}
if (_sim_failure.get() == 0) {
if (_vehicle_local_position_sub.updated() && _vehicle_global_position_sub.updated()
&& _vehicle_attitude_sub.updated()) {
if (_vehicle_local_position_sub.updated() && _vehicle_global_position_sub.updated()
&& _vehicle_attitude_sub.updated()) {
check_failure_injection();
if (!_airspeed_disconnected) {
vehicle_local_position_s lpos{};
_vehicle_local_position_sub.copy(&lpos);
@@ -136,26 +139,95 @@ void SensorAirspeedSim::Run()
const float density_ratio = powf(TEMPERATURE_MSL / temperature_local, 4.256f);
const float air_density = AIR_DENSITY_MSL / density_ratio;
// calculate differential pressure + noise in hPa
const float diff_pressure_noise = (float)generate_wgn() * 0.01f;
float diff_pressure = sign(body_velocity(0)) * 0.005f * air_density * body_velocity(0) * body_velocity(
0) + diff_pressure_noise;
if (!_airspeed_stuck) {
// calculate differential pressure + noise in hPa
const float diff_pressure_noise = (float)generate_wgn() * 0.01f;
float diff_pressure = sign(body_velocity(0)) * 0.005f * air_density * body_velocity(0) * body_velocity(
0) + diff_pressure_noise;
// simulate pitot blockage: ramp down differential pressure over time
const float blockage_fraction = 0.7f; // max blockage (fully ramped)
const float airspeed_blockage_rampup_time = 30_s;
float airspeed_blockage_scale = 1.f;
if (_airspeed_blocked_timestamp > 0) {
airspeed_blockage_scale = math::constrain(1.f - (hrt_absolute_time() - _airspeed_blocked_timestamp) /
airspeed_blockage_rampup_time, 1.f - blockage_fraction, 1.f);
}
_last_differential_pressure_pa = diff_pressure * 100.0f * airspeed_blockage_scale; // hPa to Pa
}
differential_pressure_s differential_pressure{};
// report.timestamp_sample = time;
differential_pressure.device_id = 1377548; // 1377548: DRV_DIFF_PRESS_DEVTYPE_SIM, BUS: 1, ADDR: 5, TYPE: SIMULATION
differential_pressure.differential_pressure_pa = (double)diff_pressure * 100.0; // hPa to Pa;
differential_pressure.differential_pressure_pa = _last_differential_pressure_pa;
differential_pressure.temperature = temperature_local + ABSOLUTE_ZERO_C; // K to C
differential_pressure.timestamp = hrt_absolute_time();
_differential_pressure_pub.publish(differential_pressure);
}
}
perf_end(_loop_perf);
}
void SensorAirspeedSim::check_failure_injection()
{
vehicle_command_s vehicle_command;
while (_vehicle_command_sub.update(&vehicle_command)) {
if (vehicle_command.command != vehicle_command_s::VEHICLE_CMD_INJECT_FAILURE) {
continue;
}
bool handled = false;
bool supported = false;
const int failure_unit = static_cast<int>(std::lround(vehicle_command.param1));
const int failure_type = static_cast<int>(std::lround(vehicle_command.param2));
if (failure_unit == vehicle_command_s::FAILURE_UNIT_SENSOR_AIRSPEED) {
handled = true;
if (failure_type == vehicle_command_s::FAILURE_TYPE_OFF) {
PX4_WARN("CMD_INJECT_FAILURE, airspeed off");
supported = true;
_airspeed_disconnected = true;
} else if (failure_type == vehicle_command_s::FAILURE_TYPE_STUCK) {
PX4_WARN("CMD_INJECT_FAILURE, airspeed stuck");
supported = true;
_airspeed_stuck = true;
} else if (failure_type == vehicle_command_s::FAILURE_TYPE_WRONG) {
PX4_WARN("CMD_INJECT_FAILURE, airspeed wrong (simulate pitot blockage)");
supported = true;
_airspeed_blocked_timestamp = hrt_absolute_time();
} else if (failure_type == vehicle_command_s::FAILURE_TYPE_OK) {
PX4_INFO("CMD_INJECT_FAILURE, airspeed ok");
supported = true;
_airspeed_disconnected = false;
_airspeed_stuck = false;
_airspeed_blocked_timestamp = 0;
}
}
if (handled) {
vehicle_command_ack_s ack{};
ack.command = vehicle_command.command;
ack.from_external = false;
ack.result = supported ?
vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED :
vehicle_command_ack_s::VEHICLE_CMD_RESULT_UNSUPPORTED;
ack.timestamp = hrt_absolute_time();
_command_ack_pub.publish(ack);
}
}
}
int SensorAirspeedSim::task_spawn(int argc, char *argv[])
{
SensorAirspeedSim *instance = new SensorAirspeedSim();
@@ -34,16 +34,21 @@
#pragma once
#include <lib/perf/perf_counter.h>
#include <math.h>
#include <mathlib/mathlib.h>
#include <px4_platform_common/defines.h>
#include <px4_platform_common/module.h>
#include <px4_platform_common/module_params.h>
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
#include <uORB/Publication.hpp>
#include <uORB/PublicationMulti.hpp>
#include <uORB/Subscription.hpp>
#include <uORB/SubscriptionInterval.hpp>
#include <uORB/topics/parameter_update.h>
#include <uORB/topics/differential_pressure.h>
#include <uORB/topics/parameter_update.h>
#include <uORB/topics/vehicle_attitude.h>
#include <uORB/topics/vehicle_command.h>
#include <uORB/topics/vehicle_command_ack.h>
#include <uORB/topics/vehicle_global_position.h>
#include <uORB/topics/vehicle_local_position.h>
@@ -74,6 +79,8 @@ public:
bool init();
void check_failure_injection();
private:
void Run() override;
@@ -87,12 +94,15 @@ private:
uORB::Subscription _vehicle_attitude_sub{ORB_ID(vehicle_attitude)};
uORB::Subscription _vehicle_global_position_sub{ORB_ID(vehicle_global_position_groundtruth)};
uORB::Subscription _vehicle_local_position_sub{ORB_ID(vehicle_local_position_groundtruth)};
uORB::Subscription _vehicle_command_sub{ORB_ID(vehicle_command)};
uORB::PublicationMulti<differential_pressure_s> _differential_pressure_pub{ORB_ID(differential_pressure)};
uORB::Publication<vehicle_command_ack_s> _command_ack_pub{ORB_ID(vehicle_command_ack)};
bool _airspeed_disconnected{false};
bool _airspeed_stuck{false};
hrt_abstime _airspeed_blocked_timestamp{0};
float _last_differential_pressure_pa{0.f};
perf_counter_t _loop_perf{perf_alloc(PC_ELAPSED, MODULE_NAME": cycle")};
DEFINE_PARAMETERS(
(ParamInt<px4::params::SIM_ARSPD_FAIL>) _sim_failure
)
};
@@ -13,14 +13,3 @@ parameters:
reboot_required: true
min: 0
max: 1
SIM_ARSPD_FAIL:
description:
short: Dynamically simulate failure of airspeed sensor instance
type: enum
values:
0: Disabled
1: Enabled
default: 0
reboot_required: true
min: 0
max: 1
@@ -65,243 +65,6 @@
#include <conversion/rotation.h> // math::radians,
// #include <lib/mathlib/mathlib.h>
#include <math.h>
#include <px4_platform_common/defines.h> // PX4_ISFINITE
#include <px4_platform_common/log.h> // PX4_INFO
// class Thruster using the terminology from UIUC Propeller Data site https://m-selig.ae.illinois.edu/props/propDB.html
class Thruster
{
private:
static constexpr float INCH_TO_M = 0.0254f;
float CT0, CT1, CT2, CP0, CP1, CP2;
float _d_m;
float _rpm_max;
float T_MAX;
float Q_MAX;
public:
// public implicit constructor
Thruster() : Thruster(0.1f, 1000.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f) {}
/** public explicit constructor for static model
* using the maximum thrust and torque.
* In this case, the prop diameter and RPM are not needed.
*/
Thruster(float Tmax, float Qmax)
{
_d_m = 0.0f;
_rpm_max = 0.0f;
CT0 = 0.0f;
CT1 = 0.0f;
CT2 = 0.0f;
CP0 = 0.0f;
CP1 = 0.0f;
CP2 = 0.0f;
T_MAX = Tmax;
Q_MAX = Qmax;
}
/** public explicit constructor
* - prop_dia_inch: propeller diameter in inches
* - rpm_max: max RPM
* - ct0, ct1, ct2: second order thrust coefficient
* - cp0, cp1, cp2: second order power coefficient
*/
Thruster(float prop_dia_inch, float rpm_max, float ct0, float ct1, float ct2, float cp0, float cp1, float cp2)
{
_d_m = dia_inch_to_m(prop_dia_inch);
_rpm_max = rpm_max;
CT0 = ct0;
CT1 = ct1;
CT2 = ct2;
CP0 = cp0;
CP1 = cp1;
CP2 = cp2;
// Initialize T_MAX and Q_MAX before they may be used inside the compute_* helpers
T_MAX = 0.0f;
Q_MAX = 0.0f;
T_MAX = compute_thrust_from_throttle(1.0f);
Q_MAX = compute_torque_from_throttle(1.0f);
}
/** advance_ratio(float n_rev_s, float vx_ms)
* compute the advance ratio J = vx_ms / n_rev_s / d_m
* with
* - n_rev_s is the propeller rotational speed in revolution/s
* - vx_ms is the valocity seen by the thruster in m/s,
* usually projected on the propeller revolution axis
*/
float advance_ratio(float n_rev_s, float vx_ms)
{
return vx_ms / n_rev_s / _d_m;
}
/** fCT(float J, float ct0, float ct1, float ct2)
* Compute the thrust coefficient ct from the advance ratio J
*
*/
float fCT(float J)
{
if (!PX4_ISFINITE(J)) {
return 0;
}
// do not allow ct < 0 (i.e. windmill)
return fmaxf(CT0 + CT1 * J + CT2 * J * J, 0.0f);
}
/** fCP(float J, float cp0, float cp1, float cp2)
* Compute the power coefficient cp from the advance ratio J
*
*/
float fCP(float J)
{
if (!PX4_ISFINITE(J)) {
return 0;
}
return fmaxf(CP0 + CP1 * J + CP2 * J * J, 0.0f);
}
/** compute_thrust(float n_rev_s, float vx_ms=0.0f, float rho=1.225f)
* Compute the thrust force in (N) given
* - n_rev_s is the propeller rotational speed in revolution/s
* - vx_ms is the velocity seen by the thruster in m/s,
* usually projected on the propeller revolution axis
* - rho is the density in kg/m^3
*/
float compute_thrust(float n_rev_s, float vx_ms = 0.0f, float rho = 1.225f)
{
if (CT0 <= 0.0f || n_rev_s <= 1.0e-4f) {
return 0.0f;
}
float J = advance_ratio(n_rev_s, vx_ms);
return fCT(J) * rho * n_rev_s * n_rev_s * _d_m * _d_m * _d_m * _d_m;
}
/** compute_thrust_from_throttle(float u, float vx_ms=0.0f, float rho=1.225f)
* Compute the thrust force in (N) given
* - u is the thruster unit throttle in range [0,1]
* - vx_ms is the velocity seen by the thruster in m/s,
* usually projected on the propeller revolution axis
* - rho is the density in kg/m^3
*/
float compute_thrust_from_throttle(float u, float vx_ms = 0.0f, float rho = 1.225f)
{
if (CT0 <= 0.0f) {
return T_MAX * u;
}
float n_rev_s = throttle_to_rev_s(u, _rpm_max);
return compute_thrust(n_rev_s, vx_ms, rho);
}
/** compute_torque(float n_rev_s, float vx_ms=0.0f, float rho=1.225f)
* Compute the propeller torque in (Nm) given
* - n_rev_s is the propeller rotational speed in revolution/s
* - vx_ms is the velocity seen by the thruster in m/s,
* usually projected on the propeller revolution axis
* - rho is the density in kg/m^3
*/
float compute_torque(float n_rev_s, float vx_ms = 0.0f, float rho = 1.225f)
{
if (CP0 <= 0.0f || n_rev_s <= 1.0e-4f) {
return 0.0f;
}
float J = advance_ratio(n_rev_s, vx_ms);
float cq = fCP(J) / 2.0f / M_PI_F;
return cq * rho * n_rev_s * n_rev_s * _d_m * _d_m * _d_m * _d_m * _d_m;
}
/** compute_torque_from_throttle(float u, float vx_ms=0.0f, float rho=1.225f)
* Compute the propeller torque in (Nm) given
* - u is the thruster unit throttle in range [0,1]
* - vx_ms is the velocity seen by the thruster in m/s,
* usually projected on the propeller revolution axis
* - rho is the density in kg/m^3
*/
float compute_torque_from_throttle(float u, float vx_ms = 0.0f, float rho = 1.225f)
{
if (CP0 <= 0.0f) {
return Q_MAX * u;
}
float n_rev_s = throttle_to_rev_s(u, _rpm_max);
return compute_torque(n_rev_s, vx_ms, rho);
}
/** dia_inch_to_m(float dia_inch)
* compute the propeller diameter in meter,
* given dia_inch the propeller diameter in inches.
*/
static float dia_inch_to_m(float dia_inch)
{
return dia_inch * INCH_TO_M;
}
/** rpm_to_rev_s(float rpm)
* compute the propeller revolutions per seconds,
* given the propeller rpm.
*/
static float rpm_to_rev_s(float rpm)
{
return rpm / 60.0f;
}
/** rev_s_to_rpm(float n_rev_s)
* compute the propeller rpm,
* given the propeller revolutions per seconds.
*/
static float rev_s_to_rpm(float n_rev_s)
{
return n_rev_s * 60.0f;
}
/** throttle_to_rpm(float throttle, const float rpm_max)
* compute the propeller rpm,
* given the unit throttle u (in range [0,1])
* and the max RPM rpm_max.
*/
static float throttle_to_rpm(float u, const float rpm_max)
{
return rpm_max * sqrtf(fminf(fmaxf(u, 0.0f), 1.0f));
}
/** throttle_to_rev_s(float throttle, const float rpm_max)
* compute the propeller revolution per seconds,
* given the unit throttle u (in range [0,1])
* and the max RPM rpm_max.
*/
static float throttle_to_rev_s(float u, const float rpm_max)
{
return rpm_to_rev_s(throttle_to_rpm(u, rpm_max));
}
float get_T_max()
{
return T_MAX;
}
float get_Q_max()
{
return Q_MAX;
}
void print_status()
{
if (CT0 <= 0.0f) {
PX4_INFO("Thruster simple model: Tmax %.4f N, Qmax %.4f Nm", (double)T_MAX, (double)Q_MAX);
} else {
PX4_INFO("Thruster dyn. model: dia %.4f m, max rpm %.0f, Tmax %.4f N, Qmax %.4f Nm",
(double)_d_m, (double)_rpm_max, (double)T_MAX, (double)Q_MAX);
PX4_INFO(" Tmax: %.3f N at 10 m/s, %.3f N at 20 m/s",
(double)compute_thrust_from_throttle(1.0f, 10.0f), (double)compute_thrust_from_throttle(1.0f, 20.0f));
}
}
};
// class Aerodynamic Segment ------------------------------------------------------------------------
class AeroSeg
+29 -74
View File
@@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2019-2026 PX4 Development Team. All rights reserved.
* Copyright (c) 2019-2025 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
@@ -252,37 +252,6 @@ void Sih::parameters_updated()
_L_PITCH = _sih_l_pitch.get();
_KDV = _sih_kdv.get();
_KDW = _sih_kdw.get();
_F_T_MAX = _sih_f_thrust_max.get();
_F_Q_MAX = _sih_f_torque_max.get();
// update the thruster models
for (size_t i = 0; i < NUM_DYN_THRUSTER; i++) {
if (_sih_f_ct0.get() > 0.0f && _sih_f_cp0.get() > 0.0f) {
_thruster[i] = Thruster(_sih_forward_diameter_inch.get(), _sih_forward_rpm_max.get(),
_sih_f_ct0.get(), _sih_f_ct1.get(), _sih_f_ct2.get(),
_sih_f_cp0.get(), _sih_f_cp1.get(), _sih_f_cp2.get());
} else {
_thruster[i] = Thruster(_F_T_MAX, _F_Q_MAX);
}
}
if (_sih_f_ct0.get() > 0.0f && _sih_f_cp0.get() > 0.0f) {
_F_T_MAX = _thruster[0].get_T_max();
_F_Q_MAX = _thruster[0].get_Q_max();
if (fabsf(_F_T_MAX - _sih_f_thrust_max.get()) > 1.0e-5f) {
_sih_f_thrust_max.set(_F_T_MAX);
_sih_f_thrust_max.commit();
PX4_INFO("SIH_F_CT0 > 0, using propeller dynamic model, overriding SIH_F_T_MAX");
}
if (fabsf(_F_Q_MAX - _sih_f_torque_max.get()) > 1.0e-5f) {
_sih_f_torque_max.set(_F_Q_MAX);
_sih_f_torque_max.commit();
PX4_INFO("SIH_F_CP0 > 0, using propeller dynamic model, overriding SIH_F_Q_MAX");
}
}
if (!_lpos_ref.isInitialized()
|| (fabsf(static_cast<float>(_lpos_ref.getProjectionReferenceLat()) - _sih_lat0.get()) > FLT_EPSILON)
@@ -345,11 +314,7 @@ void Sih::read_motors(const float dt)
void Sih::generate_force_and_torques(const float dt)
{
// air-relative velocity in body frame [m/s]
_v_B = _q_E.rotateVectorInverse(_R_N2E * _v_apparent_N);
if (_vehicle == VehicleType::Quadcopter) {
_T_B = Vector3f(0.0f, 0.0f, -_T_MAX * (+_u[0] + _u[1] + _u[2] + _u[3]));
_Mt_B = Vector3f(_L_ROLL * _T_MAX * (-_u[0] + _u[1] + _u[2] - _u[3]),
_L_PITCH * _T_MAX * (+_u[0] - _u[1] + _u[2] - _u[3]),
@@ -375,34 +340,28 @@ void Sih::generate_force_and_torques(const float dt)
_Ma_B = -_KDW * _w_B; // first order angular damper
} else if (_vehicle == VehicleType::FixedWing) {
_T[0] = _thruster[0].compute_thrust_from_throttle(_u[3], _v_B(0));
_Q[0] = _thruster[0].compute_torque_from_throttle(_u[3], _v_B(0));
_T_B = Vector3f(_T[0], 0.0f, 0.0f); // forward thruster
_Mt_B = Vector3f(_Q[0], 0.0f, 0.0f); // thruster torque
generate_fw_aerodynamics(_u[0], _u[1], _u[2], _T[0]);
_T_B = Vector3f(_T_MAX * _u[3], 0.0f, 0.0f); // forward thruster
// _Mt_B = Vector3f(_Q_MAX*_u[3], 0.0f,0.0f); // thruster torque
_Mt_B = Vector3f();
generate_fw_aerodynamics(_u[0], _u[1], _u[2], _u[3]);
} else if (_vehicle == VehicleType::TailsitterVTOL) {
for (size_t i = 0; i < NUM_DYN_THRUSTER; i++) {
_T[i] = _thruster[i].compute_thrust_from_throttle(_u[i], -_v_B(2));
_Q[i] = _thruster[i].compute_torque_from_throttle(_u[i], -_v_B(2));
}
_T_B = Vector3f(0.0f, 0.0f, -_T[0] - _T[1]);
_Mt_B = Vector3f(_L_ROLL * (_T[1] - _T[0]), 0.0f, _Q[1] - _Q[0]);
_T_B = Vector3f(0.0f, 0.0f, -_T_MAX * (_u[0] + _u[1]));
_Mt_B = Vector3f(_L_ROLL * _T_MAX * (_u[1] - _u[0]), 0.0f, _Q_MAX * (_u[1] - _u[0]));
generate_ts_aerodynamics();
// _Fa_E = -_KDV * _R_N2E * _v_apparent_N; // first order drag to slow down the aircraft
// _Ma_B = -_KDW * _w_B; // first order angular damper
} else if (_vehicle == VehicleType::StandardVTOL) {
_T[0] = _thruster[0].compute_thrust_from_throttle(_u[7], _v_B(0));
_Q[0] = _thruster[0].compute_torque_from_throttle(_u[7], _v_B(0));
_T_B = Vector3f(_T[0], 0.0f, -_T_MAX * (+_u[0] + _u[1] + _u[2] + _u[3]));
_Mt_B = Vector3f(_L_ROLL * _T_MAX * (-_u[0] + _u[1] + _u[2] - _u[3]) + _Q[0],
_T_B = Vector3f(_T_MAX * 2 * _u[7], 0.0f, -_T_MAX * (+_u[0] + _u[1] + _u[2] + _u[3]));
_Mt_B = Vector3f(_L_ROLL * _T_MAX * (-_u[0] + _u[1] + _u[2] - _u[3]),
_L_PITCH * _T_MAX * (+_u[0] - _u[1] + _u[2] - _u[3]),
_Q_MAX * (+_u[0] + _u[1] - _u[2] - _u[3]));
// thrust 0 means no propwash on the tail
// thrust 0 because it is already contained in _T_B. in
// equations_of_motion they are all summed into sum_of_forces_E
generate_fw_aerodynamics(_u[4], _u[5], _u[6], 0);
} else if (_vehicle == VehicleType::RoverAckermann) {
@@ -411,20 +370,21 @@ void Sih::generate_force_and_torques(const float dt)
}
void Sih::generate_fw_aerodynamics(const float roll_cmd, const float pitch_cmd, const float yaw_cmd,
const float thrust_for_prowash)
const float throttle_cmd)
{
const Vector3f v_B = _q.rotateVectorInverse(_v_apparent_N);
const float &alt = _lla.altitude();
_wing_l.update_aero(_v_B, _w_B, alt, roll_cmd * FLAP_MAX);
_wing_r.update_aero(_v_B, _w_B, alt, -roll_cmd * FLAP_MAX);
_wing_l.update_aero(v_B, _w_B, alt, roll_cmd * FLAP_MAX);
_wing_r.update_aero(v_B, _w_B, alt, -roll_cmd * FLAP_MAX);
_tailplane.update_aero(_v_B, _w_B, alt, -pitch_cmd * FLAP_MAX, thrust_for_prowash);
_fin.update_aero(_v_B, _w_B, alt, yaw_cmd * FLAP_MAX, thrust_for_prowash);
_fuselage.update_aero(_v_B, _w_B, alt);
_tailplane.update_aero(v_B, _w_B, alt, -pitch_cmd * FLAP_MAX, _T_MAX * throttle_cmd);
_fin.update_aero(v_B, _w_B, alt, yaw_cmd * FLAP_MAX, _T_MAX * throttle_cmd);
_fuselage.update_aero(v_B, _w_B, alt);
// sum of aerodynamic forces
const Vector3f Fa_B = _wing_l.get_Fa() + _wing_r.get_Fa() + _tailplane.get_Fa() + _fin.get_Fa() + _fuselage.get_Fa() -
_KDV * _v_B;
_KDV * v_B;
_Fa_E = _q_E.rotateVector(Fa_B);
// aerodynamic moments
@@ -433,8 +393,11 @@ void Sih::generate_fw_aerodynamics(const float roll_cmd, const float pitch_cmd,
void Sih::generate_ts_aerodynamics()
{
// velocity in body frame [m/s]
const Vector3f v_B = _q.rotateVectorInverse(_v_apparent_N);
// the aerodynamic is resolved in a frame like a standard aircraft (nose-right-belly)
Vector3f v_ts = _R_S2B.transpose() * _v_B;
Vector3f v_ts = _R_S2B.transpose() * v_B;
Vector3f w_ts = _R_S2B.transpose() * _w_B;
float altitude = _lpos_ref_alt - _lpos(2);
@@ -443,17 +406,17 @@ void Sih::generate_ts_aerodynamics()
for (int i = 0; i < NB_TS_SEG; i++) {
if (i <= NB_TS_SEG / 2) {
_ts[i].update_aero(v_ts, w_ts, altitude, _u[5]*TS_DEF_MAX, _T[1]);
_ts[i].update_aero(v_ts, w_ts, altitude, _u[5]*TS_DEF_MAX, _T_MAX * _u[1]);
} else {
_ts[i].update_aero(v_ts, w_ts, altitude, -_u[4]*TS_DEF_MAX, _T[0]);
_ts[i].update_aero(v_ts, w_ts, altitude, -_u[4]*TS_DEF_MAX, _T_MAX * _u[0]);
}
Fa_ts += _ts[i].get_Fa();
Ma_ts += _ts[i].get_Ma();
}
const Vector3f Fa_B = _R_S2B * Fa_ts - _KDV * _v_B; // sum of aerodynamic forces
const Vector3f Fa_B = _R_S2B * Fa_ts - _KDV * v_B; // sum of aerodynamic forces
_Fa_E = _q_E.rotateVector(Fa_B);
_Ma_B = _R_S2B * Ma_ts - _KDW * _w_B; // aerodynamic moments
}
@@ -879,21 +842,15 @@ int Sih::print_status()
} else if (_vehicle == VehicleType::FixedWing) {
PX4_INFO("Fixed-Wing");
PX4_INFO("propeller model:");
_thruster[0].print_status();
} else if (_vehicle == VehicleType::TailsitterVTOL) {
PX4_INFO("TailSitter");
PX4_INFO("propeller model:");
_thruster[0].print_status();
PX4_INFO("aoa [deg]: %d", (int)(degrees(_ts[4].get_aoa())));
PX4_INFO("v segment (m/s)");
_ts[4].get_vS().print();
} else if (_vehicle == VehicleType::StandardVTOL) {
PX4_INFO("Standard VTOL");
PX4_INFO("pusher propeller model:");
_thruster[0].print_status();
} else if (_vehicle == VehicleType::RoverAckermann) {
PX4_INFO("Rover Ackermann");
@@ -915,8 +872,6 @@ int Sih::print_status()
(_R_N2E.transpose() * _Fa_E).print();
PX4_INFO("Aerodynamic moments body frame (Nm)");
_Ma_B.print();
PX4_INFO("Thruster forces in body frame (N)");
_T_B.print();
PX4_INFO("Thruster moments in body frame (Nm)");
_Mt_B.print();
return 0;
+16 -33
View File
@@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2019-2026 PX4 Development Team. All rights reserved.
* Copyright (c) 2019-2025 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
@@ -40,19 +40,19 @@
* Coriolis g Corporation - January 2019
*/
/** The sensor signals reconstruction and noise levels are from [1]. The aerodynamic model is from [2].
* The quaternion integration are from [3]. The tailsitter model is from [4]. The propeller models are from [5]
* [1] Bulka E, and Nahon M, "Autonomous fixed-wing aerobatics: from theory to flight."
* In 2018 IEEE International Conference on Robotics and Automation (ICRA), pp. 6573-6580. IEEE, 2018.
* [2] Khan W, supervised by Nahon M, "Dynamics modeling of agile fixed-wing unmanned aerial vehicles."
* McGill University (Canada), PhD thesis, 2016.
* [3] Sveier A, Sjøberg AM, Egeland O. "Applied RungeKuttaMunthe-Kaas Integration for the Quaternion Kinematics."
* Journal of Guidance, Control, and Dynamics. 2019 Dec;42(12):2747-54.
* [4] Chiappinelli R, supervised by Nahon M, "Modeling and control of a flying wing tailsitter unmanned aerial vehicle."
* McGill University (Canada), Masters Thesis, 2018.
* [5] J.B. Brandt, R.W. Deters, G.K. Ananda, O.D. Dantsker, and M.S. Selig 2026, UIUC Propeller Database,
* Vols 1-4, University of Illinois at Urbana-Champaign, Department of Aerospace Engineering, retrieved from https://m-selig.ae.illinois.edu/props/propDB.html.
*/
// The sensor signals reconstruction and noise levels are from [1]
// [1] Bulka E, and Nahon M, "Autonomous fixed-wing aerobatics: from theory to flight."
// In 2018 IEEE International Conference on Robotics and Automation (ICRA), pp. 6573-6580. IEEE, 2018.
// The aerodynamic model is from [2]
// [2] Khan W, supervised by Nahon M, "Dynamics modeling of agile fixed-wing unmanned aerial vehicles."
// McGill University (Canada), PhD thesis, 2016.
// The quaternion integration are from [3]
// [3] Sveier A, Sjøberg AM, Egeland O. "Applied RungeKuttaMunthe-Kaas Integration for the Quaternion Kinematics."
// Journal of Guidance, Control, and Dynamics. 2019 Dec;42(12):2747-54.
// The tailsitter model is from [4]
// [4] Chiappinelli R, supervised by Nahon M, "Modeling and control of a flying wing tailsitter unmanned aerial vehicle."
// McGill University (Canada), Masters Thesis, 2018.
#pragma once
#include <px4_platform_common/module.h>
@@ -142,7 +142,6 @@ private:
// hard constants
static constexpr uint16_t NUM_ACTUATORS_MAX = 9;
static constexpr uint16_t NUM_DYN_THRUSTER = 2; // number of dynamic thruster model with advance ratio
// Ranging beacon simulation constants
static constexpr uint8_t NUM_RANGING_BEACONS = 4;
@@ -191,7 +190,7 @@ private:
void send_dist_snsr(const hrt_abstime &time_now_us);
void send_ranging_beacon(const hrt_abstime &time_now_us);
void publish_ground_truth(const hrt_abstime &time_now_us);
void generate_fw_aerodynamics(const float roll_cmd, const float pitch_cmd, const float yaw_cmd, const float thrust_for_prowash);
void generate_fw_aerodynamics(const float roll_cmd, const float pitch_cmd, const float yaw_cmd, const float thrust);
void generate_ts_aerodynamics();
void generate_rover_ackermann_dynamics(const float throttle_cmd, const float steering_cmd, const float dt);
void sensor_step();
@@ -235,7 +234,6 @@ private:
matrix::Vector3f _Mt_B{}; // thruster moments [Nm]
matrix::Vector3f _Ma_B{}; // aerodynamic moments [Nm]
matrix::Vector3f _w_B{}; // body rates in body frame [rad/s]
matrix::Vector3f _v_B{}; // body frame velocity [m/s]
// Quantities in local navigation frame (NED, body-fixed)
matrix::Vector3f _v_N{}; // velocity [m/s]
@@ -259,9 +257,6 @@ private:
matrix::Vector3f _lpos{}; // position in a local tangent-plane frame [m]
float _u[NUM_ACTUATORS_MAX] {}; // thruster signals
float _T[NUM_DYN_THRUSTER] {}; // thruster forces (N)
float _Q[NUM_DYN_THRUSTER] {}; // thruster torque (Nm)
Thruster _thruster[NUM_DYN_THRUSTER] {}; // thruster objects
enum class VehicleType {Quadcopter, FixedWing, TailsitterVTOL, StandardVTOL, Hexacopter, RoverAckermann, First = Quadcopter, Last = RoverAckermann}; // numbering dependent on parameter SIH_VEHICLE_TYPE
VehicleType _vehicle = VehicleType::Quadcopter;
@@ -301,7 +296,7 @@ private:
// parameters
MapProjection _lpos_ref{};
float _lpos_ref_alt;
float _MASS, _T_MAX, _Q_MAX, _L_ROLL, _L_PITCH, _KDV, _KDW, _T_TAU, _F_T_MAX, _F_Q_MAX;
float _MASS, _T_MAX, _Q_MAX, _L_ROLL, _L_PITCH, _KDV, _KDW, _T_TAU;
matrix::Matrix3f _I; // vehicle inertia matrix
matrix::Matrix3f _Im1; // inverse of the inertia matrix
@@ -331,18 +326,6 @@ private:
(ParamFloat<px4::params::SIH_DISTSNSR_MAX>) _sih_distance_snsr_max,
(ParamFloat<px4::params::SIH_DISTSNSR_OVR>) _sih_distance_snsr_override,
(ParamFloat<px4::params::SIH_T_TAU>) _sih_thrust_tau,
// forward propeller
(ParamFloat<px4::params::SIH_F_T_MAX>) _sih_f_thrust_max,
(ParamFloat<px4::params::SIH_F_Q_MAX>) _sih_f_torque_max,
(ParamFloat<px4::params::SIH_F_CT0>) _sih_f_ct0,
(ParamFloat<px4::params::SIH_F_CT1>) _sih_f_ct1,
(ParamFloat<px4::params::SIH_F_CT2>) _sih_f_ct2,
(ParamFloat<px4::params::SIH_F_CP0>) _sih_f_cp0,
(ParamFloat<px4::params::SIH_F_CP1>) _sih_f_cp1,
(ParamFloat<px4::params::SIH_F_CP2>) _sih_f_cp2,
(ParamFloat<px4::params::SIH_F_DIA_INCH>) _sih_forward_diameter_inch,
(ParamFloat<px4::params::SIH_F_RPM_MAX>) _sih_forward_rpm_max,
(ParamInt<px4::params::BAT1_SOURCE>) _bat1_source,
(ParamInt<px4::params::SIH_VEHICLE_TYPE>) _sih_vtype,
(ParamFloat<px4::params::SIH_WIND_N>) _sih_wind_n,
(ParamFloat<px4::params::SIH_WIND_E>) _sih_wind_e,
@@ -83,14 +83,12 @@ parameters:
increment: 0.005
SIH_T_MAX:
description:
short: Max multicopter propeller thrust force
short: Max propeller thrust force
long: |-
This is the maximum force delivered by one propeller
when the motor is running at full speed.
This value is usually about 5 times the mass of the quadrotor.
Refer to SIH_F_T_MAX for the thrust for FW, Tailsitter, and VTOL pusher.
type: float
default: 5.0
unit: N
@@ -99,14 +97,12 @@ parameters:
increment: 0.5
SIH_Q_MAX:
description:
short: Max multicopter propeller torque
short: Max propeller torque
long: |-
This is the maximum torque delivered by one propeller
when the motor is running at full speed.
This value is usually about few percent of the maximum thrust force.
Refer to SIH_F_Q_MAX for the propeller torque for FW, Tailsitter, and VTOL pusher.
type: float
default: 0.1
unit: Nm
@@ -285,87 +281,3 @@ parameters:
min: 0.0
max: 100.0
decimal: 1
SIH_F_T_MAX:
description:
short: Forward thruster max thrust (N)
long: |-
This is used for the Fixed-Wing, Tailsitter, or pusher of the Standard VTOL
if SIH_F_CT0 <= 0.
If SIH_F_CT0 > 0, propeller model with advance ratio J is used
and this parameter value is overridden at simulation startup.
type: float
default: 2.0
unit: N
min: 0.0
decimal: 3
SIH_F_Q_MAX:
description:
short: Forward thruster max torque (Nm)
long: |-
This is used for the Fixed-Wing, Tailsitter, or pusher of the Standard VTOL
if SIH_F_CP0 <= 0.
If SIH_F_CP0 > 0, propeller model with advance ratio J is used
and this parameter value is overridden at simulation startup.
type: float
default: 0.0165
unit: Nm
min: 0.0
decimal: 3
SIH_F_CT0:
description:
short: Forward thruster static thrust coefficient
type: float
default: 0.0
min: 0.0
decimal: 3
SIH_F_CT1:
description:
short: Forward thruster thrust coefficient 1
long: CT(J) = CT0 + CT1*J + CT2*J^2
type: float
default: 0.0
decimal: 3
SIH_F_CT2:
description:
short: Forward thruster thrust coefficient 2
long: CT(J) = CT0 + CT1*J + CT2*J^2
type: float
default: 0.0
max: 0.0
decimal: 3
SIH_F_CP0:
description:
short: Forward thruster static power coefficient
type: float
default: 0.0
min: 0.0
decimal: 3
SIH_F_CP1:
description:
short: Forward thruster power coefficient 1
long: CP(J) = CP0 + CP1*J + CP2*J^2
type: float
default: 0.0
decimal: 3
SIH_F_CP2:
description:
short: Forward thruster power coefficient 2
long: CP(J) = CP0 + CP1*J + CP2*J^2
type: float
default: 0.0
max: 0.0
decimal: 3
SIH_F_DIA_INCH:
description:
short: Forward thruster propeller diameter in inches
type: float
default: 0.1
min: 0.1
decimal: 1
SIH_F_RPM_MAX:
description:
short: Forward thruster max RPM
type: float
default: 6000.0
min: 0.1
decimal: 1
+8 -10
View File
@@ -50,7 +50,7 @@ namespace i2cdetect
int detect(int bus)
{
PX4_INFO("Scanning I2C bus: %d", bus);
printf("Scanning I2C bus: %d\n", bus);
int ret = PX4_ERROR;
@@ -62,17 +62,15 @@ int detect(int bus)
return PX4_ERROR;
}
// Line buffer for building up output
char line[80];
int pos = 0;
PX4_INFO(" 0 1 2 3 4 5 6 7 8 9 a b c d e f");
printf(" 0 1 2 3 4 5 6 7 8 9 a b c d e f\n");
for (int i = 0; i < 128; i += 16) {
pos = snprintf(line, sizeof(line), "%02x: ", i);
printf("%02x: ", i);
for (int j = 0; j < 16; j++) {
fflush(stdout);
uint8_t addr = i + j;
unsigned retry_count = 0;
@@ -117,14 +115,14 @@ int detect(int bus)
} while (retry_count++ < retries);
if (found) {
pos += snprintf(line + pos, sizeof(line) - pos, "%02x ", addr);
printf("%02x ", addr);
} else {
pos += snprintf(line + pos, sizeof(line) - pos, "-- ");
printf("-- ");
}
}
PX4_INFO("%s", line);
printf("\n");
}
px4_i2cbus_uninitialize(i2c_dev);
+3 -3
View File
@@ -158,7 +158,7 @@ static void print_usage()
int mtd_erase(mtd_instance_s &instance)
{
uint8_t v[32];
uint8_t v[64];
memset(v, 0xFF, sizeof(v));
for (uint8_t i = 0; i < instance.n_partitions_current; i++) {
@@ -192,7 +192,7 @@ int mtd_erase(mtd_instance_s &instance)
*/
int mtd_readtest(const mtd_instance_s &instance)
{
uint8_t v[32];
uint8_t v[128];
for (uint8_t i = 0; i < instance.n_partitions_current; i++) {
ssize_t count = 0;
@@ -236,7 +236,7 @@ int mtd_readtest(const mtd_instance_s &instance)
*/
int mtd_rwtest(const mtd_instance_s &instance)
{
uint8_t v[32], v2[32];
uint8_t v[128], v2[128];
for (uint8_t i = 0; i < instance.n_partitions_current; i++) {
ssize_t count = 0;
+2 -1
View File
@@ -725,7 +725,8 @@ do_show_print_for_airframe(void *arg, param_t param)
}
if (!strncmp(p_name, "RC", 2) || !strncmp(p_name, "TC_", 3) || !strncmp(p_name, "CAL_", 4) ||
!strcmp(p_name, "SENS_DPRES_OFF") || !strcmp(p_name, "MAV_TYPE")) {
!strncmp(p_name, "SENS_BOARD_", 11) || !strcmp(p_name, "SENS_DPRES_OFF") ||
!strcmp(p_name, "MAV_TYPE")) {
return;
}