mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-05-24 09:57:35 +08:00
Compare commits
12 Commits
| Author | SHA1 | Date | |
|---|---|---|---|
| ba860bd52a | |||
| 6badbdd113 | |||
| 6f6d8c5860 | |||
| 35391ed8d0 | |||
| 48b04b1c81 | |||
| 3ab7895af7 | |||
| 3c5574c051 | |||
| eb9a76cfaf | |||
| f545f2227d | |||
| 4e5c0fac7a | |||
| fa0618463d | |||
| f025bb42eb |
@@ -0,0 +1,21 @@
|
||||
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
|
||||
@@ -0,0 +1,22 @@
|
||||
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 }}
|
||||
@@ -0,0 +1,56 @@
|
||||
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
|
||||
@@ -21,7 +21,7 @@ jobs:
|
||||
runs-on: ubuntu-latest
|
||||
|
||||
container:
|
||||
image: px4io/px4-dev:v1.16.0-rc1-258-g0369abd556
|
||||
image: ghcr.io/px4/px4-dev:v1.17.0-rc2
|
||||
|
||||
strategy:
|
||||
fail-fast: false
|
||||
@@ -50,7 +50,7 @@ jobs:
|
||||
PX4_SBOM_DISABLE: 1
|
||||
run: |
|
||||
cd "$GITHUB_WORKSPACE"
|
||||
git config --global --add safe.directory "$GITHUB_WORKSPACE"
|
||||
git config --system --add safe.directory '*'
|
||||
make ${{ matrix.check }}
|
||||
|
||||
- name: Uploading Coverage to Codecov.io
|
||||
|
||||
@@ -20,7 +20,7 @@ jobs:
|
||||
name: Clang-Tidy
|
||||
runs-on: [runs-on, runner=16cpu-linux-x64, "run-id=${{ github.run_id }}", "extras=s3-cache"]
|
||||
container:
|
||||
image: px4io/px4-dev:v1.17.0-beta1
|
||||
image: ghcr.io/px4/px4-dev:v1.17.0-rc2
|
||||
steps:
|
||||
- uses: runs-on/action@v2
|
||||
- uses: actions/checkout@v4
|
||||
|
||||
@@ -70,7 +70,7 @@ jobs:
|
||||
contents: read
|
||||
runs-on: [runs-on,runner=4cpu-linux-x64,image=ubuntu24-full-x64,"run-id=${{ github.run_id }}",spot=false,extras=s3-cache]
|
||||
container:
|
||||
image: px4io/px4-dev:v1.17.0-beta1
|
||||
image: ghcr.io/px4/px4-dev:v1.17.0-rc2
|
||||
steps:
|
||||
- uses: runs-on/action@v1
|
||||
|
||||
@@ -132,7 +132,7 @@ jobs:
|
||||
contents: write
|
||||
runs-on: [runs-on,runner=4cpu-linux-x64,image=ubuntu24-full-x64,"run-id=${{ github.run_id }}",spot=false,extras=s3-cache]
|
||||
container:
|
||||
image: px4io/px4-dev:v1.17.0-beta1
|
||||
image: ghcr.io/px4/px4-dev:v1.17.0-rc2
|
||||
steps:
|
||||
- uses: runs-on/action@v1
|
||||
|
||||
|
||||
@@ -17,7 +17,7 @@ jobs:
|
||||
runs-on: ubuntu-latest
|
||||
|
||||
container:
|
||||
image: px4io/px4-dev:v1.16.0-rc1-258-g0369abd556
|
||||
image: ghcr.io/px4/px4-dev:v1.17.0-rc2
|
||||
|
||||
steps:
|
||||
- uses: actions/checkout@v4
|
||||
@@ -27,7 +27,7 @@ jobs:
|
||||
- name: main test
|
||||
run: |
|
||||
cd "$GITHUB_WORKSPACE"
|
||||
git config --global --add safe.directory "$GITHUB_WORKSPACE"
|
||||
git config --system --add safe.directory '*'
|
||||
make tests TESTFILTER=EKF
|
||||
|
||||
- name: Check if there is a functional change
|
||||
|
||||
@@ -10,7 +10,7 @@ jobs:
|
||||
runs-on: ubuntu-latest
|
||||
|
||||
container:
|
||||
image: px4io/px4-dev:v1.16.0-rc1-258-g0369abd556
|
||||
image: ghcr.io/px4/px4-dev:v1.17.0-rc2
|
||||
|
||||
env:
|
||||
GIT_COMMITTER_EMAIL: bot@px4.io
|
||||
@@ -24,7 +24,7 @@ jobs:
|
||||
- name: main test
|
||||
run: |
|
||||
cd "$GITHUB_WORKSPACE"
|
||||
git config --global --add safe.directory "$GITHUB_WORKSPACE"
|
||||
git config --system --add safe.directory '*'
|
||||
make tests TESTFILTER=EKF
|
||||
|
||||
- name: Check if there exists diff and save result in variable
|
||||
|
||||
@@ -29,7 +29,7 @@ jobs:
|
||||
"failsafe_web",
|
||||
]
|
||||
container:
|
||||
image: px4io/px4-dev:v1.16.0-rc1-258-g0369abd556
|
||||
image: ghcr.io/px4/px4-dev:v1.17.0-rc2
|
||||
options: --privileged --ulimit core=-1 --security-opt seccomp=unconfined
|
||||
steps:
|
||||
- name: Install Node v20.18.0
|
||||
|
||||
@@ -26,7 +26,7 @@ jobs:
|
||||
name: Analyzing ${{ matrix.target }}
|
||||
runs-on: [runs-on,runner=4cpu-linux-x64,image=ubuntu24-full-x64,"run-id=${{ github.run_id }}",spot=false]
|
||||
container:
|
||||
image: px4io/px4-dev:v1.16.0-rc1-258-g0369abd556
|
||||
image: ghcr.io/px4/px4-dev:v1.17.0-rc2
|
||||
strategy:
|
||||
matrix:
|
||||
target: [px4_fmu-v5x, px4_fmu-v6x]
|
||||
|
||||
@@ -24,7 +24,7 @@ jobs:
|
||||
name: Checking ${{ matrix.target }}
|
||||
runs-on: [runs-on,runner=4cpu-linux-x64,image=ubuntu24-full-x64,"run-id=${{ github.run_id }}",spot=false]
|
||||
container:
|
||||
image: px4io/px4-dev:v1.16.0-rc1-258-g0369abd556
|
||||
image: ghcr.io/px4/px4-dev:v1.17.0-rc2
|
||||
strategy:
|
||||
fail-fast: false
|
||||
matrix:
|
||||
|
||||
@@ -21,7 +21,7 @@ jobs:
|
||||
runs-on: ubuntu-latest
|
||||
|
||||
container:
|
||||
image: px4io/px4-dev:v1.16.0-rc1-258-g0369abd556
|
||||
image: ghcr.io/px4/px4-dev:v1.17.0-rc2
|
||||
|
||||
strategy:
|
||||
matrix:
|
||||
@@ -36,7 +36,7 @@ jobs:
|
||||
- name: Build PX4 and Run Test [${{ matrix.config }}]
|
||||
run: |
|
||||
cd "$GITHUB_WORKSPACE"
|
||||
git config --global --add safe.directory "$GITHUB_WORKSPACE"
|
||||
git config --system --add safe.directory '*'
|
||||
export PX4_EXTRA_NUTTX_CONFIG='CONFIG_NSH_LOGIN_PASSWORD="test";CONFIG_NSH_CONSOLE_LOGIN=y'
|
||||
echo "PX4_EXTRA_NUTTX_CONFIG: $PX4_EXTRA_NUTTX_CONFIG"
|
||||
|
||||
|
||||
+13
-2
@@ -1,9 +1,11 @@
|
||||
Maintainers
|
||||
===========
|
||||
|
||||
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.
|
||||
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.
|
||||
|
||||
**Active Maintainers**
|
||||
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**
|
||||
|
||||
| Name | Sector | GitHub | Chat | email
|
||||
|-------------------------|--------|--------|------|----------------
|
||||
@@ -23,6 +25,15 @@ 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
|
||||
|
||||
@@ -14,6 +14,7 @@
|
||||
|
||||
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
|
||||
|
||||
@@ -38,7 +39,6 @@ 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,3 +48,21 @@ 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,6 +28,7 @@ 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
|
||||
@@ -56,7 +57,6 @@ 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,8 +66,9 @@ param set-default CBRK_SUPPLY_CHK 894281
|
||||
|
||||
param set-default SENS_DPRES_OFF 0.001
|
||||
|
||||
param set SIH_T_MAX 2.0
|
||||
param set SIH_Q_MAX 0.0165
|
||||
# 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_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
|
||||
@@ -77,6 +78,19 @@ 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,6 +56,7 @@ 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
|
||||
@@ -77,6 +78,7 @@ 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
|
||||
@@ -88,5 +90,18 @@ 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
|
||||
|
||||
@@ -0,0 +1,49 @@
|
||||
#!/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,6 +49,7 @@ 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(
|
||||
|
||||
@@ -651,10 +651,6 @@ else
|
||||
. ${R}etc/init.d/rc.autostart.post
|
||||
fi
|
||||
|
||||
#
|
||||
# Lock read-only parameters (if configured for this board).
|
||||
#
|
||||
param lock
|
||||
|
||||
set BOARD_BOOTLOADER_UPGRADE ${R}etc/init.d/rc.board_bootloader_upgrade
|
||||
if [ -f $BOARD_BOOTLOADER_UPGRADE ]
|
||||
|
||||
Executable
+147
@@ -0,0 +1,147 @@
|
||||
#!/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()
|
||||
@@ -287,8 +287,8 @@
|
||||
|
||||
/* AUX */
|
||||
|
||||
#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 */
|
||||
#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 */
|
||||
|
||||
/* GPS 1 */
|
||||
|
||||
|
||||
@@ -358,62 +358,6 @@ This ensures that metadata is always up-to-date with the code running on the veh
|
||||
This process is the same as for [events metadata](../concept/events_interface.md#publishing-event-metadata-to-a-gcs).
|
||||
For more information see [PX4 Metadata (Translation & Publication)](../advanced/px4_metadata.md)
|
||||
|
||||
## Read-Only Parameters
|
||||
|
||||
Integrators who productize PX4 can lock down parameters so that end users cannot change safety-critical or product-defining settings.
|
||||
This works in two phases:
|
||||
|
||||
1. **Build time** — a YAML file in the board directory declares _which_ parameters are read-only.
|
||||
2. **Run time** — `param lock` in the startup script activates enforcement.
|
||||
|
||||
Before the lock, all parameters (including those on the read-only list) can be freely set by startup scripts (`rc.board_defaults`, airframe scripts, `config.txt`, etc.).
|
||||
After the lock, any attempt to modify a read-only parameter is rejected.
|
||||
|
||||
### Configuration
|
||||
|
||||
Create `boards/<vendor>/<board>/readonly_params.yaml` with the following format:
|
||||
|
||||
```yaml
|
||||
# mode: 'block' = listed params are read-only (all others writable)
|
||||
# mode: 'allow' = only listed params are writable (all others read-only)
|
||||
mode: block
|
||||
parameters:
|
||||
- SYS_AUTOSTART
|
||||
- SYS_AUTOCONFIG
|
||||
- BAT1_N_CELLS
|
||||
```
|
||||
|
||||
The two modes are:
|
||||
|
||||
- **`block`**: The listed parameters are read-only; all other parameters remain writable.
|
||||
- **`allow`**: Only the listed parameters are writable; all others become read-only.
|
||||
|
||||
All parameter names in the list are validated at build time — the build will fail if any listed parameter does not exist in the firmware.
|
||||
Boards without this file have no read-only enforcement (fully backward compatible).
|
||||
|
||||
### Locking
|
||||
|
||||
The `param lock` command is called in `rcS` after all startup scripts have finished setting parameters.
|
||||
Before this call, startup scripts can freely use `param set-default` and `param set` on any parameter, including those on the read-only list.
|
||||
After `param lock`, the read-only list is enforced.
|
||||
|
||||
To set a specific locked value, use `param set-default` in a board startup script (e.g. `rc.board_defaults`) to set the desired default _before_ the lock activates.
|
||||
|
||||
### Enforcement (after lock)
|
||||
|
||||
Read-only parameters are enforced at all entry points:
|
||||
|
||||
- **`param set`** and **`param set-default`** shell commands return an error.
|
||||
- **MAVLink PARAM_SET** returns a `MAV_PARAM_ERROR_READ_ONLY` error to the GCS.
|
||||
- **`param_set()`**, **`param_set_default_value()`** C API calls return `PX4_ERROR`.
|
||||
- **`param reset`** silently skips read-only parameters (since `param_reset_all` loops over all params).
|
||||
- **`param import`** / **`param load`** from file silently skips read-only parameters.
|
||||
|
||||
### Notes
|
||||
|
||||
- The read-only list is compiled into firmware as a `constexpr` array, so there is zero runtime overhead when the list is empty.
|
||||
- If no `readonly_params.yaml` file exists for a board, `param lock` is a no-op.
|
||||
|
||||
## Further Information
|
||||
|
||||
- [Finding/Updating Parameters](../advanced_config/parameters.md)
|
||||
|
||||
@@ -40004,6 +40004,104 @@ Absolute value superior to 10000 will disable distance sensor
|
||||
| ------ | -------- | -------- | --------- | ------- | ---- |
|
||||
| | | | | -1.0 | m |
|
||||
|
||||
### SIH_F_CP0 (`FLOAT`) {#SIH_F_CP0}
|
||||
|
||||
Forward thruster static power coefficient.
|
||||
|
||||
| Reboot | minValue | maxValue | increment | default | unit |
|
||||
| ------ | -------- | -------- | --------- | ------- | ---- |
|
||||
| | 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 |
|
||||
| ------ | -------- | -------- | --------- | ------- | ---- |
|
||||
| | | | | 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 |
|
||||
| ------ | -------- | -------- | --------- | ------- | ---- |
|
||||
| | | 0.0 | | 0.0 | |
|
||||
|
||||
### SIH_F_CT0 (`FLOAT`) {#SIH_F_CT0}
|
||||
|
||||
Forward thruster static thrust coefficient.
|
||||
|
||||
| Reboot | minValue | maxValue | increment | default | unit |
|
||||
| ------ | -------- | -------- | --------- | ------- | ---- |
|
||||
| | 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 |
|
||||
| ------ | -------- | -------- | --------- | ------- | ---- |
|
||||
| | | | | 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 |
|
||||
| ------ | -------- | -------- | --------- | ------- | ---- |
|
||||
| | | 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 |
|
||||
| ------ | -------- | -------- | --------- | ------- | ---- |
|
||||
| | 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 |
|
||||
| ------ | -------- | -------- | --------- | ------- | ---- |
|
||||
| | 0.0 | | | 0.0165 | Nm |
|
||||
|
||||
### SIH_F_RPM_MAX (`FLOAT`) {#SIH_F_RPM_MAX}
|
||||
|
||||
Forward thruster max RPM.
|
||||
|
||||
| Reboot | minValue | maxValue | increment | default | unit |
|
||||
| ------ | -------- | -------- | --------- | ------- | ---- |
|
||||
| | 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 |
|
||||
| ------ | -------- | -------- | --------- | ------- | ---- |
|
||||
| | 0.0 | | | 2.0 | N |
|
||||
|
||||
### SIH_IXX (`FLOAT`) {#SIH_IXX}
|
||||
|
||||
Vehicle inertia about X axis.
|
||||
@@ -40178,13 +40276,15 @@ This value can be measured by weighting the quad on a scale.
|
||||
|
||||
### SIH_Q_MAX (`FLOAT`) {#SIH_Q_MAX}
|
||||
|
||||
Max propeller torque.
|
||||
Max multicopter 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 |
|
||||
| ------ | -------- | -------- | --------- | ------- | ---- |
|
||||
| | 0.0 | | 0.05 | 0.1 | Nm |
|
||||
@@ -40201,13 +40301,15 @@ Gaussian noise added to simulated ranging beacon measurements. Set to 0 to disab
|
||||
|
||||
### SIH_T_MAX (`FLOAT`) {#SIH_T_MAX}
|
||||
|
||||
Max propeller thrust force.
|
||||
Max multicopter 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 |
|
||||
| ------ | -------- | -------- | --------- | ------- | ---- |
|
||||
| | 0.0 | | 0.5 | 5.0 | N |
|
||||
|
||||
@@ -457,6 +457,10 @@ div.frame_variant td, div.frame_variant th {
|
||||
<td>SIH Quadcopter X</td>
|
||||
<td>Maintainer: Romain Chiappinelli <romain.chiap@gmail.com><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 <romain.chiap@gmail.com><p><code>SYS_AUTOSTART</code> = 1105</p></td>
|
||||
</tr>
|
||||
</tbody>
|
||||
</table>
|
||||
</div>
|
||||
|
||||
@@ -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="https://docs.px4.io/main/en/contribute/dev_call">See the latest version</a>.</p>
|
||||
<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>
|
||||
</div>
|
||||
</div>
|
||||
|
||||
@@ -15,8 +15,8 @@ The PX4 dev team and community come together to discuss any topic of interest to
|
||||
|
||||
## Who should attend?
|
||||
|
||||
- Core project maintainers
|
||||
- Component maintainers
|
||||
- Code Owners
|
||||
- Reviewers
|
||||
- Test team lead
|
||||
- Dronecode members
|
||||
- Community members (you!)
|
||||
|
||||
@@ -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) - Maintainers of PX4 Subsystems and Ecosystem
|
||||
- [Maintainers](./maintainers.md) - Maintainer roles, types, and how to become one
|
||||
- [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
|
||||
|
||||
@@ -1,57 +1,86 @@
|
||||
# Maintainer Role
|
||||
|
||||
Dronecode maintainers have technical leadership and responsibility for specific areas of PX4, and for other ecosystem components such as MAVLink, MAVSDK, QGroundControl, and others.
|
||||
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.
|
||||
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, visit [PX4-Autopilot README](https://github.com/PX4/PX4-Autopilot#maintenance-team).
|
||||
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.
|
||||
|
||||
## 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 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.
|
||||
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).
|
||||
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 `#maintainers` channel.
|
||||
2. Access to the private `#maintainers` channel for internal maintainer discussion.
|
||||
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. 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
|
||||
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
|
||||
|
||||
## 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
|
||||
### Responsibilities (Code Owner)
|
||||
|
||||
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.
|
||||
2. Domain expertise in the category field (for Code Owners) or broad working knowledge of the project (for Reviewers).
|
||||
3. Good overview of the project you are applying to.
|
||||
4. You need to manage approval from your employer when relevant.
|
||||
|
||||
|
||||
+195
-195
@@ -95,207 +95,207 @@ They are not build into the module, and hence are neither published or subscribe
|
||||
|
||||
::: details See messages
|
||||
|
||||
- [PowerButtonState](../msg_docs/PowerButtonState.md)
|
||||
- [Gripper](../msg_docs/Gripper.md)
|
||||
- [EstimatorAidSource1d](../msg_docs/EstimatorAidSource1d.md)
|
||||
- [RoverSpeedStatus](../msg_docs/RoverSpeedStatus.md)
|
||||
- [SensorGnssStatus](../msg_docs/SensorGnssStatus.md)
|
||||
- [UavcanParameterRequest](../msg_docs/UavcanParameterRequest.md)
|
||||
- [GpsInjectData](../msg_docs/GpsInjectData.md)
|
||||
- [SensorSelection](../msg_docs/SensorSelection.md)
|
||||
- [DatamanResponse](../msg_docs/DatamanResponse.md)
|
||||
- [GpioRequest](../msg_docs/GpioRequest.md)
|
||||
- [LandingTargetPose](../msg_docs/LandingTargetPose.md)
|
||||
- [RegisterExtComponentRequestV0](../msg_docs/RegisterExtComponentRequestV0.md)
|
||||
- [CameraStatus](../msg_docs/CameraStatus.md)
|
||||
- [RaptorInput](../msg_docs/RaptorInput.md)
|
||||
- [GimbalControls](../msg_docs/GimbalControls.md)
|
||||
- [MavlinkLog](../msg_docs/MavlinkLog.md)
|
||||
- [MountOrientation](../msg_docs/MountOrientation.md)
|
||||
- [VehicleAngularAccelerationSetpoint](../msg_docs/VehicleAngularAccelerationSetpoint.md)
|
||||
- [RtlStatus](../msg_docs/RtlStatus.md)
|
||||
- [RtlTimeEstimate](../msg_docs/RtlTimeEstimate.md)
|
||||
- [RaptorStatus](../msg_docs/RaptorStatus.md)
|
||||
- [NavigatorStatus](../msg_docs/NavigatorStatus.md)
|
||||
- [FollowTarget](../msg_docs/FollowTarget.md)
|
||||
- [SensorTemp](../msg_docs/SensorTemp.md)
|
||||
- [EscEepromRead](../msg_docs/EscEepromRead.md)
|
||||
- [EstimatorFusionControl](../msg_docs/EstimatorFusionControl.md)
|
||||
- [SensorsStatus](../msg_docs/SensorsStatus.md)
|
||||
- [FixedWingLateralStatus](../msg_docs/FixedWingLateralStatus.md)
|
||||
- [MavlinkTunnel](../msg_docs/MavlinkTunnel.md)
|
||||
- [PowerMonitor](../msg_docs/PowerMonitor.md)
|
||||
- [UlogStreamAck](../msg_docs/UlogStreamAck.md)
|
||||
- [SensorUwb](../msg_docs/SensorUwb.md)
|
||||
- [VehicleOpticalFlowVel](../msg_docs/VehicleOpticalFlowVel.md)
|
||||
- [IridiumsbdStatus](../msg_docs/IridiumsbdStatus.md)
|
||||
- [DatamanRequest](../msg_docs/DatamanRequest.md)
|
||||
- [AutotuneAttitudeControlStatus](../msg_docs/AutotuneAttitudeControlStatus.md)
|
||||
- [ActuatorArmed](../msg_docs/ActuatorArmed.md)
|
||||
- [DifferentialPressure](../msg_docs/DifferentialPressure.md)
|
||||
- [EstimatorAidSource3d](../msg_docs/EstimatorAidSource3d.md)
|
||||
- [NavigatorMissionItem](../msg_docs/NavigatorMissionItem.md)
|
||||
- [LaunchDetectionStatus](../msg_docs/LaunchDetectionStatus.md)
|
||||
- [MagnetometerBiasEstimate](../msg_docs/MagnetometerBiasEstimate.md)
|
||||
- [CanInterfaceStatus](../msg_docs/CanInterfaceStatus.md)
|
||||
- [AirspeedValidatedV0](../msg_docs/AirspeedValidatedV0.md)
|
||||
- [OrbTestMedium](../msg_docs/OrbTestMedium.md)
|
||||
- [FuelTankStatus](../msg_docs/FuelTankStatus.md)
|
||||
- [DebugKeyValue](../msg_docs/DebugKeyValue.md)
|
||||
- [UlogStream](../msg_docs/UlogStream.md)
|
||||
- [VehicleRoi](../msg_docs/VehicleRoi.md)
|
||||
- [EscStatus](../msg_docs/EscStatus.md)
|
||||
- [QshellReq](../msg_docs/QshellReq.md)
|
||||
- [ArmingCheckRequestV0](../msg_docs/ArmingCheckRequestV0.md)
|
||||
- [ActionRequest](../msg_docs/ActionRequest.md)
|
||||
- [ParameterSetUsedRequest](../msg_docs/ParameterSetUsedRequest.md)
|
||||
- [VehicleStatusV1](../msg_docs/VehicleStatusV1.md)
|
||||
- [HoverThrustEstimate](../msg_docs/HoverThrustEstimate.md)
|
||||
- [FigureEightStatus](../msg_docs/FigureEightStatus.md)
|
||||
- [IrlockReport](../msg_docs/IrlockReport.md)
|
||||
- [OpenDroneIdSystem](../msg_docs/OpenDroneIdSystem.md)
|
||||
- [ParameterUpdate](../msg_docs/ParameterUpdate.md)
|
||||
- [SensorCorrection](../msg_docs/SensorCorrection.md)
|
||||
- [DebugValue](../msg_docs/DebugValue.md)
|
||||
- [EstimatorEventFlags](../msg_docs/EstimatorEventFlags.md)
|
||||
- [SensorBaro](../msg_docs/SensorBaro.md)
|
||||
- [WheelEncoders](../msg_docs/WheelEncoders.md)
|
||||
- [VehicleMagnetometer](../msg_docs/VehicleMagnetometer.md)
|
||||
- [OpenDroneIdSelfId](../msg_docs/OpenDroneIdSelfId.md)
|
||||
- [PpsCapture](../msg_docs/PpsCapture.md)
|
||||
- [ManualControlSwitches](../msg_docs/ManualControlSwitches.md)
|
||||
- [EstimatorGpsStatus](../msg_docs/EstimatorGpsStatus.md)
|
||||
- [SensorsStatusImu](../msg_docs/SensorsStatusImu.md)
|
||||
- [EstimatorStates](../msg_docs/EstimatorStates.md)
|
||||
- [LandingTargetInnovations](../msg_docs/LandingTargetInnovations.md)
|
||||
- [RadioStatus](../msg_docs/RadioStatus.md)
|
||||
- [GimbalManagerStatus](../msg_docs/GimbalManagerStatus.md)
|
||||
- [ActuatorOutputs](../msg_docs/ActuatorOutputs.md)
|
||||
- [PwmInput](../msg_docs/PwmInput.md)
|
||||
- [EstimatorInnovations](../msg_docs/EstimatorInnovations.md)
|
||||
- [BatteryInfo](../msg_docs/BatteryInfo.md)
|
||||
- [ButtonEvent](../msg_docs/ButtonEvent.md)
|
||||
- [GimbalDeviceSetAttitude](../msg_docs/GimbalDeviceSetAttitude.md)
|
||||
- [VelocityLimits](../msg_docs/VelocityLimits.md)
|
||||
- [AirspeedWind](../msg_docs/AirspeedWind.md)
|
||||
- [GpioOut](../msg_docs/GpioOut.md)
|
||||
- [SensorAccel](../msg_docs/SensorAccel.md)
|
||||
- [SensorAirflow](../msg_docs/SensorAirflow.md)
|
||||
- [Vtx](../msg_docs/Vtx.md)
|
||||
- [GeofenceStatus](../msg_docs/GeofenceStatus.md)
|
||||
- [DebugArray](../msg_docs/DebugArray.md)
|
||||
- [VehicleCommandAckV0](../msg_docs/VehicleCommandAckV0.md)
|
||||
- [BatteryStatusV0](../msg_docs/BatteryStatusV0.md)
|
||||
- [EventV0](../msg_docs/EventV0.md)
|
||||
- [HealthReport](../msg_docs/HealthReport.md)
|
||||
- [VehicleStatusV0](../msg_docs/VehicleStatusV0.md)
|
||||
- [AdcReport](../msg_docs/AdcReport.md)
|
||||
- [ActuatorControlsStatus](../msg_docs/ActuatorControlsStatus.md)
|
||||
- [OrbTestLarge](../msg_docs/OrbTestLarge.md)
|
||||
- [SensorPreflightMag](../msg_docs/SensorPreflightMag.md)
|
||||
- [OrbTest](../msg_docs/OrbTest.md)
|
||||
- [YawEstimatorStatus](../msg_docs/YawEstimatorStatus.md)
|
||||
- [RangingBeacon](../msg_docs/RangingBeacon.md)
|
||||
- [MissionResult](../msg_docs/MissionResult.md)
|
||||
- [EstimatorBias](../msg_docs/EstimatorBias.md)
|
||||
- [LedControl](../msg_docs/LedControl.md)
|
||||
- [MagWorkerData](../msg_docs/MagWorkerData.md)
|
||||
- [EscReport](../msg_docs/EscReport.md)
|
||||
- [Rpm](../msg_docs/Rpm.md)
|
||||
- [CameraCapture](../msg_docs/CameraCapture.md)
|
||||
- [DebugVect](../msg_docs/DebugVect.md)
|
||||
- [TuneControl](../msg_docs/TuneControl.md)
|
||||
- [GimbalManagerInformation](../msg_docs/GimbalManagerInformation.md)
|
||||
- [GimbalDeviceInformation](../msg_docs/GimbalDeviceInformation.md)
|
||||
- [Ping](../msg_docs/Ping.md)
|
||||
- [SensorPreflightMag](../msg_docs/SensorPreflightMag.md)
|
||||
- [NavigatorMissionItem](../msg_docs/NavigatorMissionItem.md)
|
||||
- [SensorGyroFft](../msg_docs/SensorGyroFft.md)
|
||||
- [EstimatorFusionControl](../msg_docs/EstimatorFusionControl.md)
|
||||
- [GeneratorStatus](../msg_docs/GeneratorStatus.md)
|
||||
- [VehicleAngularAccelerationSetpoint](../msg_docs/VehicleAngularAccelerationSetpoint.md)
|
||||
- [Gripper](../msg_docs/Gripper.md)
|
||||
- [LedControl](../msg_docs/LedControl.md)
|
||||
- [MavlinkTunnel](../msg_docs/MavlinkTunnel.md)
|
||||
- [SensorGyroFifo](../msg_docs/SensorGyroFifo.md)
|
||||
- [LandingTargetPose](../msg_docs/LandingTargetPose.md)
|
||||
- [OpenDroneIdSystem](../msg_docs/OpenDroneIdSystem.md)
|
||||
- [ActuatorArmed](../msg_docs/ActuatorArmed.md)
|
||||
- [BatteryStatusV0](../msg_docs/BatteryStatusV0.md)
|
||||
- [ActuatorControlsStatus](../msg_docs/ActuatorControlsStatus.md)
|
||||
- [FlightPhaseEstimation](../msg_docs/FlightPhaseEstimation.md)
|
||||
- [BatteryInfo](../msg_docs/BatteryInfo.md)
|
||||
- [DebugValue](../msg_docs/DebugValue.md)
|
||||
- [SensorGnssRelative](../msg_docs/SensorGnssRelative.md)
|
||||
- [RaptorInput](../msg_docs/RaptorInput.md)
|
||||
- [FixedWingLateralGuidanceStatus](../msg_docs/FixedWingLateralGuidanceStatus.md)
|
||||
- [EscEepromWrite](../msg_docs/EscEepromWrite.md)
|
||||
- [OrbTestLarge](../msg_docs/OrbTestLarge.md)
|
||||
- [RoverRateStatus](../msg_docs/RoverRateStatus.md)
|
||||
- [RangingBeacon](../msg_docs/RangingBeacon.md)
|
||||
- [LandingGearWheel](../msg_docs/LandingGearWheel.md)
|
||||
- [RtlTimeEstimate](../msg_docs/RtlTimeEstimate.md)
|
||||
- [RateCtrlStatus](../msg_docs/RateCtrlStatus.md)
|
||||
- [ManualControlSwitches](../msg_docs/ManualControlSwitches.md)
|
||||
- [DebugKeyValue](../msg_docs/DebugKeyValue.md)
|
||||
- [OpenDroneIdSelfId](../msg_docs/OpenDroneIdSelfId.md)
|
||||
- [TrajectorySetpoint6dof](../msg_docs/TrajectorySetpoint6dof.md)
|
||||
- [GimbalManagerStatus](../msg_docs/GimbalManagerStatus.md)
|
||||
- [GpioConfig](../msg_docs/GpioConfig.md)
|
||||
- [PpsCapture](../msg_docs/PpsCapture.md)
|
||||
- [HealthReport](../msg_docs/HealthReport.md)
|
||||
- [FollowTarget](../msg_docs/FollowTarget.md)
|
||||
- [FigureEightStatus](../msg_docs/FigureEightStatus.md)
|
||||
- [TecsStatus](../msg_docs/TecsStatus.md)
|
||||
- [SensorSelection](../msg_docs/SensorSelection.md)
|
||||
- [EstimatorSensorBias](../msg_docs/EstimatorSensorBias.md)
|
||||
- [Ping](../msg_docs/Ping.md)
|
||||
- [FixedWingLateralStatus](../msg_docs/FixedWingLateralStatus.md)
|
||||
- [SensorsStatus](../msg_docs/SensorsStatus.md)
|
||||
- [OrbTestMedium](../msg_docs/OrbTestMedium.md)
|
||||
- [VehicleStatusV0](../msg_docs/VehicleStatusV0.md)
|
||||
- [EscStatus](../msg_docs/EscStatus.md)
|
||||
- [Event](../msg_docs/Event.md)
|
||||
- [NormalizedUnsignedSetpoint](../msg_docs/NormalizedUnsignedSetpoint.md)
|
||||
- [ArmingCheckRequestV0](../msg_docs/ArmingCheckRequestV0.md)
|
||||
- [EscReport](../msg_docs/EscReport.md)
|
||||
- [NeuralControl](../msg_docs/NeuralControl.md)
|
||||
- [GpsInjectData](../msg_docs/GpsInjectData.md)
|
||||
- [GimbalManagerSetManualControl](../msg_docs/GimbalManagerSetManualControl.md)
|
||||
- [InternalCombustionEngineStatus](../msg_docs/InternalCombustionEngineStatus.md)
|
||||
- [GimbalManagerSetAttitude](../msg_docs/GimbalManagerSetAttitude.md)
|
||||
- [OpenDroneIdArmStatus](../msg_docs/OpenDroneIdArmStatus.md)
|
||||
- [HeaterStatus](../msg_docs/HeaterStatus.md)
|
||||
- [ParameterSetValueRequest](../msg_docs/ParameterSetValueRequest.md)
|
||||
- [GeofenceStatus](../msg_docs/GeofenceStatus.md)
|
||||
- [LogMessage](../msg_docs/LogMessage.md)
|
||||
- [OrbTest](../msg_docs/OrbTest.md)
|
||||
- [DebugArray](../msg_docs/DebugArray.md)
|
||||
- [QshellReq](../msg_docs/QshellReq.md)
|
||||
- [PurePursuitStatus](../msg_docs/PurePursuitStatus.md)
|
||||
- [PwmInput](../msg_docs/PwmInput.md)
|
||||
- [LoggerStatus](../msg_docs/LoggerStatus.md)
|
||||
- [Airspeed](../msg_docs/Airspeed.md)
|
||||
- [EstimatorGpsStatus](../msg_docs/EstimatorGpsStatus.md)
|
||||
- [GainCompression](../msg_docs/GainCompression.md)
|
||||
- [GimbalDeviceInformation](../msg_docs/GimbalDeviceInformation.md)
|
||||
- [PositionControllerLandingStatus](../msg_docs/PositionControllerLandingStatus.md)
|
||||
- [VehicleAngularVelocity](../msg_docs/VehicleAngularVelocity.md)
|
||||
- [ParameterUpdate](../msg_docs/ParameterUpdate.md)
|
||||
- [GimbalControls](../msg_docs/GimbalControls.md)
|
||||
- [CameraCapture](../msg_docs/CameraCapture.md)
|
||||
- [EstimatorStatus](../msg_docs/EstimatorStatus.md)
|
||||
- [HomePositionV0](../msg_docs/HomePositionV0.md)
|
||||
- [DatamanResponse](../msg_docs/DatamanResponse.md)
|
||||
- [EstimatorBias3d](../msg_docs/EstimatorBias3d.md)
|
||||
- [GimbalManagerInformation](../msg_docs/GimbalManagerInformation.md)
|
||||
- [PositionControllerStatus](../msg_docs/PositionControllerStatus.md)
|
||||
- [MissionResult](../msg_docs/MissionResult.md)
|
||||
- [RoverAttitudeStatus](../msg_docs/RoverAttitudeStatus.md)
|
||||
- [ActuatorServosTrim](../msg_docs/ActuatorServosTrim.md)
|
||||
- [VehicleAttitudeSetpointV0](../msg_docs/VehicleAttitudeSetpointV0.md)
|
||||
- [IridiumsbdStatus](../msg_docs/IridiumsbdStatus.md)
|
||||
- [TiltrotorExtraControls](../msg_docs/TiltrotorExtraControls.md)
|
||||
- [IrlockReport](../msg_docs/IrlockReport.md)
|
||||
- [TakeoffStatus](../msg_docs/TakeoffStatus.md)
|
||||
- [DebugVect](../msg_docs/DebugVect.md)
|
||||
- [DronecanNodeStatus](../msg_docs/DronecanNodeStatus.md)
|
||||
- [SensorHygrometer](../msg_docs/SensorHygrometer.md)
|
||||
- [UlogStreamAck](../msg_docs/UlogStreamAck.md)
|
||||
- [VehicleMagnetometer](../msg_docs/VehicleMagnetometer.md)
|
||||
- [UavcanParameterRequest](../msg_docs/UavcanParameterRequest.md)
|
||||
- [NavigatorStatus](../msg_docs/NavigatorStatus.md)
|
||||
- [SensorCorrection](../msg_docs/SensorCorrection.md)
|
||||
- [ArmingCheckReplyV0](../msg_docs/ArmingCheckReplyV0.md)
|
||||
- [ParameterSetUsedRequest](../msg_docs/ParameterSetUsedRequest.md)
|
||||
- [RegisterExtComponentRequestV0](../msg_docs/RegisterExtComponentRequestV0.md)
|
||||
- [CanInterfaceStatus](../msg_docs/CanInterfaceStatus.md)
|
||||
- [VehicleOpticalFlowVel](../msg_docs/VehicleOpticalFlowVel.md)
|
||||
- [Px4ioStatus](../msg_docs/Px4ioStatus.md)
|
||||
- [HoverThrustEstimate](../msg_docs/HoverThrustEstimate.md)
|
||||
- [UavcanParameterValue](../msg_docs/UavcanParameterValue.md)
|
||||
- [RtlStatus](../msg_docs/RtlStatus.md)
|
||||
- [LandingTargetInnovations](../msg_docs/LandingTargetInnovations.md)
|
||||
- [ParameterResetRequest](../msg_docs/ParameterResetRequest.md)
|
||||
- [MavlinkLog](../msg_docs/MavlinkLog.md)
|
||||
- [VehicleStatusV2](../msg_docs/VehicleStatusV2.md)
|
||||
- [RegisterExtComponentReplyV0](../msg_docs/RegisterExtComponentReplyV0.md)
|
||||
- [ButtonEvent](../msg_docs/ButtonEvent.md)
|
||||
- [ActuatorTest](../msg_docs/ActuatorTest.md)
|
||||
- [Ekf2Timestamps](../msg_docs/Ekf2Timestamps.md)
|
||||
- [GimbalDeviceSetAttitude](../msg_docs/GimbalDeviceSetAttitude.md)
|
||||
- [InputRc](../msg_docs/InputRc.md)
|
||||
- [Rpm](../msg_docs/Rpm.md)
|
||||
- [VehicleLocalPositionSetpoint](../msg_docs/VehicleLocalPositionSetpoint.md)
|
||||
- [AirspeedWind](../msg_docs/AirspeedWind.md)
|
||||
- [AutotuneAttitudeControlStatus](../msg_docs/AutotuneAttitudeControlStatus.md)
|
||||
- [TaskStackInfo](../msg_docs/TaskStackInfo.md)
|
||||
- [RoverSpeedStatus](../msg_docs/RoverSpeedStatus.md)
|
||||
- [InternalCombustionEngineControl](../msg_docs/InternalCombustionEngineControl.md)
|
||||
- [VehicleCommandAckV0](../msg_docs/VehicleCommandAckV0.md)
|
||||
- [DeviceInformation](../msg_docs/DeviceInformation.md)
|
||||
- [ControlAllocatorStatus](../msg_docs/ControlAllocatorStatus.md)
|
||||
- [EstimatorAidSource2d](../msg_docs/EstimatorAidSource2d.md)
|
||||
- [SensorMag](../msg_docs/SensorMag.md)
|
||||
- [VehicleOpticalFlow](../msg_docs/VehicleOpticalFlow.md)
|
||||
- [VehicleGlobalPositionV0](../msg_docs/VehicleGlobalPositionV0.md)
|
||||
- [CameraTrigger](../msg_docs/CameraTrigger.md)
|
||||
- [OpenDroneIdOperatorId](../msg_docs/OpenDroneIdOperatorId.md)
|
||||
- [ActionRequest](../msg_docs/ActionRequest.md)
|
||||
- [PowerMonitor](../msg_docs/PowerMonitor.md)
|
||||
- [LaunchDetectionStatus](../msg_docs/LaunchDetectionStatus.md)
|
||||
- [YawEstimatorStatus](../msg_docs/YawEstimatorStatus.md)
|
||||
- [EventV0](../msg_docs/EventV0.md)
|
||||
- [SensorGnssStatus](../msg_docs/SensorGnssStatus.md)
|
||||
- [AdcReport](../msg_docs/AdcReport.md)
|
||||
- [DatamanRequest](../msg_docs/DatamanRequest.md)
|
||||
- [EstimatorEventFlags](../msg_docs/EstimatorEventFlags.md)
|
||||
- [AirspeedValidatedV0](../msg_docs/AirspeedValidatedV0.md)
|
||||
- [UlogStream](../msg_docs/UlogStream.md)
|
||||
- [GpioRequest](../msg_docs/GpioRequest.md)
|
||||
- [FuelTankStatus](../msg_docs/FuelTankStatus.md)
|
||||
- [SensorAccelFifo](../msg_docs/SensorAccelFifo.md)
|
||||
- [VehicleImu](../msg_docs/VehicleImu.md)
|
||||
- [OrbitStatus](../msg_docs/OrbitStatus.md)
|
||||
- [VehicleRoi](../msg_docs/VehicleRoi.md)
|
||||
- [FollowTargetEstimator](../msg_docs/FollowTargetEstimator.md)
|
||||
- [DifferentialPressure](../msg_docs/DifferentialPressure.md)
|
||||
- [MountOrientation](../msg_docs/MountOrientation.md)
|
||||
- [EstimatorStates](../msg_docs/EstimatorStates.md)
|
||||
- [SensorBaro](../msg_docs/SensorBaro.md)
|
||||
- [VelocityLimits](../msg_docs/VelocityLimits.md)
|
||||
- [EstimatorSelectorStatus](../msg_docs/EstimatorSelectorStatus.md)
|
||||
- [GpioIn](../msg_docs/GpioIn.md)
|
||||
- [Vtx](../msg_docs/Vtx.md)
|
||||
- [FollowTargetStatus](../msg_docs/FollowTargetStatus.md)
|
||||
- [PositionSetpoint](../msg_docs/PositionSetpoint.md)
|
||||
- [ConfigOverridesV0](../msg_docs/ConfigOverridesV0.md)
|
||||
- [ActuatorOutputs](../msg_docs/ActuatorOutputs.md)
|
||||
- [RcParameterMap](../msg_docs/RcParameterMap.md)
|
||||
- [VehicleConstraints](../msg_docs/VehicleConstraints.md)
|
||||
- [ParameterSetValueResponse](../msg_docs/ParameterSetValueResponse.md)
|
||||
- [FailureDetectorStatus](../msg_docs/FailureDetectorStatus.md)
|
||||
- [MagWorkerData](../msg_docs/MagWorkerData.md)
|
||||
- [VehicleLocalPositionV0](../msg_docs/VehicleLocalPositionV0.md)
|
||||
- [EstimatorAidSource1d](../msg_docs/EstimatorAidSource1d.md)
|
||||
- [RcChannels](../msg_docs/RcChannels.md)
|
||||
- [RadioStatus](../msg_docs/RadioStatus.md)
|
||||
- [Mission](../msg_docs/Mission.md)
|
||||
- [SatelliteInfo](../msg_docs/SatelliteInfo.md)
|
||||
- [TuneControl](../msg_docs/TuneControl.md)
|
||||
- [CameraStatus](../msg_docs/CameraStatus.md)
|
||||
- [GpioOut](../msg_docs/GpioOut.md)
|
||||
- [MagnetometerBiasEstimate](../msg_docs/MagnetometerBiasEstimate.md)
|
||||
- [GeofenceResult](../msg_docs/GeofenceResult.md)
|
||||
- [VehicleStatusV1](../msg_docs/VehicleStatusV1.md)
|
||||
- [SensorTemp](../msg_docs/SensorTemp.md)
|
||||
- [EstimatorAidSource3d](../msg_docs/EstimatorAidSource3d.md)
|
||||
- [FixedWingRunwayControl](../msg_docs/FixedWingRunwayControl.md)
|
||||
- [Cpuload](../msg_docs/Cpuload.md)
|
||||
- [GpsDump](../msg_docs/GpsDump.md)
|
||||
- [CellularStatus](../msg_docs/CellularStatus.md)
|
||||
- [VehicleImuStatus](../msg_docs/VehicleImuStatus.md)
|
||||
- [SensorsStatusImu](../msg_docs/SensorsStatusImu.md)
|
||||
- [SensorUwb](../msg_docs/SensorUwb.md)
|
||||
- [RaptorStatus](../msg_docs/RaptorStatus.md)
|
||||
- [PowerButtonState](../msg_docs/PowerButtonState.md)
|
||||
- [SensorGyro](../msg_docs/SensorGyro.md)
|
||||
- [SensorAirflow](../msg_docs/SensorAirflow.md)
|
||||
- [WheelEncoders](../msg_docs/WheelEncoders.md)
|
||||
- [EscEepromRead](../msg_docs/EscEepromRead.md)
|
||||
- [SystemPower](../msg_docs/SystemPower.md)
|
||||
- [DistanceSensorModeChangeRequest](../msg_docs/DistanceSensorModeChangeRequest.md)
|
||||
- [VehicleAirData](../msg_docs/VehicleAirData.md)
|
||||
- [FixedWingLateralGuidanceStatus](../msg_docs/FixedWingLateralGuidanceStatus.md)
|
||||
- [EstimatorBias3d](../msg_docs/EstimatorBias3d.md)
|
||||
- [NeuralControl](../msg_docs/NeuralControl.md)
|
||||
- [GeneratorStatus](../msg_docs/GeneratorStatus.md)
|
||||
- [VehicleLocalPositionV0](../msg_docs/VehicleLocalPositionV0.md)
|
||||
- [LoggerStatus](../msg_docs/LoggerStatus.md)
|
||||
- [SensorHygrometer](../msg_docs/SensorHygrometer.md)
|
||||
- [EstimatorStatus](../msg_docs/EstimatorStatus.md)
|
||||
- [VehicleStatusV2](../msg_docs/VehicleStatusV2.md)
|
||||
- [UavcanParameterValue](../msg_docs/UavcanParameterValue.md)
|
||||
- [TrajectorySetpoint6dof](../msg_docs/TrajectorySetpoint6dof.md)
|
||||
- [Ekf2Timestamps](../msg_docs/Ekf2Timestamps.md)
|
||||
- [GainCompression](../msg_docs/GainCompression.md)
|
||||
- [VehicleAngularVelocity](../msg_docs/VehicleAngularVelocity.md)
|
||||
- [FailureDetectorStatus](../msg_docs/FailureDetectorStatus.md)
|
||||
- [OpenDroneIdArmStatus](../msg_docs/OpenDroneIdArmStatus.md)
|
||||
- [RateCtrlStatus](../msg_docs/RateCtrlStatus.md)
|
||||
- [Cpuload](../msg_docs/Cpuload.md)
|
||||
- [Mission](../msg_docs/Mission.md)
|
||||
- [ActuatorServosTrim](../msg_docs/ActuatorServosTrim.md)
|
||||
- [OpenDroneIdOperatorId](../msg_docs/OpenDroneIdOperatorId.md)
|
||||
- [PositionControllerLandingStatus](../msg_docs/PositionControllerLandingStatus.md)
|
||||
- [LogMessage](../msg_docs/LogMessage.md)
|
||||
- [HomePositionV0](../msg_docs/HomePositionV0.md)
|
||||
- [VehicleGlobalPositionV0](../msg_docs/VehicleGlobalPositionV0.md)
|
||||
- [VehicleLocalPositionSetpoint](../msg_docs/VehicleLocalPositionSetpoint.md)
|
||||
- [QshellRetval](../msg_docs/QshellRetval.md)
|
||||
- [GpioIn](../msg_docs/GpioIn.md)
|
||||
- [GimbalManagerSetAttitude](../msg_docs/GimbalManagerSetAttitude.md)
|
||||
- [NormalizedUnsignedSetpoint](../msg_docs/NormalizedUnsignedSetpoint.md)
|
||||
- [FollowTargetStatus](../msg_docs/FollowTargetStatus.md)
|
||||
- [GimbalManagerSetManualControl](../msg_docs/GimbalManagerSetManualControl.md)
|
||||
- [TaskStackInfo](../msg_docs/TaskStackInfo.md)
|
||||
- [TakeoffStatus](../msg_docs/TakeoffStatus.md)
|
||||
- [FlightPhaseEstimation](../msg_docs/FlightPhaseEstimation.md)
|
||||
- [SensorMag](../msg_docs/SensorMag.md)
|
||||
- [PositionSetpoint](../msg_docs/PositionSetpoint.md)
|
||||
- [FixedWingRunwayControl](../msg_docs/FixedWingRunwayControl.md)
|
||||
- [FollowTargetEstimator](../msg_docs/FollowTargetEstimator.md)
|
||||
- [DeviceInformation](../msg_docs/DeviceInformation.md)
|
||||
- [OrbitStatus](../msg_docs/OrbitStatus.md)
|
||||
- [CellularStatus](../msg_docs/CellularStatus.md)
|
||||
- [ArmingCheckReplyV0](../msg_docs/ArmingCheckReplyV0.md)
|
||||
- [InternalCombustionEngineControl](../msg_docs/InternalCombustionEngineControl.md)
|
||||
- [TecsStatus](../msg_docs/TecsStatus.md)
|
||||
- [Event](../msg_docs/Event.md)
|
||||
- [ParameterResetRequest](../msg_docs/ParameterResetRequest.md)
|
||||
- [SensorGnssRelative](../msg_docs/SensorGnssRelative.md)
|
||||
- [VehicleAttitudeSetpointV0](../msg_docs/VehicleAttitudeSetpointV0.md)
|
||||
- [VehicleAcceleration](../msg_docs/VehicleAcceleration.md)
|
||||
- [LandingGearWheel](../msg_docs/LandingGearWheel.md)
|
||||
- [SatelliteInfo](../msg_docs/SatelliteInfo.md)
|
||||
- [VehicleConstraints](../msg_docs/VehicleConstraints.md)
|
||||
- [VehicleImu](../msg_docs/VehicleImu.md)
|
||||
- [VehicleOpticalFlow](../msg_docs/VehicleOpticalFlow.md)
|
||||
- [VehicleImuStatus](../msg_docs/VehicleImuStatus.md)
|
||||
- [CameraTrigger](../msg_docs/CameraTrigger.md)
|
||||
- [RoverRateStatus](../msg_docs/RoverRateStatus.md)
|
||||
- [RoverAttitudeStatus](../msg_docs/RoverAttitudeStatus.md)
|
||||
- [TiltrotorExtraControls](../msg_docs/TiltrotorExtraControls.md)
|
||||
- [EstimatorAidSource2d](../msg_docs/EstimatorAidSource2d.md)
|
||||
- [ControlAllocatorStatus](../msg_docs/ControlAllocatorStatus.md)
|
||||
- [PositionControllerStatus](../msg_docs/PositionControllerStatus.md)
|
||||
- [EstimatorSelectorStatus](../msg_docs/EstimatorSelectorStatus.md)
|
||||
- [EstimatorSensorBias](../msg_docs/EstimatorSensorBias.md)
|
||||
- [SensorGyroFifo](../msg_docs/SensorGyroFifo.md)
|
||||
- [SensorGyro](../msg_docs/SensorGyro.md)
|
||||
- [ActuatorTest](../msg_docs/ActuatorTest.md)
|
||||
- [PurePursuitStatus](../msg_docs/PurePursuitStatus.md)
|
||||
- [DronecanNodeStatus](../msg_docs/DronecanNodeStatus.md)
|
||||
- [GpioConfig](../msg_docs/GpioConfig.md)
|
||||
- [EscEepromWrite](../msg_docs/EscEepromWrite.md)
|
||||
- [Px4ioStatus](../msg_docs/Px4ioStatus.md)
|
||||
- [ParameterSetValueRequest](../msg_docs/ParameterSetValueRequest.md)
|
||||
- [HeaterStatus](../msg_docs/HeaterStatus.md)
|
||||
- [InputRc](../msg_docs/InputRc.md)
|
||||
- [RcParameterMap](../msg_docs/RcParameterMap.md)
|
||||
- [SystemPower](../msg_docs/SystemPower.md)
|
||||
- [GeofenceResult](../msg_docs/GeofenceResult.md)
|
||||
- [ConfigOverridesV0](../msg_docs/ConfigOverridesV0.md)
|
||||
- [RcChannels](../msg_docs/RcChannels.md)
|
||||
- [SensorAccelFifo](../msg_docs/SensorAccelFifo.md)
|
||||
- [RegisterExtComponentReplyV0](../msg_docs/RegisterExtComponentReplyV0.md)
|
||||
- [Airspeed](../msg_docs/Airspeed.md)
|
||||
- [InternalCombustionEngineStatus](../msg_docs/InternalCombustionEngineStatus.md)
|
||||
- [QshellRetval](../msg_docs/QshellRetval.md)
|
||||
- [SensorAccel](../msg_docs/SensorAccel.md)
|
||||
:::
|
||||
|
||||
@@ -18,7 +18,7 @@ It has been tested with the following devices:
|
||||
Any of the devices can be connected to any free/unused serial port on the flight controller.
|
||||
Most commonly they are connected to `TELEM2` (if this is not being use for some other purpose).
|
||||
|
||||
### PingRX
|
||||
### PingRX Pro
|
||||
|
||||
The PingRX MAVLink port uses a JST ZHR-4 mating connector with pinout as shown below.
|
||||
|
||||
@@ -29,9 +29,19 @@ The PingRX MAVLink port uses a JST ZHR-4 mating connector with pinout as shown b
|
||||
| 3 (blk) | Power | +4 to 6V |
|
||||
| 4 (blk) | GND | GND |
|
||||
|
||||
The PingRX comes with connector cable that can be attached directly to the TELEM2 port (DF13-6P) on an [mRo Pixhawk](../flight_controller/mro_pixhawk.md).
|
||||
The PingRX comes with connector cable that can be attached directly to the `TELEM2` port (DF13-6P) on an [mRo Pixhawk](../flight_controller/mro_pixhawk.md).
|
||||
For other ports or boards, you will need to obtain your own cable.
|
||||
|
||||
The recommended port configuration for this receiver is:
|
||||
|
||||
| Parameter | Recommended Value |
|
||||
| ---------------------------------------------------------------------------- | ----------------- |
|
||||
| [MAV_1_CONFIG](../advanced_config/parameter_reference.md#MAV_1_CONFIG) | `TELEM 2` |
|
||||
| [MAV_1_MODE](../advanced_config/parameter_reference.md#MAV_1_MODE) | uAvionix |
|
||||
| [MAV_1_FORWARD](../advanced_config/parameter_reference.md#MAV_1_FORWARD) | Enabled |
|
||||
| [MAV_1_RADIO_CTL](../advanced_config/parameter_reference.md#MAV_1_RADIO_CTL) | Disabled |
|
||||
| [MAV_1_FLOW_CTRL](../advanced_config/parameter_reference.md#MAV_2_FLOW_CTRL) | Force off |
|
||||
|
||||
## FLARM
|
||||
|
||||
FLARM has an on-board DF-13 6 Pin connector that has an identical pinout to the [mRo Pixhawk](../flight_controller/mro_pixhawk.md).
|
||||
@@ -49,7 +59,7 @@ FLARM has an on-board DF-13 6 Pin connector that has an identical pinout to the
|
||||
The TX and RX on the flight controller must be connected to the RX and TX on the FLARM, respectively.
|
||||
:::
|
||||
|
||||
## Software Configuration
|
||||
## PX4 Configuration
|
||||
|
||||
### Port Configuration
|
||||
|
||||
@@ -58,10 +68,12 @@ The only _specific_ setup is that the port baud rate must be set to 57600 and th
|
||||
|
||||
Assuming you have connected the device to the TELEM2 port, [set the parameters](../advanced_config/parameters.md) as shown:
|
||||
|
||||
- [MAV_1_CONFIG](../advanced_config/parameter_reference.md#MAV_1_CONFIG) = TELEM 2
|
||||
- [MAV_1_MODE](../advanced_config/parameter_reference.md#MAV_1_MODE) = Normal
|
||||
- [MAV_1_RATE](../advanced_config/parameter_reference.md#MAV_1_RATE) = 0 (default sending rate for port).
|
||||
- [MAV_1_FORWARD](../advanced_config/parameter_reference.md#MAV_1_FORWARD) = Enabled
|
||||
| Parameter | Recommended Value |
|
||||
| ------------------------------------------------------------------------ | --------------------------------- |
|
||||
| [MAV_1_CONFIG](../advanced_config/parameter_reference.md#MAV_1_CONFIG) | `TELEM 2` |
|
||||
| [MAV_1_MODE](../advanced_config/parameter_reference.md#MAV_1_MODE) | Normal |
|
||||
| [MAV_1_RATE](../advanced_config/parameter_reference.md#MAV_1_RATE) | 0 (default sending rate for port) |
|
||||
| [MAV_1_FORWARD](../advanced_config/parameter_reference.md#MAV_1_FORWARD) | Enabled |
|
||||
|
||||
Then reboot the vehicle.
|
||||
|
||||
|
||||
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
@@ -193,7 +193,7 @@ config WQ_HP_DEFAULT_PRIORITY
|
||||
|
||||
config WQ_UAVCAN_STACKSIZE
|
||||
int "Stack size for uavcan"
|
||||
default 3624
|
||||
default 3754
|
||||
range 1000 10000
|
||||
help
|
||||
Sets the stack size for the uavcan work queue.
|
||||
|
||||
@@ -98,16 +98,6 @@ add_custom_command(OUTPUT ${generated_serial_params_file} ${generated_module_par
|
||||
COMMENT "Generating serial_params.c"
|
||||
)
|
||||
|
||||
# readonly params config (used by both px_process_params.py and px_generate_params.py)
|
||||
set(READONLY_PARAMS_CONFIG "${PX4_BOARD_DIR}/readonly_params.yaml")
|
||||
if(EXISTS ${READONLY_PARAMS_CONFIG})
|
||||
set(READONLY_PARAMS_ARG "--readonly-config" "${READONLY_PARAMS_CONFIG}")
|
||||
set(READONLY_PARAMS_DEPEND "${READONLY_PARAMS_CONFIG}")
|
||||
else()
|
||||
set(READONLY_PARAMS_ARG "")
|
||||
set(READONLY_PARAMS_DEPEND "")
|
||||
endif()
|
||||
|
||||
set(parameters_xml ${PX4_BINARY_DIR}/parameters.xml)
|
||||
set(parameters_json ${PX4_BINARY_DIR}/parameters.json)
|
||||
add_custom_command(OUTPUT ${parameters_xml} ${parameters_json} ${parameters_json}.xz
|
||||
@@ -118,7 +108,6 @@ add_custom_command(OUTPUT ${parameters_xml} ${parameters_json} ${parameters_json
|
||||
--compress
|
||||
--overrides ${PARAM_DEFAULT_OVERRIDES}
|
||||
--board ${PX4_BOARD}
|
||||
${READONLY_PARAMS_ARG}
|
||||
#--verbose
|
||||
COMMAND ${PYTHON_EXECUTABLE} ${PX4_SOURCE_DIR}/Tools/validate_json.py
|
||||
--schema-file ${PX4_SOURCE_DIR}/src/modules/mavlink/mavlink/component_information/parameter.schema.json
|
||||
@@ -128,26 +117,21 @@ add_custom_command(OUTPUT ${parameters_xml} ${parameters_json} ${parameters_json
|
||||
DEPENDS
|
||||
${generated_serial_params_file}
|
||||
${generated_module_params_file}
|
||||
${READONLY_PARAMS_DEPEND}
|
||||
px4params/srcparser.py
|
||||
px4params/srcscanner.py
|
||||
px4params/jsonout.py
|
||||
px4params/xmlout.py
|
||||
px4params/readonly_config.py
|
||||
px_process_params.py
|
||||
COMMENT "Generating parameters.xml"
|
||||
)
|
||||
add_custom_target(parameters_xml DEPENDS ${parameters_xml})
|
||||
|
||||
# generate px4_parameters.hpp
|
||||
|
||||
add_custom_command(OUTPUT px4_parameters.hpp
|
||||
COMMAND ${PYTHON_EXECUTABLE} ${CMAKE_CURRENT_SOURCE_DIR}/px_generate_params.py
|
||||
--xml ${parameters_xml} --dest ${CMAKE_CURRENT_BINARY_DIR}
|
||||
${READONLY_PARAMS_ARG}
|
||||
DEPENDS
|
||||
${PX4_BINARY_DIR}/parameters.xml
|
||||
${READONLY_PARAMS_DEPEND}
|
||||
px_generate_params.py
|
||||
templates/px4_parameters.hpp.jinja
|
||||
)
|
||||
|
||||
@@ -175,23 +175,6 @@ __EXPORT const char *param_name(param_t param);
|
||||
*/
|
||||
__EXPORT bool param_is_volatile(param_t param);
|
||||
|
||||
/**
|
||||
* Obtain the read-only state of a parameter.
|
||||
*
|
||||
* @param param A handle returned by param_find or passed by param_foreach.
|
||||
* @return true if the parameter is read-only
|
||||
*/
|
||||
__EXPORT bool param_is_readonly(param_t param);
|
||||
|
||||
/**
|
||||
* Lock all read-only parameters.
|
||||
*
|
||||
* Before this call, read-only parameters can be freely modified (e.g. by
|
||||
* startup scripts). After this call, any attempt to set, set-default, or
|
||||
* reset a read-only parameter will be rejected.
|
||||
*/
|
||||
__EXPORT void param_lock_readonly(void);
|
||||
|
||||
/**
|
||||
* Test whether a parameter's value has changed from the default.
|
||||
*
|
||||
|
||||
@@ -413,11 +413,6 @@ param_set_internal(param_t param, const void *val, bool mark_saved, bool notify_
|
||||
return PX4_ERROR;
|
||||
}
|
||||
|
||||
if (param_is_readonly(param)) {
|
||||
PX4_WARN("param %s is read-only", param_name(param));
|
||||
return PX4_ERROR;
|
||||
}
|
||||
|
||||
int result = -1;
|
||||
bool param_changed = false;
|
||||
perf_begin(param_set_perf);
|
||||
@@ -549,11 +544,6 @@ int param_set_default_value(param_t param, const void *val)
|
||||
return PX4_ERROR;
|
||||
}
|
||||
|
||||
if (param_is_readonly(param)) {
|
||||
PX4_WARN("param %s is read-only", param_name(param));
|
||||
return PX4_ERROR;
|
||||
}
|
||||
|
||||
int result = PX4_ERROR;
|
||||
|
||||
|
||||
@@ -625,10 +615,6 @@ static int param_reset_internal(param_t param, bool notify = true, bool autosave
|
||||
return false;
|
||||
#endif
|
||||
|
||||
if (param_is_readonly(param)) {
|
||||
return 0; // silently skip — param_reset_all loops over all params
|
||||
}
|
||||
|
||||
bool param_found = user_config.contains(param);
|
||||
|
||||
if (handle_in_range(param)) {
|
||||
|
||||
@@ -96,26 +96,6 @@ bool param_is_volatile(param_t param)
|
||||
return false;
|
||||
}
|
||||
|
||||
static bool params_locked = false;
|
||||
|
||||
bool param_is_readonly(param_t param)
|
||||
{
|
||||
if (params_locked && handle_in_range(param)) {
|
||||
for (const auto &p : px4::parameters_readonly) {
|
||||
if (static_cast<px4::params>(param) == p) {
|
||||
return true;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
return false;
|
||||
}
|
||||
|
||||
void param_lock_readonly()
|
||||
{
|
||||
params_locked = true;
|
||||
}
|
||||
|
||||
size_t param_size(param_t param)
|
||||
{
|
||||
if (handle_in_range(param)) {
|
||||
|
||||
@@ -82,8 +82,6 @@ class JsonOutput():
|
||||
|
||||
if param.GetVolatile():
|
||||
curr_param['volatile'] = True
|
||||
if param.GetReadonly():
|
||||
curr_param['readOnly'] = True
|
||||
|
||||
last_param_name = param.GetName()
|
||||
for code in param.GetFieldCodes():
|
||||
|
||||
@@ -104,8 +104,7 @@ If a listed parameter is missing from the Firmware see: [Finding/Updating Parame
|
||||
if bitmask_list:
|
||||
result += bitmask_output
|
||||
# Format the ranges as a table.
|
||||
is_readonly = param.GetReadonly()
|
||||
result += f"Reboot | minValue | maxValue | increment | default | unit | Read-Only\n--- | --- | --- | --- | --- | --- | ---\n{'✓' if reboot_required else ' ' } | {min_val} | {max_val} | {increment} | {def_val} | {unit} | {'✓' if is_readonly else ' '}\n\n"
|
||||
result += f"Reboot | minValue | maxValue | increment | default | unit\n--- | --- | --- | --- | --- | ---\n{'✓' if reboot_required else ' ' } | {min_val} | {max_val} | {increment} | {def_val} | {unit} | \n\n"
|
||||
|
||||
self.output = result
|
||||
|
||||
|
||||
@@ -1,48 +0,0 @@
|
||||
"""
|
||||
Shared helper to load readonly parameter configuration from YAML.
|
||||
"""
|
||||
import sys
|
||||
|
||||
try:
|
||||
import yaml
|
||||
except ImportError as e:
|
||||
print("Failed to import yaml: " + str(e))
|
||||
print("")
|
||||
print("You may need to install it using:")
|
||||
print(" pip3 install --user pyyaml")
|
||||
print("")
|
||||
sys.exit(1)
|
||||
|
||||
|
||||
def load_readonly_params(readonly_config, all_param_names):
|
||||
"""
|
||||
Load readonly parameter config and return the set of readonly param names.
|
||||
|
||||
@param readonly_config: path to readonly_params.yaml
|
||||
@param all_param_names: set of all known parameter names
|
||||
@return: set of readonly parameter names
|
||||
"""
|
||||
if readonly_config is None:
|
||||
return set()
|
||||
|
||||
with open(readonly_config, 'r') as f:
|
||||
config = yaml.safe_load(f)
|
||||
|
||||
mode = config.get('mode', 'block')
|
||||
listed_params = set(config.get('parameters', []))
|
||||
|
||||
# Validate that all listed parameters actually exist
|
||||
unknown = listed_params - all_param_names
|
||||
if unknown:
|
||||
print("Error: readonly_params.yaml lists unknown parameters: %s" % ', '.join(sorted(unknown)))
|
||||
sys.exit(1)
|
||||
|
||||
if mode == 'block':
|
||||
# Listed params are read-only
|
||||
return listed_params
|
||||
elif mode == 'allow':
|
||||
# Only listed params are writable, all others are read-only
|
||||
return all_param_names - listed_params
|
||||
else:
|
||||
print("Error: readonly_params.yaml has unknown mode '%s' (expected 'block' or 'allow')" % mode)
|
||||
sys.exit(1)
|
||||
@@ -61,7 +61,6 @@ class Parameter(object):
|
||||
self.category = ""
|
||||
self.volatile = False
|
||||
self.boolean = False
|
||||
self.readonly = False
|
||||
|
||||
def GetName(self):
|
||||
return self.name
|
||||
@@ -81,9 +80,6 @@ class Parameter(object):
|
||||
def GetBoolean(self):
|
||||
return self.boolean
|
||||
|
||||
def GetReadonly(self):
|
||||
return self.readonly
|
||||
|
||||
def SetField(self, code, value):
|
||||
"""
|
||||
Set named field value
|
||||
@@ -114,12 +110,6 @@ class Parameter(object):
|
||||
"""
|
||||
self.boolean = True
|
||||
|
||||
def SetReadonly(self):
|
||||
"""
|
||||
Set readonly flag
|
||||
"""
|
||||
self.readonly = True
|
||||
|
||||
def SetCategory(self, category):
|
||||
"""
|
||||
Set param category
|
||||
|
||||
@@ -43,8 +43,6 @@ class XMLOutput():
|
||||
xml_param.attrib["volatile"] = "true"
|
||||
if param.GetBoolean():
|
||||
xml_param.attrib["boolean"] = "true"
|
||||
if param.GetReadonly():
|
||||
xml_param.attrib["readonly"] = "true"
|
||||
if (param.GetCategory()):
|
||||
xml_param.attrib["category"] = param.GetCategory()
|
||||
last_param_name = param.GetName()
|
||||
|
||||
@@ -18,15 +18,13 @@ except ImportError as e:
|
||||
sys.exit(1)
|
||||
|
||||
import os
|
||||
from px4params.readonly_config import load_readonly_params
|
||||
|
||||
def generate(xml_file, dest='.', readonly_config=None):
|
||||
def generate(xml_file, dest='.'):
|
||||
"""
|
||||
Generate px4 param source from xml.
|
||||
|
||||
@param xml_file: input parameter xml file
|
||||
@param dest: Destination directory for generated files
|
||||
@param readonly_config: path to readonly_params.yaml (optional)
|
||||
None means to scan everything.
|
||||
"""
|
||||
# pylint: disable=broad-except
|
||||
@@ -41,9 +39,6 @@ def generate(xml_file, dest='.', readonly_config=None):
|
||||
|
||||
params = sorted(params, key=lambda name: name.attrib["name"])
|
||||
|
||||
all_param_names = set(p.attrib["name"] for p in params)
|
||||
readonly_params = load_readonly_params(readonly_config, all_param_names)
|
||||
|
||||
script_path = os.path.dirname(os.path.realpath(__file__))
|
||||
|
||||
# for jinja docs see: http://jinja.pocoo.org/docs/2.9/api/
|
||||
@@ -60,14 +55,13 @@ def generate(xml_file, dest='.', readonly_config=None):
|
||||
template = env.get_template(template_file)
|
||||
with open(os.path.join(
|
||||
dest, template_file.replace('.jinja','')), 'w') as fid:
|
||||
fid.write(template.render(params=params, readonly_params=readonly_params))
|
||||
fid.write(template.render(params=params))
|
||||
|
||||
if __name__ == "__main__":
|
||||
arg_parser = argparse.ArgumentParser()
|
||||
arg_parser.add_argument("--xml", help="parameter xml file")
|
||||
arg_parser.add_argument("--dest", help="destination path", default=os.path.curdir)
|
||||
arg_parser.add_argument("--readonly-config", help="path to readonly_params.yaml", default=None)
|
||||
args = arg_parser.parse_args()
|
||||
generate(xml_file=args.xml, dest=args.dest, readonly_config=args.readonly_config)
|
||||
generate(xml_file=args.xml, dest=args.dest)
|
||||
|
||||
# vim: set et fenc=utf-8 ff=unix sts=4 sw=4 ts=4 :
|
||||
|
||||
@@ -47,7 +47,7 @@ from __future__ import print_function
|
||||
import sys
|
||||
import os
|
||||
import argparse
|
||||
from px4params import srcscanner, srcparser, injectxmlparams, xmlout, markdownout, jsonout, readonly_config
|
||||
from px4params import srcscanner, srcparser, injectxmlparams, xmlout, markdownout, jsonout
|
||||
|
||||
import lzma #to create .xz file
|
||||
import json
|
||||
@@ -102,10 +102,6 @@ def main():
|
||||
default="{}",
|
||||
metavar="OVERRIDES",
|
||||
help="a dict of overrides in the form of a json string")
|
||||
parser.add_argument("--readonly-config",
|
||||
default=None,
|
||||
metavar="FILENAME",
|
||||
help="path to readonly_params.yaml")
|
||||
|
||||
args = parser.parse_args()
|
||||
|
||||
@@ -147,18 +143,6 @@ def main():
|
||||
param.default = val
|
||||
print("OVERRIDING {:s} to {:s}!!!!!".format(name, val))
|
||||
|
||||
# Mark readonly parameters
|
||||
if args.readonly_config:
|
||||
all_param_names = set()
|
||||
for group in param_groups:
|
||||
for param in group.GetParams():
|
||||
all_param_names.add(param.GetName())
|
||||
readonly_params = readonly_config.load_readonly_params(args.readonly_config, all_param_names)
|
||||
for group in param_groups:
|
||||
for param in group.GetParams():
|
||||
if param.GetName() in readonly_params:
|
||||
param.SetReadonly()
|
||||
|
||||
output_files = []
|
||||
|
||||
# Output to XML file
|
||||
|
||||
@@ -47,13 +47,5 @@ static constexpr params parameters_volatile[] = {
|
||||
{% endfor %}
|
||||
};
|
||||
|
||||
static constexpr params parameters_readonly[] = {
|
||||
{% for param in params %}
|
||||
{%- if param.attrib["name"] in readonly_params %}
|
||||
params::{{ param.attrib["name"] }},
|
||||
{%- endif -%}
|
||||
{% endfor %}
|
||||
};
|
||||
|
||||
|
||||
} // namespace px4
|
||||
|
||||
@@ -140,9 +140,6 @@ MavlinkParametersManager::handle_message(const mavlink_message_t *msg)
|
||||
PX4_ERR("param types mismatch param: %s", name);
|
||||
send_error(MAV_PARAM_ERROR_TYPE_MISMATCH, name, -1, msg->sysid, msg->compid);
|
||||
|
||||
} else if (param_is_readonly(param)) {
|
||||
PX4_WARN("param %s is read-only", name);
|
||||
send_error(MAV_PARAM_ERROR_READ_ONLY, name, -1, msg->sysid, msg->compid);
|
||||
|
||||
} else {
|
||||
// According to the mavlink spec we should always acknowledge a write operation.
|
||||
|
||||
@@ -65,6 +65,243 @@
|
||||
#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
|
||||
|
||||
@@ -1,6 +1,6 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2019-2025 PX4 Development Team. All rights reserved.
|
||||
* Copyright (c) 2019-2026 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
@@ -252,6 +252,37 @@ 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)
|
||||
@@ -314,7 +345,11 @@ 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]),
|
||||
@@ -340,28 +375,34 @@ void Sih::generate_force_and_torques(const float dt)
|
||||
_Ma_B = -_KDW * _w_B; // first order angular damper
|
||||
|
||||
} else if (_vehicle == VehicleType::FixedWing) {
|
||||
_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]);
|
||||
|
||||
_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]);
|
||||
|
||||
} else if (_vehicle == VehicleType::TailsitterVTOL) {
|
||||
_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
|
||||
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]);
|
||||
generate_ts_aerodynamics();
|
||||
|
||||
} else if (_vehicle == VehicleType::StandardVTOL) {
|
||||
|
||||
_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]),
|
||||
_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],
|
||||
_L_PITCH * _T_MAX * (+_u[0] - _u[1] + _u[2] - _u[3]),
|
||||
_Q_MAX * (+_u[0] + _u[1] - _u[2] - _u[3]));
|
||||
|
||||
// thrust 0 because it is already contained in _T_B. in
|
||||
// equations_of_motion they are all summed into sum_of_forces_E
|
||||
// thrust 0 means no propwash on the tail
|
||||
generate_fw_aerodynamics(_u[4], _u[5], _u[6], 0);
|
||||
|
||||
} else if (_vehicle == VehicleType::RoverAckermann) {
|
||||
@@ -370,21 +411,20 @@ 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 throttle_cmd)
|
||||
const float thrust_for_prowash)
|
||||
{
|
||||
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, _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);
|
||||
_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);
|
||||
|
||||
// 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
|
||||
@@ -393,11 +433,8 @@ 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);
|
||||
|
||||
@@ -406,17 +443,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_MAX * _u[1]);
|
||||
_ts[i].update_aero(v_ts, w_ts, altitude, _u[5]*TS_DEF_MAX, _T[1]);
|
||||
|
||||
} else {
|
||||
_ts[i].update_aero(v_ts, w_ts, altitude, -_u[4]*TS_DEF_MAX, _T_MAX * _u[0]);
|
||||
_ts[i].update_aero(v_ts, w_ts, altitude, -_u[4]*TS_DEF_MAX, _T[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
|
||||
}
|
||||
@@ -842,15 +879,21 @@ 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");
|
||||
@@ -872,6 +915,8 @@ 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;
|
||||
|
||||
@@ -1,6 +1,6 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2019-2025 PX4 Development Team. All rights reserved.
|
||||
* Copyright (c) 2019-2026 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
@@ -40,19 +40,19 @@
|
||||
* Coriolis g Corporation - January 2019
|
||||
*/
|
||||
|
||||
// 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 Runge–Kutta–Munthe-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.
|
||||
|
||||
/** 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 Runge–Kutta–Munthe-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.
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
#include <px4_platform_common/module.h>
|
||||
@@ -142,6 +142,7 @@ 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;
|
||||
@@ -190,7 +191,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);
|
||||
void generate_fw_aerodynamics(const float roll_cmd, const float pitch_cmd, const float yaw_cmd, const float thrust_for_prowash);
|
||||
void generate_ts_aerodynamics();
|
||||
void generate_rover_ackermann_dynamics(const float throttle_cmd, const float steering_cmd, const float dt);
|
||||
void sensor_step();
|
||||
@@ -234,6 +235,7 @@ 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]
|
||||
@@ -257,6 +259,9 @@ 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;
|
||||
@@ -296,7 +301,7 @@ private:
|
||||
// parameters
|
||||
MapProjection _lpos_ref{};
|
||||
float _lpos_ref_alt;
|
||||
float _MASS, _T_MAX, _Q_MAX, _L_ROLL, _L_PITCH, _KDV, _KDW, _T_TAU;
|
||||
float _MASS, _T_MAX, _Q_MAX, _L_ROLL, _L_PITCH, _KDV, _KDW, _T_TAU, _F_T_MAX, _F_Q_MAX;
|
||||
matrix::Matrix3f _I; // vehicle inertia matrix
|
||||
matrix::Matrix3f _Im1; // inverse of the inertia matrix
|
||||
|
||||
@@ -326,6 +331,18 @@ 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,12 +83,14 @@ parameters:
|
||||
increment: 0.005
|
||||
SIH_T_MAX:
|
||||
description:
|
||||
short: Max propeller thrust force
|
||||
short: Max multicopter 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
|
||||
@@ -97,12 +99,14 @@ parameters:
|
||||
increment: 0.5
|
||||
SIH_Q_MAX:
|
||||
description:
|
||||
short: Max propeller torque
|
||||
short: Max multicopter 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
|
||||
@@ -281,3 +285,87 @@ 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
|
||||
|
||||
@@ -81,7 +81,6 @@ static int do_import(const char *param_file_name = nullptr);
|
||||
static int do_show(const char *search_string, bool only_changed);
|
||||
static int do_show_for_airframe();
|
||||
static int do_show_all();
|
||||
static int do_show_locked();
|
||||
static int do_show_quiet(const char *param_name);
|
||||
static int do_show_index(const char *index, bool used_index);
|
||||
static void do_show_print(void *arg, param_t param);
|
||||
@@ -139,7 +138,6 @@ $ reboot
|
||||
PRINT_MODULE_USAGE_COMMAND_DESCR("show", "Show parameter values");
|
||||
PRINT_MODULE_USAGE_PARAM_FLAG('a', "Show all parameters (not just used)", true);
|
||||
PRINT_MODULE_USAGE_PARAM_FLAG('c', "Show only changed params (unused too)", true);
|
||||
PRINT_MODULE_USAGE_PARAM_FLAG('l', "Show only locked (read-only) params", true);
|
||||
PRINT_MODULE_USAGE_PARAM_FLAG('q', "quiet mode, print only param value (name needs to be exact)", true);
|
||||
PRINT_MODULE_USAGE_ARG("<filter>", "Filter by param name (wildcard at end allowed, eg. sys_*)", true);
|
||||
|
||||
@@ -181,8 +179,6 @@ $ reboot
|
||||
PRINT_MODULE_USAGE_ARG("<index>", "Index: an integer >= 0", false);
|
||||
PRINT_MODULE_USAGE_COMMAND_DESCR("find", "Show index of a param");
|
||||
PRINT_MODULE_USAGE_ARG("<param>", "param name", false);
|
||||
|
||||
PRINT_MODULE_USAGE_COMMAND_DESCR("lock", "Lock read-only params (reject future set/reset)");
|
||||
}
|
||||
|
||||
int
|
||||
@@ -272,9 +268,6 @@ param_main(int argc, char *argv[])
|
||||
} else if (!strcmp(argv[2], "-a")) {
|
||||
return do_show_all();
|
||||
|
||||
} else if (!strcmp(argv[2], "-l")) {
|
||||
return do_show_locked();
|
||||
|
||||
} else if (!strcmp(argv[2], "-q")) {
|
||||
if (argc >= 4) {
|
||||
return do_show_quiet(argv[3]);
|
||||
@@ -412,11 +405,6 @@ param_main(int argc, char *argv[])
|
||||
return 1;
|
||||
}
|
||||
}
|
||||
|
||||
if (!strcmp(argv[1], "lock")) {
|
||||
param_lock_readonly();
|
||||
return 0;
|
||||
}
|
||||
}
|
||||
|
||||
print_usage();
|
||||
@@ -520,7 +508,7 @@ do_save_default()
|
||||
static int
|
||||
do_show(const char *search_string, bool only_changed)
|
||||
{
|
||||
PX4_INFO_RAW("Symbols: x = used, + = saved, * = unsaved, l = locked\n");
|
||||
PX4_INFO_RAW("Symbols: x = used, + = saved, * = unsaved\n");
|
||||
// also show unused params if we show non-default values only
|
||||
param_foreach(do_show_print, (char *)search_string, only_changed, !only_changed);
|
||||
PX4_INFO_RAW("\n %u/%u parameters used.\n", param_count_used(), param_count());
|
||||
@@ -543,30 +531,13 @@ do_show_for_airframe()
|
||||
static int
|
||||
do_show_all()
|
||||
{
|
||||
PX4_INFO_RAW("Symbols: x = used, + = saved, * = unsaved, l = locked\n");
|
||||
PX4_INFO_RAW("Symbols: x = used, + = saved, * = unsaved\n");
|
||||
param_foreach(do_show_print, nullptr, false, false);
|
||||
PX4_INFO_RAW("\n %u parameters total, %u used.\n", param_count(), param_count_used());
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
static void
|
||||
do_show_print_locked(void *arg, param_t param)
|
||||
{
|
||||
if (param_is_readonly(param)) {
|
||||
do_show_print(arg, param);
|
||||
}
|
||||
}
|
||||
|
||||
static int
|
||||
do_show_locked()
|
||||
{
|
||||
PX4_INFO_RAW("Symbols: x = used, + = saved, * = unsaved, l = locked\n");
|
||||
param_foreach(do_show_print_locked, nullptr, false, false);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
static int
|
||||
do_show_quiet(const char *param_name)
|
||||
{
|
||||
@@ -636,9 +607,8 @@ do_show_index(const char *index, bool used_index)
|
||||
return 1;
|
||||
}
|
||||
|
||||
PX4_INFO_RAW("index %d: %c %c %c %s [%d,%d] : ", i, (param_used(param) ? 'x' : ' '),
|
||||
PX4_INFO_RAW("index %d: %c %c %s [%d,%d] : ", i, (param_used(param) ? 'x' : ' '),
|
||||
param_value_unsaved(param) ? '*' : (param_value_is_default(param) ? ' ' : '+'),
|
||||
param_is_readonly(param) ? 'l' : ' ',
|
||||
param_name(param), param_get_used_index(param), param_get_index(param));
|
||||
|
||||
switch (param_type(param)) {
|
||||
@@ -707,9 +677,8 @@ do_show_print(void *arg, param_t param)
|
||||
}
|
||||
}
|
||||
|
||||
PX4_INFO_RAW("%c %c %c %s [%d,%d] : ", (param_used(param) ? 'x' : ' '),
|
||||
PX4_INFO_RAW("%c %c %s [%d,%d] : ", (param_used(param) ? 'x' : ' '),
|
||||
param_value_unsaved(param) ? '*' : (param_value_is_default(param) ? ' ' : '+'),
|
||||
param_is_readonly(param) ? 'l' : ' ',
|
||||
param_name(param), param_get_used_index(param), param_get_index(param));
|
||||
|
||||
/*
|
||||
@@ -802,11 +771,6 @@ do_set(const char *name, const char *val, bool fail_on_not_found)
|
||||
return (fail_on_not_found) ? 1 : 0;
|
||||
}
|
||||
|
||||
if (param_is_readonly(param)) {
|
||||
PX4_ERR("Parameter %s is read-only.", name);
|
||||
return 1;
|
||||
}
|
||||
|
||||
/*
|
||||
* Set parameter if type is known and conversion from string to value turns out fine
|
||||
*/
|
||||
@@ -874,14 +838,6 @@ do_set_custom_default(const char *name, const char *val, bool silent_fail)
|
||||
return PX4_ERROR;
|
||||
}
|
||||
|
||||
if (param_is_readonly(param)) {
|
||||
if (!silent_fail) {
|
||||
PX4_ERR("Parameter %s is read-only.", name);
|
||||
}
|
||||
|
||||
return PX4_ERROR;
|
||||
}
|
||||
|
||||
// Set parameter if type is known and conversion from string to value turns out fine
|
||||
switch (param_type(param)) {
|
||||
case PARAM_TYPE_INT32: {
|
||||
|
||||
Reference in New Issue
Block a user