mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-06-15 15:31:30 +08:00
Compare commits
2 Commits
mrpollo/me
...
mrpollo/re
| Author | SHA1 | Date | |
|---|---|---|---|
|
|
55168855e6 | ||
|
|
05b018c185 |
8
.github/workflows/build_all_targets.yml
vendored
8
.github/workflows/build_all_targets.yml
vendored
@ -54,13 +54,7 @@ jobs:
|
||||
run: echo "::set-output name=timestamp::$(date +"%Y%m%d%H%M%S")"
|
||||
|
||||
- id: set-branch
|
||||
run: |
|
||||
echo "branchname=${{
|
||||
github.event_name == 'pull_request' &&
|
||||
format('pr-{0}', github.event.pull_request.number) ||
|
||||
github.head_ref ||
|
||||
github.ref_name
|
||||
}}" >> $GITHUB_OUTPUT
|
||||
run: echo "::set-output name=branchname::${GITHUB_HEAD_REF:-${GITHUB_REF#refs/heads/}}"
|
||||
|
||||
- name: Debug Matrix Output
|
||||
if: runner.debug == '1'
|
||||
|
||||
47
.github/workflows/docs_metadata_check.yml
vendored
47
.github/workflows/docs_metadata_check.yml
vendored
@ -1,47 +0,0 @@
|
||||
name: Docs Metadata
|
||||
|
||||
permissions:
|
||||
contents: write
|
||||
|
||||
on:
|
||||
pull_request: {}
|
||||
|
||||
jobs:
|
||||
metadata-check:
|
||||
name: ${{ matrix.name }}
|
||||
runs-on: [runs-on,runner=2cpu-linux-x64,image=ubuntu24-full-x64,"run-id=${{ github.run_id }}",spot=true]
|
||||
container:
|
||||
image: ghcr.io/px4/px4-dev:v1.16.0-ondemand
|
||||
strategy:
|
||||
fail-fast: false
|
||||
matrix:
|
||||
include:
|
||||
- name: uORB Graphs
|
||||
script: Tools/ci/metadata_uorb_graph.sh
|
||||
- name: Failsafe Web
|
||||
script: Tools/ci/metadata_failsafe_web.sh --debug
|
||||
- name: uORB Messages
|
||||
script: Tools/ci/metadata_msg_docs.sh
|
||||
- name: Parameter Reference
|
||||
script: Tools/ci/metadata_parameters.sh
|
||||
- name: Airframe Reference
|
||||
script: Tools/ci/metadata_airframe.sh
|
||||
- name: Module Reference
|
||||
script: Tools/ci/metadata_modules.sh
|
||||
steps:
|
||||
- name: Checkout repository
|
||||
uses: actions/checkout@v4
|
||||
with:
|
||||
ref: ${{ github.event.pull_request.head.sha }}
|
||||
fetch-depth: 0
|
||||
persist-credentials: true
|
||||
|
||||
- name: Mark all directories safe for Git
|
||||
run: git config --system --add safe.directory '*'
|
||||
|
||||
- name: Run ${{ matrix.name }} metadata check
|
||||
run: ${{ matrix.script }} --test-only
|
||||
|
||||
- name: Setup tmate session
|
||||
if: ${{ failure() }}
|
||||
uses: mxschmitt/action-tmate@v3
|
||||
3
.gitignore
vendored
3
.gitignore
vendored
@ -109,6 +109,3 @@ src/systemcmds/topic_listener/listener_generated.cpp
|
||||
# colcon
|
||||
log/
|
||||
keys/
|
||||
|
||||
# metadata dependencies
|
||||
_emscripten_sdk/
|
||||
|
||||
5
Makefile
5
Makefile
@ -379,10 +379,7 @@ module_documentation:
|
||||
extract_events:
|
||||
@$(MAKE) --no-print-directory px4_sitl_default metadata_extract_events ver_gen
|
||||
|
||||
msg_docs:
|
||||
@$(MAKE) --no-print-directory px4_sitl_default metadata_msg_documentation ver_gen
|
||||
|
||||
px4_metadata: parameters_metadata airframe_metadata module_documentation extract_events msg_docs
|
||||
px4_metadata: parameters_metadata airframe_metadata module_documentation extract_events
|
||||
|
||||
doxygen:
|
||||
@mkdir -p "$(SRC_DIR)"/build/doxygen
|
||||
|
||||
@ -1,47 +0,0 @@
|
||||
#!/bin/sh
|
||||
#
|
||||
# @name HexarotorX SITL for SIH
|
||||
#
|
||||
# @type Hexarotor x
|
||||
# @class Copter
|
||||
#
|
||||
# @maintainer Matthias Grob <maetugr@gmail.com>
|
||||
#
|
||||
|
||||
. ${R}etc/init.d/rc.mc_defaults
|
||||
|
||||
PX4_SIMULATOR=${PX4_SIMULATOR:=sihsim}
|
||||
PX4_SIM_MODEL=${PX4_SIM_MODEL:=hex}
|
||||
|
||||
param set-default SENS_EN_GPSSIM 1
|
||||
param set-default SENS_EN_BAROSIM 1
|
||||
param set-default SENS_EN_MAGSIM 1
|
||||
|
||||
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 PWM_MAIN_FUNC1 101
|
||||
param set-default PWM_MAIN_FUNC2 102
|
||||
param set-default PWM_MAIN_FUNC3 103
|
||||
param set-default PWM_MAIN_FUNC4 104
|
||||
param set-default PWM_MAIN_FUNC5 105
|
||||
param set-default PWM_MAIN_FUNC6 106
|
||||
|
||||
param set-default EKF2_GPS_DELAY 0
|
||||
@ -109,7 +109,6 @@ px4_add_romfs_files(
|
||||
10041_sihsim_airplane
|
||||
10042_sihsim_xvert
|
||||
10043_sihsim_standard_vtol
|
||||
10044_sihsim_hex
|
||||
|
||||
17001_flightgear_tf-g1
|
||||
17002_flightgear_tf-g2
|
||||
|
||||
@ -295,15 +295,10 @@ then
|
||||
# for multi intances setup, add namespace prefix
|
||||
uxrce_dds_ns="-n px4_$px4_instance"
|
||||
fi
|
||||
if [ "${PX4_UXRCE_DDS_NS+x}" ]; then
|
||||
# Override, as variable is set (empty or not)
|
||||
if [ -n "$PX4_UXRCE_DDS_NS" ]; then
|
||||
# Override namespace if environment variable is non-empty
|
||||
uxrce_dds_ns="-n $PX4_UXRCE_DDS_NS"
|
||||
else
|
||||
# Clear namespace if variable is empty
|
||||
uxrce_dds_ns=""
|
||||
fi
|
||||
if [ -n "$PX4_UXRCE_DDS_NS" ]
|
||||
then
|
||||
# Override namespace if environment variable is defined
|
||||
uxrce_dds_ns="-n $PX4_UXRCE_DDS_NS"
|
||||
fi
|
||||
if [ -n "$ROS_DOMAIN_ID" ]
|
||||
then
|
||||
|
||||
@ -15,8 +15,7 @@ control_allocator start
|
||||
#
|
||||
fw_rate_control start
|
||||
fw_att_control start
|
||||
fw_mode_manager start
|
||||
fw_lat_lon_control start
|
||||
fw_pos_control start
|
||||
airspeed_selector start
|
||||
|
||||
#
|
||||
|
||||
@ -13,6 +13,8 @@ param set-default MAV_TYPE 1
|
||||
#
|
||||
# Default parameters for fixed wing UAVs.
|
||||
#
|
||||
# there is a 2.5 factor applied on the _FS thresholds if for invalidation
|
||||
param set-default COM_POS_FS_EPH 50
|
||||
param set-default COM_VEL_FS_EVH 3
|
||||
|
||||
param set-default COM_POS_LOW_EPH 50
|
||||
|
||||
@ -20,5 +20,7 @@ param set-default NAV_ACC_RAD 2
|
||||
param set-default RTL_RETURN_ALT 30
|
||||
param set-default RTL_DESCEND_ALT 10
|
||||
|
||||
param set-default GPS_UBX_DYNMODEL 6
|
||||
|
||||
# lower RNG_FOG since MC are expected to fly closer over obstacles
|
||||
param set-default EKF2_RNG_FOG 1.0
|
||||
|
||||
@ -27,8 +27,7 @@ fi
|
||||
|
||||
fw_rate_control start vtol
|
||||
fw_att_control start vtol
|
||||
fw_mode_manager start
|
||||
fw_lat_lon_control start vtol
|
||||
fw_pos_control start vtol
|
||||
fw_autotune_attitude_control start vtol
|
||||
|
||||
# Start Land Detector
|
||||
|
||||
@ -10,6 +10,9 @@ set VEHICLE_TYPE vtol
|
||||
# MAV_TYPE_VTOL_FIXEDROTOR 22
|
||||
param set-default MAV_TYPE 22
|
||||
|
||||
# there is a 2.5 factor applied on COM_POS_FS_EPH if for invalidation
|
||||
param set-default COM_POS_FS_EPH 50
|
||||
|
||||
param set-default COM_POS_LOW_EPH 50
|
||||
|
||||
param set-default MIS_TAKEOFF_ALT 20
|
||||
|
||||
@ -39,7 +39,7 @@ set VEHICLE_TYPE none
|
||||
# Airframe parameter versioning
|
||||
# Value set to 1 by default but can optionally be overridden in the airframe configuration startup script.
|
||||
# Airframe maintainers can ensure a reset to the airframe defaults during an update by increasing by one.
|
||||
# e.g. add line "set PARAM_DEFAULTS_VER 2" in your airframe file to build the first update that enforces a reset.
|
||||
# e.g. add line "set PARAM_DEFAULTS_VER 2" in your airframe file to build the first update that enfoces a reset.
|
||||
set PARAM_DEFAULTS_VER 1
|
||||
|
||||
#
|
||||
|
||||
@ -27,9 +27,9 @@ do
|
||||
# - An old .msg version exists
|
||||
# - A translation header exists and is included
|
||||
|
||||
# Ignore changes to comments or constants and trim whitespace
|
||||
content_a=$(git show "${BASE_COMMIT}:${file}" | grep -o '^[^#]*' | grep -v = | sed 's/^ *//;s/[ \t]*$//')
|
||||
content_b=$(git show "${HEAD_COMMIT}:${file}" | grep -o '^[^#]*' | grep -v = | sed 's/^ *//;s/[ \t]*$//')
|
||||
# Ignore changes to comments or constants
|
||||
content_a=$(git show "${BASE_COMMIT}:${file}" | grep -o '^[^#]*' | grep -v =)
|
||||
content_b=$(git show "${HEAD_COMMIT}:${file}" | grep -o '^[^#]*' | grep -v =)
|
||||
if [ "${content_a}" == "${content_b}" ]; then
|
||||
echo "No version update required for ${file}"
|
||||
continue
|
||||
|
||||
@ -1,68 +0,0 @@
|
||||
#!/usr/bin/env bash
|
||||
#
|
||||
# metadata_airframe.sh — generate and sync PX4 airframe reference documentation
|
||||
#
|
||||
# Usage:
|
||||
# Tools/ci/metadata_airframe.sh [--test-only] [--debug]
|
||||
#
|
||||
# Options:
|
||||
# --test-only Run make target and comparison; exit 1 if diffs found, without copying file
|
||||
# --debug Show full make output and debug info for comparison
|
||||
#
|
||||
set -euo pipefail
|
||||
shopt -s nullglob
|
||||
|
||||
# Parse flags
|
||||
test_only=false
|
||||
debug=false
|
||||
while [[ $# -gt 0 ]]; do
|
||||
case "$1" in
|
||||
--test-only) test_only=true; shift ;;
|
||||
--debug) debug=true; shift ;;
|
||||
*) echo "Usage: $0 [--test-only] [--debug]"; exit 2 ;;
|
||||
esac
|
||||
done
|
||||
|
||||
# Paths and make target
|
||||
make_target="airframe_metadata"
|
||||
src_file="build/px4_sitl_default/docs/airframes.md"
|
||||
dest_file="docs/en/airframes/airframe_reference.md"
|
||||
|
||||
# Run make target
|
||||
if [ "$debug" = true ]; then
|
||||
echo "🔧 Running 'make $make_target' (verbose)"
|
||||
make $make_target
|
||||
else
|
||||
echo "🔧 Running 'make $make_target'"
|
||||
make $make_target > /dev/null 2>&1
|
||||
fi
|
||||
|
||||
# Verify build output
|
||||
if [[ ! -f "$src_file" ]]; then
|
||||
echo "❌ Generated file not found: $src_file"
|
||||
exit 1
|
||||
fi
|
||||
|
||||
echo "🔍 Comparing airframe reference docs"
|
||||
|
||||
# Compare files
|
||||
if cmp -s "$src_file" "$dest_file"; then
|
||||
echo "✅ Airframe reference is up to date."
|
||||
exit 0
|
||||
else
|
||||
if [ "$debug" = true ]; then
|
||||
echo "DEBUG: cmp -s '$src_file' '$dest_file'; echo \$?"
|
||||
fi
|
||||
echo "⚠️ Airframe reference needs updating."
|
||||
if [ "$test_only" = true ]; then
|
||||
exit 1
|
||||
fi
|
||||
# Copy over updated file
|
||||
echo "📂 Copying updated airframe_reference.md"
|
||||
cp -v "$src_file" "$dest_file"
|
||||
echo "🚨 Airframe docs updated; commit the change:"
|
||||
echo " git status -s $dest_file"
|
||||
echo " git add $dest_file"
|
||||
echo " git commit -m 'docs: update airframe reference metadata'"
|
||||
exit 1
|
||||
fi
|
||||
@ -1,112 +0,0 @@
|
||||
#!/usr/bin/env bash
|
||||
#
|
||||
# metadata_failsafe_web.sh — build and sync failsafe webapp metadata files
|
||||
#
|
||||
# Usage:
|
||||
# Tools/ci/metadata_failsafe_web.sh [--test-only] [--debug]
|
||||
#
|
||||
# Options:
|
||||
# --test-only Run build and comparison; exit 1 if diffs found, without copying files
|
||||
# --debug Show full build output and debug info for file comparisons and EMSDK install
|
||||
#
|
||||
set -euo pipefail
|
||||
shopt -s nullglob
|
||||
|
||||
# Parse flags
|
||||
test_only=false
|
||||
debug=false
|
||||
while [[ $# -gt 0 ]]; do
|
||||
case "$1" in
|
||||
--test-only) test_only=true; shift ;;
|
||||
--debug) debug=true; shift ;;
|
||||
*) echo "Usage: $0 [--test-only] [--debug]"; exit 2 ;;
|
||||
esac
|
||||
done
|
||||
|
||||
# Paths and commands
|
||||
build_cmd="make failsafe_web"
|
||||
src_dir="build/px4_sitl_default_failsafe_web"
|
||||
dest_dir="docs/public/config/failsafe"
|
||||
|
||||
# Ensure Emscripten SDK is available
|
||||
if ! command -v emcc >/dev/null 2>&1; then
|
||||
echo "🔧 Emscripten not found. Ensuring EMSDK is installed."
|
||||
# Clone SDK only if not already present
|
||||
if [ ! -d "_emscripten_sdk" ]; then
|
||||
if [ "$debug" = true ]; then
|
||||
git clone https://github.com/emscripten-core/emsdk.git _emscripten_sdk
|
||||
else
|
||||
git clone https://github.com/emscripten-core/emsdk.git _emscripten_sdk > /dev/null 2>&1
|
||||
fi
|
||||
fi
|
||||
pushd _emscripten_sdk >/dev/null
|
||||
if [ "$debug" = true ]; then
|
||||
./emsdk install latest
|
||||
./emsdk activate latest
|
||||
else
|
||||
./emsdk install latest > /dev/null 2>&1
|
||||
./emsdk activate latest > /dev/null 2>&1
|
||||
fi
|
||||
popd >/dev/null
|
||||
# Load environment into current shell
|
||||
if [ "$debug" = true ]; then
|
||||
# shellcheck source=/dev/null
|
||||
. ./_emscripten_sdk/emsdk_env.sh
|
||||
else
|
||||
# shellcheck source=/dev/null
|
||||
. ./_emscripten_sdk/emsdk_env.sh > /dev/null 2>&1
|
||||
fi
|
||||
fi
|
||||
|
||||
# Build step
|
||||
if [ "$debug" = true ]; then
|
||||
echo "🔧 Running build: $build_cmd"
|
||||
$build_cmd
|
||||
else
|
||||
echo "🔧 Running build"
|
||||
$build_cmd > /dev/null 2>&1
|
||||
fi
|
||||
|
||||
# Gather built files
|
||||
src_files=("$src_dir"/*.{js,wasm,json})
|
||||
if [ ${#src_files[@]} -eq 0 ]; then
|
||||
echo "❌ No generated files found in $src_dir. Build failed or path wrong."
|
||||
exit 1
|
||||
fi
|
||||
|
||||
# Prepare destination
|
||||
echo "🔍 Checking failsafe web metadata"
|
||||
mkdir -p "$dest_dir"
|
||||
|
||||
changed=()
|
||||
for src in "${src_files[@]}"; do
|
||||
name=$(basename "$src")
|
||||
dst="$dest_dir/$name"
|
||||
|
||||
if [[ ! -f "$dst" ]]; then
|
||||
[ "$debug" = true ] && echo "DEBUG: missing $dst"
|
||||
changed+=("$name")
|
||||
elif ! cmp -s "$src" "$dst"; then
|
||||
[ "$debug" = true ] && echo "DEBUG: cmp -s '$src' '$dst'; echo \$?"
|
||||
changed+=("$name")
|
||||
fi
|
||||
done
|
||||
|
||||
if [ ${#changed[@]} -eq 0 ]; then
|
||||
echo "✅ All failsafe web metadata files are in sync."
|
||||
exit 0
|
||||
fi
|
||||
|
||||
echo "⚠️ Detected updates in:"
|
||||
for f in "${changed[@]}"; do echo " - $f"; done
|
||||
|
||||
if [ "$test_only" = true ]; then
|
||||
echo "🚨 Failsafe web metadata needs update; rerun without --test-only to apply."
|
||||
exit 1
|
||||
fi
|
||||
|
||||
echo "📂 Copying updated files"
|
||||
for f in "${changed[@]}"; do cp -v "$src_dir/$f" "$dest_dir/$f"; done
|
||||
|
||||
echo "🚨 Failsafe web metadata updated; please commit changes."
|
||||
exit 1
|
||||
@ -1,99 +0,0 @@
|
||||
#!/usr/bin/env bash
|
||||
#
|
||||
# metadata_modules.sh - generate and sync PX4 module reference documentation
|
||||
#
|
||||
# Usage:
|
||||
# Tools/ci/metadata_modules.sh [--test-only] [--debug]
|
||||
#
|
||||
# Options:
|
||||
# --test-only Run make target and comparison; exit 1 if diffs found, without copying files
|
||||
# --debug Show full make output and debug info for file comparisons
|
||||
#
|
||||
set -euo pipefail
|
||||
shopt -s nullglob
|
||||
|
||||
# Parse flags
|
||||
test_only=false
|
||||
debug=false
|
||||
while [[ $# -gt 0 ]]; do
|
||||
case "$1" in
|
||||
--test-only) test_only=true; shift ;;
|
||||
--debug) debug=true; shift ;;
|
||||
*) echo "Usage: $0 [--test-only] [--debug]"; exit 2 ;;
|
||||
esac
|
||||
done
|
||||
|
||||
# Paths and make target
|
||||
make_target="module_documentation"
|
||||
src_dir="build/px4_sitl_default/docs/modules"
|
||||
dest_dir="docs/en/modules"
|
||||
|
||||
# Run make target
|
||||
if [ "$debug" = true ]; then
|
||||
echo "🔧 Running 'make $make_target' (verbose)"
|
||||
make $make_target
|
||||
else
|
||||
echo "🔧 Running 'make $make_target'"
|
||||
make $make_target > /dev/null 2>&1
|
||||
fi
|
||||
|
||||
# Verify build output
|
||||
src_files=("$src_dir"/*)
|
||||
if [ ${#src_files[@]} -eq 0 ]; then
|
||||
echo "❌ No generated module docs found in $src_dir. Build failed or path wrong."
|
||||
exit 1
|
||||
fi
|
||||
|
||||
# ─── Strip trailing whitespace from all generated module docs (unless test-only) ─────────────
|
||||
if [ "$test_only" = false ]; then
|
||||
echo "✂️ Removing trailing whitespace from generated module docs"
|
||||
for src in "${src_files[@]}"; do
|
||||
sed -i 's/[[:space:]]\+$//' "$src"
|
||||
done
|
||||
else
|
||||
[ "$debug" = true ] && echo "🧪 Test-only mode: skipping whitespace removal"
|
||||
fi
|
||||
|
||||
echo "🔍 Checking module reference docs in $dest_dir"
|
||||
mkdir -p "$dest_dir"
|
||||
|
||||
changed=()
|
||||
for src in "${src_files[@]}"; do
|
||||
name=$(basename "$src")
|
||||
dst="$dest_dir/$name"
|
||||
|
||||
if [[ ! -e "$dst" ]]; then
|
||||
[ "$debug" = true ] && echo "DEBUG: missing $dst"
|
||||
changed+=("$name")
|
||||
else
|
||||
# Use diff -q -b (ignore whitespace changes) and --strip-trailing-cr (ignore CRLF vs LF)
|
||||
if ! diff -q -b --strip-trailing-cr "$src" "$dst" > /dev/null; then
|
||||
[ "$debug" = true ] && echo "DEBUG: diff -q -b --strip-trailing-cr '$src' '$dst' (exit_code=$?)"
|
||||
changed+=("$name")
|
||||
fi
|
||||
fi
|
||||
done
|
||||
|
||||
if [ ${#changed[@]} -eq 0 ]; then
|
||||
echo "✅ All module reference docs are up to date."
|
||||
exit 0
|
||||
fi
|
||||
|
||||
echo "⚠️ Detected updates in module docs:"
|
||||
for f in "${changed[@]}"; do echo " - $f"; done
|
||||
|
||||
if [ "$test_only" = true ]; then
|
||||
echo "🚨 Module reference docs need updating; rerun without --test-only to apply."
|
||||
exit 1
|
||||
fi
|
||||
|
||||
echo "📂 Copying updated module docs to $dest_dir"
|
||||
for f in "${changed[@]}"; do
|
||||
cp -rv "$src_dir/$f" "$dest_dir/$f"
|
||||
done
|
||||
|
||||
echo "🚨 Module reference docs updated; please commit changes:"
|
||||
echo " git status -s $dest_dir"
|
||||
echo " git add $dest_dir/*"
|
||||
echo " git commit -m 'docs: update module reference metadata'"
|
||||
exit 1
|
||||
@ -1,97 +0,0 @@
|
||||
#!/usr/bin/env bash
|
||||
#
|
||||
# metadata_msg_docs.sh — generate and sync uORB message reference documentation
|
||||
#
|
||||
# Usage:
|
||||
# Tools/ci/metadata_msg_docs.sh [--test-only] [--debug]
|
||||
#
|
||||
# Options:
|
||||
# --test-only Run make target and comparison; exit 1 if diffs found, without copying files
|
||||
# --debug Show full make output and debug info for file comparisons
|
||||
#
|
||||
set -euo pipefail
|
||||
shopt -s nullglob
|
||||
|
||||
# Parse flags
|
||||
test_only=false
|
||||
debug=false
|
||||
while [[ $# -gt 0 ]]; do
|
||||
case "$1" in
|
||||
--test-only) test_only=true; shift ;;
|
||||
--debug) debug=true; shift ;;
|
||||
*) echo "Usage: $0 [--test-only] [--debug]"; exit 2 ;;
|
||||
esac
|
||||
done
|
||||
|
||||
# Paths and make target
|
||||
make_target="msg_docs"
|
||||
src_dir="build/px4_sitl_default/msg_docs"
|
||||
dest_dir="docs/en/msg_docs"
|
||||
middleware_dir="docs/en/middleware"
|
||||
|
||||
# Run make target
|
||||
if [ "$debug" = true ]; then
|
||||
echo "🔧 Running 'make $make_target' (verbose)"
|
||||
make $make_target
|
||||
else
|
||||
echo "🔧 Running 'make $make_target'"
|
||||
make $make_target > /dev/null 2>&1
|
||||
fi
|
||||
|
||||
# Verify build output
|
||||
src_files=("$src_dir"/*)
|
||||
if [ ${#src_files[@]} -eq 0 ]; then
|
||||
echo "❌ No files found in $src_dir. Build target '$make_target' failed or path is wrong."
|
||||
exit 1
|
||||
fi
|
||||
|
||||
echo "🔍 Checking uORB message docs in $dest_dir"
|
||||
mkdir -p "$dest_dir"
|
||||
|
||||
changed=()
|
||||
for src in "${src_files[@]}"; do
|
||||
name=$(basename "$src")
|
||||
|
||||
# special-case dds_topics.md
|
||||
if [[ "$name" == "dds_topics.md" ]]; then
|
||||
dst="$middleware_dir/$name"
|
||||
else
|
||||
dst="$dest_dir/$name"
|
||||
fi
|
||||
|
||||
if [[ ! -f "$dst" ]]; then
|
||||
[ "$debug" = true ] && echo "DEBUG: missing $dst"
|
||||
changed+=("$name")
|
||||
elif ! cmp -s "$src" "$dst"; then
|
||||
[ "$debug" = true ] && echo "DEBUG: cmp -s '$src' '$dst'; echo \$?"
|
||||
changed+=("$name")
|
||||
fi
|
||||
done
|
||||
|
||||
if [ ${#changed[@]} -eq 0 ]; then
|
||||
echo "✅ All uORB message docs are up to date."
|
||||
exit 0
|
||||
fi
|
||||
|
||||
echo "⚠️ Detected updates in the following docs:"
|
||||
for f in "${changed[@]}"; do echo " - $f"; done
|
||||
|
||||
if [ "$test_only" = true ]; then
|
||||
echo "🚨 uORB message docs need updating! Rerun without --test-only to apply changes."
|
||||
exit 1
|
||||
fi
|
||||
|
||||
echo "📂 Copying updated doc files to $dest_dir"
|
||||
for f in "${changed[@]}"; do
|
||||
if [[ "$f" == "dds_topics.md" ]]; then
|
||||
cp -v "$src_dir/$f" "$middleware_dir/$f"
|
||||
else
|
||||
cp -v "$src_dir/$f" "$dest_dir/$f"
|
||||
fi
|
||||
done
|
||||
|
||||
echo "🚨 uORB message docs updated; please commit changes:"
|
||||
echo " git status -s $dest_dir"
|
||||
echo " git add $dest_dir/*"
|
||||
echo " git commit -m 'docs: update uORB message reference docs'"
|
||||
exit 1
|
||||
@ -1,71 +0,0 @@
|
||||
#!/usr/bin/env bash
|
||||
#
|
||||
# metadata_parameters.sh — generate and sync PX4 parameter reference documentation
|
||||
#
|
||||
# Usage:
|
||||
# Tools/ci/metadata_parameters.sh [--test-only] [--debug]
|
||||
#
|
||||
# Options:
|
||||
# --test-only Run make target and comparison; exit 1 if diffs found, without copying file
|
||||
# --debug Show full make output and debug info for comparison
|
||||
#
|
||||
set -euo pipefail
|
||||
|
||||
# Parse flags
|
||||
test_only=false
|
||||
debug=false
|
||||
while [[ $# -gt 0 ]]; do
|
||||
case "$1" in
|
||||
--test-only) test_only=true; shift ;;
|
||||
--debug) debug=true; shift ;;
|
||||
*) echo "Usage: $0 [--test-only] [--debug]"; exit 2 ;;
|
||||
esac
|
||||
done
|
||||
|
||||
# Paths and make target
|
||||
make_target="parameters_metadata"
|
||||
src_file="build/px4_sitl_default/docs/parameters.md"
|
||||
dest_file="docs/en/advanced_config/parameter_reference.md"
|
||||
|
||||
# Run make target
|
||||
if [ "$debug" = true ]; then
|
||||
echo "🔧 Running 'make $make_target' (verbose)"
|
||||
make $make_target
|
||||
else
|
||||
echo "🔧 Running 'make $make_target'"
|
||||
make $make_target > /dev/null 2>&1
|
||||
fi
|
||||
|
||||
# ─── Strip trailing whitespace from the newly generated Markdown ────────────────────────────────
|
||||
echo "✂️ Removing trailing whitespace from $src_file"
|
||||
sed -i 's/[[:space:]]\+$//' "$src_file"
|
||||
|
||||
# Verify build output
|
||||
if [[ ! -f "$src_file" ]]; then
|
||||
echo "❌ Generated file not found: $src_file"
|
||||
exit 1
|
||||
fi
|
||||
|
||||
echo "🔍 Comparing parameter docs"
|
||||
|
||||
# Compare files
|
||||
if cmp -s "$src_file" "$dest_file"; then
|
||||
echo "✅ Parameter reference is up to date."
|
||||
exit 0
|
||||
else
|
||||
if [ "$debug" = true ]; then
|
||||
echo "DEBUG: cmp -s '$src_file' '$dest_file'; echo \$?"
|
||||
fi
|
||||
echo "⚠️ Parameter reference needs updating."
|
||||
if [ "$test_only" = true ]; then
|
||||
exit 1
|
||||
fi
|
||||
# Copy over updated file
|
||||
echo "📂 Copying updated parameter_reference.md"
|
||||
cp -v "$src_file" "$dest_file"
|
||||
echo "🚨 Parameter docs updated; commit the change:"
|
||||
echo " git status -s $dest_file"
|
||||
echo " git add $dest_file"
|
||||
echo " git commit -m 'docs: update parameter reference metadata'"
|
||||
exit 1
|
||||
fi
|
||||
@ -1,108 +0,0 @@
|
||||
#!/usr/bin/env bash
|
||||
#
|
||||
# update_uorb_graphs.sh — generate, compare, and sync uORB graph JSONs
|
||||
#
|
||||
# Usage:
|
||||
# ./scripts/update_uorb_graphs.sh [--test-only] [--debug]
|
||||
#
|
||||
# Options:
|
||||
# --test-only Run generation and comparison only; exit 1 if diffs found, without copying files
|
||||
# --debug Echo debug info for missing or differing files and show full make output
|
||||
#
|
||||
# Examples:
|
||||
# # CI mode: fail if docs need updates
|
||||
# ./scripts/update_uorb_graphs.sh --test-only
|
||||
#
|
||||
# # Developer mode: regenerate and sync JSONs
|
||||
# ./scripts/update_uorb_graphs.sh
|
||||
#
|
||||
set -euo pipefail
|
||||
|
||||
shopt -s nullglob
|
||||
|
||||
# Parse flags
|
||||
test_only=false
|
||||
debug=false
|
||||
while [[ $# -gt 0 ]]; do
|
||||
case "$1" in
|
||||
--test-only)
|
||||
test_only=true
|
||||
shift
|
||||
;;
|
||||
--debug)
|
||||
debug=true
|
||||
shift
|
||||
;;
|
||||
*)
|
||||
echo "Usage: $0 [--test-only] [--debug]"
|
||||
exit 2
|
||||
;;
|
||||
esac
|
||||
done
|
||||
|
||||
# Paths
|
||||
graph_dir="Tools/uorb_graph"
|
||||
dest_dir="docs/public/middleware"
|
||||
|
||||
# Generate uORB graphs (conditionally silent)
|
||||
if [ "$debug" = true ]; then
|
||||
echo "🔧 Generating uORB message graphs (verbose output)"
|
||||
make uorb_graphs
|
||||
else
|
||||
echo "🔧 Generating uORB message graphs"
|
||||
make uorb_graphs > /dev/null 2>&1
|
||||
fi
|
||||
|
||||
# Verify generation
|
||||
src_files=("$graph_dir"/*.json)
|
||||
if [ ${#src_files[@]} -eq 0 ]; then
|
||||
echo "❌ No JSON files found in $graph_dir. Generation failed or path is wrong."
|
||||
exit 1
|
||||
fi
|
||||
|
||||
echo "🔍 Checking for updated uORB graph JSONs"
|
||||
mkdir -p "$dest_dir"
|
||||
|
||||
changed=()
|
||||
for src in "${src_files[@]}"; do
|
||||
name=$(basename "$src")
|
||||
dst="$dest_dir/$name"
|
||||
|
||||
if [[ ! -f "$dst" ]]; then
|
||||
[ "$debug" = true ] && echo "DEBUG: $dst missing"
|
||||
changed+=("$name")
|
||||
|
||||
elif ! cmp -s "$src" "$dst"; then
|
||||
[ "$debug" = true ] && echo "DEBUG: cmp -s '$src' '$dst'; echo \$?"
|
||||
changed+=("$name")
|
||||
fi
|
||||
done
|
||||
|
||||
if [ ${#changed[@]} -eq 0 ]; then
|
||||
echo "✅ All uORB graph JSONs are already in sync."
|
||||
exit 0
|
||||
fi
|
||||
|
||||
echo "⚠️ Detected updates in the following files:"
|
||||
for name in "${changed[@]}"; do
|
||||
echo " - $name"
|
||||
done
|
||||
|
||||
if [ "$test_only" = true ]; then
|
||||
echo
|
||||
echo "🚨 uORB graph docs need updating! Rerun without --test-only to apply changes."
|
||||
exit 1
|
||||
fi
|
||||
|
||||
echo
|
||||
echo "📂 Copying updated files over"
|
||||
for name in "${changed[@]}"; do
|
||||
cp -v "$graph_dir/$name" "$dest_dir/$name"
|
||||
done
|
||||
|
||||
echo
|
||||
echo "🚨 uORB graph docs need updating! Review above, then run:"
|
||||
echo " git status -s $dest_dir/"
|
||||
echo " git add $dest_dir/*.json"
|
||||
echo " git commit -m 'docs: metadata: update uORB graph JSONs'"
|
||||
exit 1
|
||||
@ -2,7 +2,19 @@
|
||||
|
||||
if [ -z ${PX4_DOCKER_REPO+x} ]; then
|
||||
echo "guessing PX4_DOCKER_REPO based on input";
|
||||
if [[ $@ =~ .*clang.* ]] || [[ $@ =~ .*scan-build.* ]]; then
|
||||
if [[ $@ =~ .*px4_fmu.* ]]; then
|
||||
# nuttx-px4fmu-v{1,2,3,4,5}
|
||||
PX4_DOCKER_REPO="px4io/px4-dev-nuttx-focal:2022-08-12"
|
||||
elif [[ $@ =~ .*navio2.* ]] || [[ $@ =~ .*raspberry.* ]] || [[ $@ =~ .*beaglebone.* ]] || [[ $@ =~ .*pilotpi.default ]] || [[ $@ =~ .*navigator.* ]]; then
|
||||
# beaglebone_blue_default, emlid_navio2_default, px4_raspberrypi_default, scumaker_pilotpi_default, bluerobotics_navigator_default
|
||||
PX4_DOCKER_REPO="px4io/px4-dev-armhf:2023-06-26"
|
||||
elif [[ $@ =~ .*pilotpi.arm64 ]]; then
|
||||
# scumaker_pilotpi_arm64
|
||||
PX4_DOCKER_REPO="px4io/px4-dev-aarch64:2022-08-12"
|
||||
elif [[ $@ =~ .*navio2.* ]] || [[ $@ =~ .*raspberry.* ]] || [[ $@ =~ .*bebop.* ]]; then
|
||||
# posix_rpi_cross, posix_bebop_default
|
||||
PX4_DOCKER_REPO="px4io/px4-dev-armhf:2023-06-26"
|
||||
elif [[ $@ =~ .*clang.* ]] || [[ $@ =~ .*scan-build.* ]]; then
|
||||
# clang tools
|
||||
PX4_DOCKER_REPO="px4io/px4-dev-clang:2021-02-04"
|
||||
elif [[ $@ =~ .*tests* ]]; then
|
||||
@ -15,9 +27,17 @@ fi
|
||||
|
||||
# otherwise default to nuttx
|
||||
if [ -z ${PX4_DOCKER_REPO+x} ]; then
|
||||
PX4_DOCKER_REPO="px4io/px4-dev:v1.16.0-ondemand"
|
||||
PX4_DOCKER_REPO="px4io/px4-dev-nuttx-focal:2022-08-12"
|
||||
fi
|
||||
|
||||
# docker hygiene
|
||||
|
||||
#Delete all stopped containers (including data-only containers)
|
||||
# docker container prune
|
||||
|
||||
#Delete all 'untagged/dangling' (<none>) images
|
||||
# docker image prune
|
||||
|
||||
echo "PX4_DOCKER_REPO: $PX4_DOCKER_REPO";
|
||||
|
||||
PWD=$( cd "$( dirname "${BASH_SOURCE[0]}" )" && pwd )
|
||||
|
||||
@ -2,7 +2,6 @@
|
||||
|
||||
"""
|
||||
Generate docs from .msg files
|
||||
Also generates docs/en/middleware/dds_topics.md from dds_topics.yaml
|
||||
"""
|
||||
|
||||
import os
|
||||
@ -10,109 +9,6 @@ import argparse
|
||||
import sys
|
||||
|
||||
|
||||
import yaml
|
||||
|
||||
def sort_dds_topics(topics):
|
||||
return sorted(
|
||||
topics,
|
||||
key=lambda pub: pub["type"].rsplit("::", 1)[-1]
|
||||
)
|
||||
|
||||
def generate_dds_yaml_doc(allMessageFiles, output_dir):
|
||||
"""
|
||||
Generates human readable version of dds_topics.yaml.
|
||||
Default output is to docs/en/middleware/dds_topics.md
|
||||
"""
|
||||
output_file = 'dds_topics.md'
|
||||
dds_markdown = ""
|
||||
if not os.path.isdir(output_dir):
|
||||
print("Output directory not found")
|
||||
sys.exit(1)
|
||||
|
||||
dds_file_path = os.path.join(os.path.dirname(os.path.realpath(__file__)),"../../src/modules/uxrce_dds_client/dds_topics.yaml")
|
||||
output_file_path = os.path.join(output_dir, output_file)
|
||||
|
||||
try:
|
||||
with open(dds_file_path, 'r') as file:
|
||||
data = yaml.safe_load(file)
|
||||
|
||||
# Get messages and topics that are not published by default
|
||||
# Start by getting all that are published.
|
||||
all_messages_in_source = set()
|
||||
all_message_types =set()
|
||||
all_topics =set()
|
||||
for message in data["publications"]:
|
||||
all_message_types.add(message['type'].split("::")[-1])
|
||||
all_topics.add(message['topic'].split('/')[-1])
|
||||
for message in data["subscriptions"]:
|
||||
all_message_types.add(message['type'].split("::")[-1])
|
||||
all_topics.add(message['topic'].split('/')[-1])
|
||||
if data["subscriptions_multi"]: # There is none now
|
||||
dds_markdown += "None\n"
|
||||
for message in data["subscriptions_multi"]:
|
||||
all_message_types.add(message['type'].split("::")[-1])
|
||||
all_topics.add(message['topic'].split('/')[-1])
|
||||
for message in allMessageFiles:
|
||||
all_messages_in_source.add(message.split('/')[-1].split('.')[0])
|
||||
messagesNotExported = sorted(all_messages_in_source - all_message_types)
|
||||
|
||||
# write out the dds file
|
||||
dds_markdown="""# dds_topics.yaml — PX4 Topics Exposed to ROS 2
|
||||
|
||||
::: info
|
||||
This document is [auto-generated](https://github.com/PX4/PX4-Autopilot/blob/main/Tools/msg/generate_msg_docs.py) from the source code.
|
||||
:::
|
||||
|
||||
|
||||
The [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml) file specifies which uORB message definitions are compiled into the [uxrce_dds_client](../modules/modules_system.md#uxrce-dds-client) module when [PX4 is built](../middleware/uxrce_dds.md#code-generation), and hence which topics are available for ROS 2 applications to subscribe or publish (by default).
|
||||
|
||||
This document shows a markdown-rendered version of [dds_topics.yaml](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/uxrce_dds_client/dds_topics.yaml), listing the publications, subscriptions, and so on.
|
||||
|
||||
## Publications
|
||||
|
||||
Topic | Type| Rate Limit
|
||||
--- | --- | ---
|
||||
"""
|
||||
|
||||
for message in sort_dds_topics(data["publications"]):
|
||||
type = message['type']
|
||||
px4Type=type.split("::")[-1]
|
||||
dds_markdown += f"`{message['topic']}` | [{type}](../msg_docs/{px4Type}.md) | {message.get('rate_limit','')}\n"
|
||||
|
||||
dds_markdown += "\n## Subscriptions\n\nTopic | Type\n--- | ---\n"
|
||||
|
||||
for message in sort_dds_topics(data["subscriptions"]):
|
||||
type = message['type']
|
||||
px4Type=type.split("::")[-1]
|
||||
dds_markdown += f"{message['topic']} | [{type}](../msg_docs/{px4Type}.md)\n"
|
||||
|
||||
dds_markdown += "\n## Subscriptions Multi\n\n"
|
||||
|
||||
if not data["subscriptions_multi"]: # There is none now
|
||||
dds_markdown += "None\n"
|
||||
else:
|
||||
print("Warning - we now have subscription_multi data - check format")
|
||||
dds_markdown += "Topic | Type\n--- | ---\n"
|
||||
for message in sort_dds_topics(data["subscriptions_multi"]):
|
||||
dds_markdown += f"{message['topic']} | {message['type']}\n"
|
||||
|
||||
if messagesNotExported:
|
||||
# Print the topics that are not exported to DDS
|
||||
dds_markdown += "\n## Not Exported\n\nThese messages are not listed in the yaml file.\nThey are not build into the module, and hence are neither published or subscribed."
|
||||
dds_markdown += "\n\n::: details See messages\n"
|
||||
for item in sorted(messagesNotExported):
|
||||
dds_markdown += f"\n- [{item}](../msg_docs/{item}.md)"
|
||||
dds_markdown += "\n:::\n" # End of details block
|
||||
|
||||
with open(output_file_path, 'w') as content_file:
|
||||
content_file.write(dds_markdown)
|
||||
|
||||
except yaml.YAMLError as exc:
|
||||
print(f"Error parsing YAML: {exc}")
|
||||
except FileNotFoundError:
|
||||
print(f"Error: {dds_file_path} not found.")
|
||||
|
||||
|
||||
def get_msgs_list(msgdir):
|
||||
"""
|
||||
Makes a list of relative paths of .msg files in the given directory
|
||||
@ -134,10 +30,8 @@ def get_msgs_list(msgdir):
|
||||
|
||||
|
||||
if __name__ == "__main__":
|
||||
|
||||
parser = argparse.ArgumentParser(description='Generate docs from .msg files')
|
||||
parser.add_argument('-d', dest='dir', help='output directory', required=True)
|
||||
parser.add_argument('--dds_topics', dest='dds_topics', help='Generate dds yaml doc', action='store_true')
|
||||
args = parser.parse_args()
|
||||
|
||||
output_dir = args.dir
|
||||
@ -148,9 +42,6 @@ if __name__ == "__main__":
|
||||
msg_files = get_msgs_list(msg_path)
|
||||
msg_files.sort()
|
||||
|
||||
if args.dds_topics:
|
||||
generate_dds_yaml_doc(msg_files, output_dir)
|
||||
|
||||
versioned_msgs_list = ''
|
||||
unversioned_msgs_list = ''
|
||||
|
||||
|
||||
@ -40,25 +40,25 @@ The generated files will be written to the `modules` directory.
|
||||
## Categories
|
||||
"""
|
||||
for category in sorted(module_groups):
|
||||
result += f"- [{category.capitalize()}](modules_{category}.md)\n"
|
||||
result += "- [%s](modules_%s.md)\n" % (category.capitalize(), category)
|
||||
|
||||
self._outputs['main'] = result
|
||||
|
||||
for category in sorted(module_groups):
|
||||
result = f"# Modules Reference: {category.capitalize()}\n\n"
|
||||
result = "# Modules Reference: %s\n" % category.capitalize()
|
||||
subcategories = module_groups[category]
|
||||
|
||||
if len(subcategories) > 1:
|
||||
result += 'Subcategories:\n\n'
|
||||
for subcategory in sorted(subcategories):
|
||||
result += 'Subcategories:\n'
|
||||
for subcategory in subcategories:
|
||||
if subcategory == '':
|
||||
continue
|
||||
subcategory_label = subcategory.replace('_', ' ').title()
|
||||
subcategory_file_name = category+'_'+subcategory
|
||||
result += f'- [{subcategory_label}](modules_{subcategory_file_name}.md)\n'
|
||||
result += '- [%s](modules_%s.md)\n' % (subcategory_label, subcategory_file_name)
|
||||
|
||||
# add a sub-page for the subcategory
|
||||
result_subpage = f'# Modules Reference: {subcategory_label} ({category.capitalize()})\n'
|
||||
result_subpage = '# Modules Reference: %s (%s)\n' % \
|
||||
(subcategory_label, category.capitalize())
|
||||
result_subpage += self._ProcessModules(subcategories[subcategory])
|
||||
self._outputs[subcategory_file_name] = result_subpage
|
||||
|
||||
@ -68,14 +68,14 @@ The generated files will be written to the `modules` directory.
|
||||
def _ProcessModules(self, module_list):
|
||||
result = ''
|
||||
for module in module_list:
|
||||
result += f"\n## {module.name()}\n\n"
|
||||
result += f"Source: [{module.scope()}](https://github.com/PX4/PX4-Autopilot/tree/main/src/{module.scope()})\n\n"
|
||||
result += "## %s\n" % module.name()
|
||||
result += "Source: [%s](https://github.com/PX4/PX4-Autopilot/tree/main/src/%s)\n\n" % (module.scope(), module.scope())
|
||||
doc = module.documentation()
|
||||
if len(doc) > 0:
|
||||
result += f"{doc}\n"
|
||||
result += "%s\n" % doc
|
||||
usage_string = module.usage_string()
|
||||
if len(usage_string) > 0:
|
||||
result += f'### Usage {{#{module.name()}_usage}}\n\n```\n{usage_string}\n```\n'
|
||||
result += '<a id="%s_usage"></a>\n### Usage\n```\n%s\n```\n' % (module.name(), usage_string)
|
||||
return result
|
||||
|
||||
def Save(self, dirname):
|
||||
|
||||
@ -12,11 +12,11 @@ class ModuleDocumentation(object):
|
||||
"""
|
||||
|
||||
# If you add categories or subcategories, they also need to be added to the
|
||||
# TOC in https://github.com/PX4/PX4-Autopilot/blob/main/docs/en/SUMMARY.md
|
||||
# TOC in https://github.com/PX4/PX4-user_guide/blob/main/en/SUMMARY.md
|
||||
valid_categories = ['driver', 'estimator', 'controller', 'system',
|
||||
'communication', 'command', 'template', 'simulation', 'autotune']
|
||||
valid_subcategories = ['', 'camera', 'distance_sensor', 'imu', 'ins', 'airspeed_sensor',
|
||||
'magnetometer', 'baro', 'optical_flow', 'radio_control','rpm_sensor', 'transponder']
|
||||
'magnetometer', 'baro', 'optical_flow', 'rpm_sensor', 'transponder']
|
||||
|
||||
max_line_length = 80 # wrap lines that are longer than this
|
||||
|
||||
|
||||
@ -59,7 +59,7 @@ def get_N_colors(N, s=0.8, v=0.9):
|
||||
def topic_filename(topic):
|
||||
MSG_PATH = 'msg/'
|
||||
|
||||
file_list = sorted(os.listdir(MSG_PATH))
|
||||
file_list = os.listdir(MSG_PATH)
|
||||
msg_files = [file.replace('.msg', '') for file in file_list if file.endswith(".msg")]
|
||||
|
||||
if topic in msg_files:
|
||||
@ -369,14 +369,12 @@ class Graph(object):
|
||||
if not scope.is_empty():
|
||||
scopes_with_topic[name] = scope
|
||||
|
||||
# scopes_with_topic = sorted(scopes_with_topic)
|
||||
|
||||
self._print_ambiguities = ambiguous_topics
|
||||
if use_topic_pubsub_union:
|
||||
self._print_topics = sorted(subscribed_topics | published_topics)
|
||||
self._print_topics = subscribed_topics | published_topics
|
||||
self._print_scopes = scopes_with_topic
|
||||
else:
|
||||
self._print_topics = sorted(subscribed_topics & published_topics)
|
||||
self._print_topics = subscribed_topics & published_topics
|
||||
|
||||
# cull scopes to only those that pub or sub to a topic that has both
|
||||
intersect_scopes = {}
|
||||
@ -394,7 +392,7 @@ class Graph(object):
|
||||
log.debug('ignoring excluded path '+path)
|
||||
return
|
||||
|
||||
entries = sorted(os.listdir(path))
|
||||
entries = os.listdir(path)
|
||||
|
||||
# check if entering a new scope
|
||||
cmake_file = 'CMakeLists.txt'
|
||||
@ -687,8 +685,8 @@ class OutputJSON(object):
|
||||
|
||||
|
||||
# edges
|
||||
for name,scope in sorted(output_scopes.items(), key=lambda kv: kv[0]):
|
||||
for topic in sorted(scope.publications):
|
||||
for name,scope in output_scopes.items():
|
||||
for topic in scope.publications:
|
||||
if topic in output_topics:
|
||||
edge = {}
|
||||
edge['source'] = 'm_'+name
|
||||
@ -697,8 +695,8 @@ class OutputJSON(object):
|
||||
edge['style'] = 'dashed'
|
||||
edges.append(edge)
|
||||
|
||||
for name,scope in sorted(output_scopes.items(), key=lambda kv: kv[0]):
|
||||
for topic in sorted(scope.subscriptions):
|
||||
for name,scope in output_scopes.items():
|
||||
for topic in scope.subscriptions:
|
||||
if topic in output_topics:
|
||||
edge = {}
|
||||
edge['source'] = 't_'+topic
|
||||
@ -725,16 +723,10 @@ if "__main__" == __name__:
|
||||
log.setLevel(logging.DEBUG)
|
||||
print("set log level to DEBUG")
|
||||
|
||||
|
||||
print('')
|
||||
print('== Starting uorb_graph/create.py ==')
|
||||
if args.file:
|
||||
print(' =Filename:', os.path.basename(args.file))
|
||||
|
||||
# ignore topics that are subscribed/published by many topics, but are not really
|
||||
# useful to show in the graph
|
||||
topic_blacklist = [ 'parameter_update', 'mavlink_log', 'log_message' ]
|
||||
print(' =Excluded Topics: '+str(topic_blacklist))
|
||||
print('Excluded topics: '+str(topic_blacklist))
|
||||
|
||||
if len(args.modules) == 0:
|
||||
scope_whitelist = []
|
||||
@ -765,7 +757,7 @@ if "__main__" == __name__:
|
||||
if 0 < len(args.exclude_path):
|
||||
path_blacklist = args.exclude_path
|
||||
if path_blacklist:
|
||||
print(' =Excluded Path: '+str(path_blacklist))
|
||||
print('Excluded Path: '+str(path_blacklist))
|
||||
|
||||
graph.build(source_paths, path_blacklist=path_blacklist, use_topic_pubsub_union=args.use_topic_union, merge_depends=args.merge_depends)
|
||||
|
||||
@ -792,6 +784,3 @@ if "__main__" == __name__:
|
||||
pass
|
||||
else:
|
||||
print('Error: unknown output format '+args.output)
|
||||
|
||||
print("== Completed uorb_graph/create.py ==")
|
||||
print("")
|
||||
|
||||
@ -10,7 +10,6 @@ CONFIG_DRIVERS_BAROMETER_DPS310=y
|
||||
CONFIG_DRIVERS_BATT_SMBUS=y
|
||||
CONFIG_DRIVERS_CAMERA_CAPTURE=y
|
||||
CONFIG_DRIVERS_CAMERA_TRIGGER=y
|
||||
CONFIG_DRIVERS_CDCACM_AUTOSTART=y
|
||||
CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y
|
||||
CONFIG_COMMON_DISTANCE_SENSOR=y
|
||||
CONFIG_DRIVERS_DSHOT=y
|
||||
@ -42,8 +41,7 @@ CONFIG_MODULES_EVENTS=y
|
||||
CONFIG_MODULES_FLIGHT_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_ATT_CONTROL=y
|
||||
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y
|
||||
CONFIG_MODULES_FW_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y
|
||||
CONFIG_MODULES_FW_POS_CONTROL=y
|
||||
CONFIG_MODULES_FW_RATE_CONTROL=y
|
||||
CONFIG_MODULES_GIMBAL=y
|
||||
CONFIG_MODULES_GYRO_CALIBRATION=y
|
||||
|
||||
@ -46,8 +46,7 @@ CONFIG_MODULES_EVENTS=y
|
||||
CONFIG_MODULES_FLIGHT_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_ATT_CONTROL=y
|
||||
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y
|
||||
CONFIG_MODULES_FW_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y
|
||||
CONFIG_MODULES_FW_POS_CONTROL=y
|
||||
CONFIG_MODULES_FW_RATE_CONTROL=y
|
||||
CONFIG_MODULES_GIMBAL=y
|
||||
CONFIG_MODULES_GYRO_CALIBRATION=y
|
||||
|
||||
@ -56,8 +56,7 @@ CONFIG_MODULES_EVENTS=y
|
||||
CONFIG_MODULES_FLIGHT_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_ATT_CONTROL=y
|
||||
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y
|
||||
CONFIG_MODULES_FW_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y
|
||||
CONFIG_MODULES_FW_POS_CONTROL=y
|
||||
CONFIG_MODULES_FW_RATE_CONTROL=y
|
||||
CONFIG_MODULES_GIMBAL=y
|
||||
CONFIG_MODULES_GYRO_CALIBRATION=y
|
||||
|
||||
@ -37,8 +37,7 @@ CONFIG_MODULES_EVENTS=y
|
||||
CONFIG_MODULES_FLIGHT_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_ATT_CONTROL=y
|
||||
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y
|
||||
CONFIG_MODULES_FW_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y
|
||||
CONFIG_MODULES_FW_POS_CONTROL=y
|
||||
CONFIG_MODULES_FW_RATE_CONTROL=y
|
||||
CONFIG_MODULES_GIMBAL=y
|
||||
CONFIG_MODULES_GYRO_CALIBRATION=y
|
||||
@ -57,11 +56,9 @@ CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y
|
||||
CONFIG_MODULES_MC_POS_CONTROL=y
|
||||
CONFIG_MODULES_MC_RATE_CONTROL=y
|
||||
CONFIG_MODULES_NAVIGATOR=y
|
||||
CONFIG_NUM_MISSION_ITMES_SUPPORTED=1000
|
||||
CONFIG_MODULES_RC_UPDATE=y
|
||||
CONFIG_MODULES_SENSORS=y
|
||||
CONFIG_MODULES_UXRCE_DDS_CLIENT=y
|
||||
CONFIG_MODULES_VTOL_ATT_CONTROL=y
|
||||
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
|
||||
CONFIG_SYSTEMCMDS_BSONDUMP=y
|
||||
CONFIG_SYSTEMCMDS_DMESG=y
|
||||
|
||||
@ -37,8 +37,7 @@ CONFIG_MODULES_EVENTS=y
|
||||
CONFIG_MODULES_FLIGHT_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_ATT_CONTROL=y
|
||||
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y
|
||||
CONFIG_MODULES_FW_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y
|
||||
CONFIG_MODULES_FW_POS_CONTROL=y
|
||||
CONFIG_FIGURE_OF_EIGHT=y
|
||||
CONFIG_MODULES_FW_RATE_CONTROL=y
|
||||
CONFIG_MODULES_GIMBAL=y
|
||||
|
||||
@ -26,6 +26,3 @@ nshterm /dev/ttyS3 &
|
||||
|
||||
# Start the time_persistor to cyclically store the RTC in FRAM
|
||||
time_persistor start
|
||||
|
||||
# Start the ESC telemetry
|
||||
dshot telemetry -d /dev/ttyS5 -x
|
||||
|
||||
@ -3,8 +3,7 @@ CONFIG_MODE_NAVIGATOR_VTOL_TAKEOFF=n
|
||||
CONFIG_MODULES_AIRSPEED_SELECTOR=n
|
||||
CONFIG_MODULES_FW_ATT_CONTROL=n
|
||||
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=n
|
||||
CONFIG_MODULES_FW_MODE_MANAGER=n
|
||||
CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=n
|
||||
CONFIG_MODULES_FW_POS_CONTROL=n
|
||||
CONFIG_MODULES_FW_RATE_CONTROL=n
|
||||
CONFIG_MODULES_VTOL_ATT_CONTROL=n
|
||||
CONFIG_COMMON_RC=y
|
||||
|
||||
@ -2,8 +2,7 @@ CONFIG_MODULES_AIRSPEED_SELECTOR=n
|
||||
CONFIG_MODULES_FLIGHT_MODE_MANAGER=n
|
||||
CONFIG_MODULES_FW_ATT_CONTROL=n
|
||||
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=n
|
||||
CONFIG_MODULES_FW_MODE_MANAGER=n
|
||||
CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=n
|
||||
CONFIG_MODULES_FW_POS_CONTROL=n
|
||||
CONFIG_MODULES_FW_RATE_CONTROL=n
|
||||
CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=n
|
||||
CONFIG_MODULES_MC_ATT_CONTROL=n
|
||||
|
||||
@ -42,8 +42,7 @@ CONFIG_MODULES_EVENTS=y
|
||||
CONFIG_MODULES_FLIGHT_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_ATT_CONTROL=y
|
||||
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y
|
||||
CONFIG_MODULES_FW_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y
|
||||
CONFIG_MODULES_FW_POS_CONTROL=y
|
||||
CONFIG_MODULES_FW_RATE_CONTROL=y
|
||||
CONFIG_MODULES_GIMBAL=y
|
||||
CONFIG_MODULES_GYRO_CALIBRATION=y
|
||||
|
||||
@ -30,8 +30,7 @@ CONFIG_MODULES_EVENTS=y
|
||||
CONFIG_MODULES_FLIGHT_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_ATT_CONTROL=y
|
||||
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y
|
||||
CONFIG_MODULES_FW_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y
|
||||
CONFIG_MODULES_FW_POS_CONTROL=y
|
||||
CONFIG_MODULES_FW_RATE_CONTROL=y
|
||||
CONFIG_MODULES_GIMBAL=y
|
||||
CONFIG_MODULES_GYRO_CALIBRATION=y
|
||||
|
||||
@ -49,8 +49,7 @@ CONFIG_MODULES_UUV_ATT_CONTROL=y
|
||||
CONFIG_MODULES_UUV_POS_CONTROL=y
|
||||
CONFIG_MODULES_FW_ATT_CONTROL=y
|
||||
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y
|
||||
CONFIG_MODULES_FW_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y
|
||||
CONFIG_MODULES_FW_POS_CONTROL=y
|
||||
CONFIG_MODULES_FW_RATE_CONTROL=y
|
||||
CONFIG_MODULES_MANUAL_CONTROL=y
|
||||
CONFIG_MODULES_MC_ATT_CONTROL=y
|
||||
|
||||
@ -38,8 +38,7 @@ CONFIG_MODULES_EVENTS=y
|
||||
CONFIG_MODULES_FLIGHT_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_ATT_CONTROL=y
|
||||
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y
|
||||
CONFIG_MODULES_FW_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y
|
||||
CONFIG_MODULES_FW_POS_CONTROL=y
|
||||
CONFIG_MODULES_FW_RATE_CONTROL=y
|
||||
CONFIG_MODULES_GYRO_CALIBRATION=y
|
||||
CONFIG_MODULES_GYRO_FFT=y
|
||||
|
||||
@ -42,8 +42,7 @@ CONFIG_MODULES_EVENTS=y
|
||||
CONFIG_MODULES_FLIGHT_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_ATT_CONTROL=y
|
||||
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y
|
||||
CONFIG_MODULES_FW_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y
|
||||
CONFIG_MODULES_FW_POS_CONTROL=y
|
||||
CONFIG_MODULES_FW_RATE_CONTROL=y
|
||||
CONFIG_MODULES_GIMBAL=y
|
||||
CONFIG_MODULES_GYRO_CALIBRATION=y
|
||||
|
||||
@ -50,8 +50,7 @@ CONFIG_MODULES_EVENTS=y
|
||||
CONFIG_MODULES_FLIGHT_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_ATT_CONTROL=y
|
||||
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y
|
||||
CONFIG_MODULES_FW_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y
|
||||
CONFIG_MODULES_FW_POS_CONTROL=y
|
||||
CONFIG_MODULES_FW_RATE_CONTROL=y
|
||||
CONFIG_MODULES_GIMBAL=y
|
||||
CONFIG_MODULES_GYRO_CALIBRATION=y
|
||||
|
||||
@ -50,8 +50,7 @@ CONFIG_MODULES_EVENTS=y
|
||||
CONFIG_MODULES_FLIGHT_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_ATT_CONTROL=y
|
||||
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y
|
||||
CONFIG_MODULES_FW_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y
|
||||
CONFIG_MODULES_FW_POS_CONTROL=y
|
||||
CONFIG_MODULES_FW_RATE_CONTROL=y
|
||||
CONFIG_MODULES_GIMBAL=y
|
||||
CONFIG_MODULES_GYRO_CALIBRATION=y
|
||||
|
||||
@ -49,8 +49,7 @@ CONFIG_MODULES_EVENTS=y
|
||||
CONFIG_MODULES_FLIGHT_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_ATT_CONTROL=y
|
||||
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y
|
||||
CONFIG_MODULES_FW_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y
|
||||
CONFIG_MODULES_FW_POS_CONTROL=y
|
||||
CONFIG_MODULES_FW_RATE_CONTROL=y
|
||||
CONFIG_MODULES_GIMBAL=y
|
||||
CONFIG_MODULES_GYRO_CALIBRATION=y
|
||||
|
||||
@ -50,8 +50,7 @@ CONFIG_MODULES_EVENTS=y
|
||||
CONFIG_MODULES_FLIGHT_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_ATT_CONTROL=y
|
||||
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y
|
||||
CONFIG_MODULES_FW_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y
|
||||
CONFIG_MODULES_FW_POS_CONTROL=y
|
||||
CONFIG_MODULES_FW_RATE_CONTROL=y
|
||||
CONFIG_MODULES_GIMBAL=y
|
||||
CONFIG_MODULES_GYRO_CALIBRATION=y
|
||||
|
||||
@ -46,8 +46,7 @@ CONFIG_MODULES_EVENTS=y
|
||||
CONFIG_MODULES_FLIGHT_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_ATT_CONTROL=y
|
||||
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y
|
||||
CONFIG_MODULES_FW_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y
|
||||
CONFIG_MODULES_FW_POS_CONTROL=y
|
||||
CONFIG_MODULES_FW_RATE_CONTROL=y
|
||||
CONFIG_MODULES_GIMBAL=y
|
||||
CONFIG_MODULES_GYRO_CALIBRATION=y
|
||||
|
||||
@ -32,8 +32,7 @@ CONFIG_MODULES_EVENTS=y
|
||||
CONFIG_MODULES_FLIGHT_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_ATT_CONTROL=y
|
||||
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y
|
||||
CONFIG_MODULES_FW_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y
|
||||
CONFIG_MODULES_FW_POS_CONTROL=y
|
||||
CONFIG_MODULES_FW_RATE_CONTROL=y
|
||||
CONFIG_MODULES_GIMBAL=y
|
||||
CONFIG_MODULES_GYRO_CALIBRATION=y
|
||||
|
||||
@ -39,8 +39,7 @@ CONFIG_MODULES_EVENTS=y
|
||||
CONFIG_MODULES_FLIGHT_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_ATT_CONTROL=y
|
||||
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y
|
||||
CONFIG_MODULES_FW_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y
|
||||
CONFIG_MODULES_FW_POS_CONTROL=y
|
||||
CONFIG_MODULES_FW_RATE_CONTROL=y
|
||||
CONFIG_MODULES_GIMBAL=y
|
||||
CONFIG_MODULES_GYRO_CALIBRATION=y
|
||||
|
||||
@ -10,4 +10,4 @@
|
||||
# fi
|
||||
|
||||
# DShot telemetry is always on UART7
|
||||
# dshot telemetry -d /dev/ttyS5
|
||||
# dshot telemetry /dev/ttyS5
|
||||
|
||||
@ -41,8 +41,7 @@ CONFIG_MODULES_EVENTS=y
|
||||
CONFIG_MODULES_FLIGHT_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_ATT_CONTROL=y
|
||||
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y
|
||||
CONFIG_MODULES_FW_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y
|
||||
CONFIG_MODULES_FW_POS_CONTROL=y
|
||||
CONFIG_MODULES_FW_RATE_CONTROL=y
|
||||
CONFIG_MODULES_GIMBAL=y
|
||||
CONFIG_MODULES_GYRO_CALIBRATION=y
|
||||
|
||||
@ -10,4 +10,4 @@
|
||||
# fi
|
||||
|
||||
# DShot telemetry is always on UART7
|
||||
# dshot telemetry -d /dev/ttyS5
|
||||
# dshot telemetry /dev/ttyS5
|
||||
|
||||
@ -44,8 +44,7 @@ CONFIG_MODULES_EVENTS=y
|
||||
CONFIG_MODULES_FLIGHT_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_ATT_CONTROL=y
|
||||
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y
|
||||
CONFIG_MODULES_FW_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y
|
||||
CONFIG_MODULES_FW_POS_CONTROL=y
|
||||
CONFIG_MODULES_FW_RATE_CONTROL=y
|
||||
CONFIG_MODULES_GIMBAL=y
|
||||
CONFIG_MODULES_GYRO_CALIBRATION=y
|
||||
|
||||
@ -9,4 +9,4 @@ then
|
||||
fi
|
||||
|
||||
# DShot telemetry is always on UART7
|
||||
dshot telemetry -d /dev/ttyS5
|
||||
dshot telemetry /dev/ttyS5
|
||||
|
||||
@ -13,11 +13,13 @@ CONFIG_DRIVERS_CDCACM_AUTOSTART=y
|
||||
CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y
|
||||
CONFIG_COMMON_DISTANCE_SENSOR=y
|
||||
CONFIG_DRIVERS_DSHOT=y
|
||||
CONFIG_DRIVERS_GNSS_SEPTENTRIO=y
|
||||
CONFIG_DRIVERS_GPS=y
|
||||
CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y
|
||||
CONFIG_DRIVERS_OSD_ATXXXX=y
|
||||
CONFIG_COMMON_LIGHT=y
|
||||
CONFIG_COMMON_MAGNETOMETER=y
|
||||
CONFIG_COMMON_OPTICAL_FLOW=y
|
||||
CONFIG_DRIVERS_PWM_OUT=y
|
||||
CONFIG_DRIVERS_RC_INPUT=y
|
||||
CONFIG_COMMON_TELEMETRY=y
|
||||
@ -35,8 +37,7 @@ CONFIG_MODULES_EVENTS=y
|
||||
CONFIG_MODULES_FLIGHT_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_ATT_CONTROL=y
|
||||
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y
|
||||
CONFIG_MODULES_FW_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y
|
||||
CONFIG_MODULES_FW_POS_CONTROL=y
|
||||
CONFIG_MODULES_FW_RATE_CONTROL=y
|
||||
CONFIG_MODULES_GIMBAL=y
|
||||
CONFIG_MODULES_GYRO_CALIBRATION=y
|
||||
@ -56,7 +57,9 @@ CONFIG_MODULES_MC_RATE_CONTROL=y
|
||||
CONFIG_MODULES_NAVIGATOR=y
|
||||
CONFIG_NUM_MISSION_ITMES_SUPPORTED=1000
|
||||
CONFIG_MODULES_RC_UPDATE=y
|
||||
CONFIG_MODULES_ROVER_POS_CONTROL=y
|
||||
CONFIG_MODULES_SENSORS=y
|
||||
CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=y
|
||||
CONFIG_MODULES_VTOL_ATT_CONTROL=y
|
||||
CONFIG_SYSTEMCMDS_BSONDUMP=y
|
||||
CONFIG_SYSTEMCMDS_DMESG=y
|
||||
@ -66,7 +69,6 @@ CONFIG_SYSTEMCMDS_MFT=y
|
||||
CONFIG_SYSTEMCMDS_NSHTERM=y
|
||||
CONFIG_SYSTEMCMDS_PARAM=y
|
||||
CONFIG_SYSTEMCMDS_REBOOT=y
|
||||
CONFIG_SYSTEMCMDS_SD_BENCH=y
|
||||
CONFIG_SYSTEMCMDS_SYSTEM_TIME=y
|
||||
CONFIG_SYSTEMCMDS_TOP=y
|
||||
CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y
|
||||
|
||||
@ -7,7 +7,7 @@
|
||||
"summary": "KAKUTEH7-WING",
|
||||
"version": "0.1",
|
||||
"image_size": 0,
|
||||
"image_maxsize": 1703936,
|
||||
"image_maxsize": 1835008,
|
||||
"git_identity": "",
|
||||
"board_revision": 0
|
||||
}
|
||||
|
||||
@ -110,7 +110,7 @@
|
||||
MEMORY
|
||||
{
|
||||
ITCM_RAM (rwx) : ORIGIN = 0x00000000, LENGTH = 64K
|
||||
FLASH (rx) : ORIGIN = 0x08020000, LENGTH = 1664K /* params in last two sectors */
|
||||
FLASH (rx) : ORIGIN = 0x08020000, LENGTH = 1792K /* params in last sector */
|
||||
|
||||
DTCM1_RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 64K
|
||||
DTCM2_RAM (rwx) : ORIGIN = 0x20010000, LENGTH = 64K
|
||||
|
||||
@ -114,6 +114,7 @@
|
||||
|
||||
#define BOARD_NUMBER_BRICKS 2
|
||||
|
||||
// TODO: fix
|
||||
#define GPIO_nVDD_BRICK1_VALID (1) /* Brick 1 Is Chosen */
|
||||
#define GPIO_nVDD_BRICK2_VALID (0) /* Brick 2 Is Chosen */
|
||||
|
||||
@ -128,20 +129,17 @@
|
||||
*/
|
||||
#define UAVCAN_NUM_IFACES_RUNTIME 1
|
||||
|
||||
#define GPIO_VDD_3V3_SENSORS_EN /* PB2 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN2)
|
||||
|
||||
#define GPIO_VTX_9V_EN /* PE3 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN3)
|
||||
|
||||
#define GPIO_CAM_SWITCH /* PC13 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN13)
|
||||
#define GPIO_VDD_5V_PERIPH_nEN /* PE2 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN2)
|
||||
#define GPIO_VDD_5V_PERIPH_nOC /* PE3 */ (GPIO_INPUT |GPIO_FLOAT|GPIO_PORTE|GPIO_PIN3)
|
||||
#define GPIO_VDD_5V_HIPOWER_nEN /* PC10 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN10)
|
||||
#define GPIO_VDD_5V_HIPOWER_nOC /* PC11 */ (GPIO_INPUT |GPIO_FLOAT|GPIO_PORTC|GPIO_PIN11)
|
||||
#define GPIO_VDD_3V3_SENSORS_EN /* PB2 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN2)
|
||||
|
||||
/* Define True logic Power Control in arch agnostic form */
|
||||
|
||||
#define VDD_3V3_SENSORS_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_3V3_SENSORS_EN, (on_true))
|
||||
|
||||
#define VTX_9V_EN(on_true) px4_arch_gpiowrite(GPIO_VTX_9V_EN, (on_true))
|
||||
|
||||
#define CAM_SWITCH_CAM1 px4_arch_gpiowrite(GPIO_CAM_SWITCH, false) // low is CAM1
|
||||
#define CAM_SWITCH_CAM2 px4_arch_gpiowrite(GPIO_CAM_SWITCH, true) // high is CAM2
|
||||
#define VDD_5V_PERIPH_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_5V_PERIPH_nEN, !(on_true))
|
||||
#define VDD_5V_HIPOWER_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_5V_HIPOWER_nEN, !(on_true))
|
||||
#define VDD_3V3_SENSORS_EN(on_true) px4_arch_gpiowrite(GPIO_VDD_3V3_SENSORS4_EN, (on_true))
|
||||
|
||||
/* Tone alarm output */
|
||||
|
||||
@ -198,10 +196,11 @@
|
||||
|
||||
#define BOARD_ADC_SERVO_VALID (1)
|
||||
|
||||
#define BOARD_ADC_BRICK1_VALID (1)
|
||||
#define BOARD_ADC_BRICK2_VALID (1)
|
||||
#define BOARD_ADC_BRICK1_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK1_VALID))
|
||||
#define BOARD_ADC_BRICK2_VALID (!px4_arch_gpioread(GPIO_nVDD_BRICK2_VALID))
|
||||
|
||||
#define BOARD_ADC_SERVO_VALID (1)
|
||||
#define BOARD_ADC_PERIPH_5V_OC (!px4_arch_gpioread(GPIO_VDD_5V_PERIPH_nOC))
|
||||
#define BOARD_ADC_HIPOWER_5V_OC (!px4_arch_gpioread(GPIO_VDD_5V_HIPOWER_nOC))
|
||||
|
||||
|
||||
/* This board provides a DMA pool and APIs */
|
||||
@ -218,8 +217,6 @@
|
||||
GPIO_VDD_3V3_SENSORS_EN, \
|
||||
GPIO_TONE_ALARM_IDLE, \
|
||||
GPIO_PPM_IN, \
|
||||
GPIO_VTX_9V_EN, \
|
||||
GPIO_CAM_SWITCH, \
|
||||
}
|
||||
|
||||
#define BOARD_ENABLE_CONSOLE_BUFFER
|
||||
|
||||
@ -108,21 +108,21 @@ __END_DECLS
|
||||
************************************************************************************/
|
||||
__EXPORT void board_peripheral_reset(int ms)
|
||||
{
|
||||
/* off */
|
||||
VTX_9V_EN(false);
|
||||
VDD_3V3_SENSORS_EN(false);
|
||||
/* set the peripheral rails off */
|
||||
|
||||
VDD_5V_PERIPH_EN(false);
|
||||
board_control_spi_sensors_power(false, 0xffff);
|
||||
|
||||
/* wait for the peripheral rail to reach GND */
|
||||
usleep(ms * 1000);
|
||||
syslog(LOG_DEBUG, "reset done, %d ms\n", ms);
|
||||
|
||||
/* re-enable power */
|
||||
board_control_spi_sensors_power(true, 0xffff);
|
||||
VDD_3V3_SENSORS_EN(true);
|
||||
VTX_9V_EN(true);
|
||||
|
||||
CAM_SWITCH_CAM1;
|
||||
/* switch the peripheral rail back on */
|
||||
board_control_spi_sensors_power(true, 0xffff);
|
||||
VDD_5V_PERIPH_EN(true);
|
||||
|
||||
}
|
||||
|
||||
/************************************************************************************
|
||||
@ -210,6 +210,10 @@ __EXPORT int board_app_initialize(uintptr_t arg)
|
||||
{
|
||||
#if !defined(BOOTLOADER)
|
||||
|
||||
/* Power on Interfaces */
|
||||
VDD_5V_PERIPH_EN(true);
|
||||
VDD_5V_HIPOWER_EN(true);
|
||||
|
||||
/* Need hrt running before using the ADC */
|
||||
|
||||
px4_platform_init();
|
||||
@ -250,7 +254,6 @@ __EXPORT int board_app_initialize(uintptr_t arg)
|
||||
|
||||
#if defined(FLASH_BASED_PARAMS)
|
||||
static sector_descriptor_t params_sector_map[] = {
|
||||
{14, 128 * 1024, 0x081C0000},
|
||||
{15, 128 * 1024, 0x081E0000},
|
||||
{0, 0, 0},
|
||||
};
|
||||
|
||||
@ -45,8 +45,7 @@ CONFIG_MODULES_EVENTS=y
|
||||
CONFIG_MODULES_FLIGHT_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_ATT_CONTROL=y
|
||||
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y
|
||||
CONFIG_MODULES_FW_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y
|
||||
CONFIG_MODULES_FW_POS_CONTROL=y
|
||||
CONFIG_MODULES_FW_RATE_CONTROL=y
|
||||
CONFIG_MODULES_GIMBAL=y
|
||||
CONFIG_MODULES_GYRO_CALIBRATION=y
|
||||
|
||||
@ -9,4 +9,4 @@ then
|
||||
fi
|
||||
|
||||
# DShot telemetry is always on UART7
|
||||
dshot telemetry -d /dev/ttyS5
|
||||
dshot telemetry /dev/ttyS5
|
||||
|
||||
@ -48,8 +48,7 @@ CONFIG_MODULES_EVENTS=y
|
||||
CONFIG_MODULES_FLIGHT_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_ATT_CONTROL=y
|
||||
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y
|
||||
CONFIG_MODULES_FW_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y
|
||||
CONFIG_MODULES_FW_POS_CONTROL=y
|
||||
CONFIG_MODULES_FW_RATE_CONTROL=y
|
||||
CONFIG_MODULES_GIMBAL=y
|
||||
CONFIG_MODULES_GYRO_CALIBRATION=y
|
||||
|
||||
@ -9,4 +9,4 @@ then
|
||||
fi
|
||||
|
||||
# DShot telemetry is always on UART7
|
||||
dshot telemetry -d /dev/ttyS5
|
||||
dshot telemetry /dev/ttyS5
|
||||
|
||||
@ -45,8 +45,7 @@ CONFIG_MODULES_EVENTS=y
|
||||
CONFIG_MODULES_FLIGHT_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_ATT_CONTROL=y
|
||||
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y
|
||||
CONFIG_MODULES_FW_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y
|
||||
CONFIG_MODULES_FW_POS_CONTROL=y
|
||||
CONFIG_MODULES_FW_RATE_CONTROL=y
|
||||
CONFIG_MODULES_GIMBAL=y
|
||||
CONFIG_MODULES_GYRO_CALIBRATION=y
|
||||
|
||||
@ -9,4 +9,4 @@ then
|
||||
fi
|
||||
|
||||
# DShot telemetry is always on UART7
|
||||
dshot telemetry -d /dev/ttyS5
|
||||
dshot telemetry /dev/ttyS5
|
||||
|
||||
@ -45,8 +45,7 @@ CONFIG_MODULES_EVENTS=y
|
||||
CONFIG_MODULES_FLIGHT_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_ATT_CONTROL=y
|
||||
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y
|
||||
CONFIG_MODULES_FW_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y
|
||||
CONFIG_MODULES_FW_POS_CONTROL=y
|
||||
CONFIG_MODULES_FW_RATE_CONTROL=y
|
||||
CONFIG_MODULES_GIMBAL=y
|
||||
CONFIG_MODULES_GYRO_CALIBRATION=y
|
||||
|
||||
@ -9,4 +9,4 @@ then
|
||||
fi
|
||||
|
||||
# DShot telemetry is always on UART7
|
||||
dshot telemetry -d /dev/ttyS5
|
||||
dshot telemetry /dev/ttyS5
|
||||
|
||||
@ -50,8 +50,7 @@ CONFIG_MODULES_EVENTS=y
|
||||
CONFIG_MODULES_FLIGHT_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_ATT_CONTROL=y
|
||||
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y
|
||||
CONFIG_MODULES_FW_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y
|
||||
CONFIG_MODULES_FW_POS_CONTROL=y
|
||||
CONFIG_MODULES_FW_RATE_CONTROL=y
|
||||
CONFIG_MODULES_GIMBAL=y
|
||||
CONFIG_MODULES_GYRO_CALIBRATION=y
|
||||
|
||||
@ -30,8 +30,7 @@ CONFIG_MODULES_EKF2=y
|
||||
CONFIG_MODULES_EVENTS=y
|
||||
CONFIG_MODULES_FLIGHT_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_ATT_CONTROL=y
|
||||
CONFIG_MODULES_FW_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y
|
||||
CONFIG_MODULES_FW_POS_CONTROL=y
|
||||
CONFIG_MODULES_FW_RATE_CONTROL=y
|
||||
CONFIG_MODULES_GYRO_CALIBRATION=y
|
||||
CONFIG_MODULES_GYRO_FFT=y
|
||||
|
||||
@ -11,4 +11,4 @@
|
||||
atxxxx start -s
|
||||
|
||||
# DShot telemetry is always on UART7
|
||||
# dshot telemetry -d /dev/ttyS5
|
||||
# dshot telemetry /dev/ttyS5
|
||||
|
||||
@ -33,8 +33,7 @@ CONFIG_MODULES_EKF2=y
|
||||
CONFIG_MODULES_EVENTS=y
|
||||
CONFIG_MODULES_FLIGHT_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_ATT_CONTROL=y
|
||||
CONFIG_MODULES_FW_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y
|
||||
CONFIG_MODULES_FW_POS_CONTROL=y
|
||||
CONFIG_MODULES_FW_RATE_CONTROL=y
|
||||
CONFIG_MODULES_GYRO_CALIBRATION=y
|
||||
CONFIG_MODULES_GYRO_FFT=y
|
||||
|
||||
@ -12,4 +12,4 @@ atxxxx start -s
|
||||
|
||||
|
||||
# DShot telemetry is always on UART7
|
||||
# dshot telemetry -d /dev/ttyS5
|
||||
# dshot telemetry /dev/ttyS5
|
||||
|
||||
@ -32,8 +32,7 @@ CONFIG_MODULES_EKF2=y
|
||||
CONFIG_MODULES_EVENTS=y
|
||||
CONFIG_MODULES_FLIGHT_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_ATT_CONTROL=y
|
||||
CONFIG_MODULES_FW_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y
|
||||
CONFIG_MODULES_FW_POS_CONTROL=y
|
||||
CONFIG_MODULES_FW_RATE_CONTROL=y
|
||||
CONFIG_MODULES_GYRO_CALIBRATION=y
|
||||
CONFIG_MODULES_GYRO_FFT=y
|
||||
|
||||
@ -12,4 +12,4 @@ atxxxx start -s
|
||||
|
||||
|
||||
# DShot telemetry is always on UART7
|
||||
# dshot telemetry -d /dev/ttyS5
|
||||
# dshot telemetry /dev/ttyS5
|
||||
|
||||
@ -39,8 +39,7 @@ CONFIG_MODULES_EVENTS=y
|
||||
CONFIG_MODULES_FLIGHT_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_ATT_CONTROL=y
|
||||
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y
|
||||
CONFIG_MODULES_FW_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y
|
||||
CONFIG_MODULES_FW_POS_CONTROL=y
|
||||
CONFIG_MODULES_FW_RATE_CONTROL=y
|
||||
CONFIG_MODULES_GYRO_CALIBRATION=y
|
||||
CONFIG_MODULES_GYRO_FFT=y
|
||||
|
||||
@ -40,8 +40,7 @@ CONFIG_MODULES_EVENTS=y
|
||||
CONFIG_MODULES_FLIGHT_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_ATT_CONTROL=y
|
||||
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y
|
||||
CONFIG_MODULES_FW_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y
|
||||
CONFIG_MODULES_FW_POS_CONTROL=y
|
||||
CONFIG_MODULES_FW_RATE_CONTROL=y
|
||||
CONFIG_MODULES_GYRO_CALIBRATION=y
|
||||
CONFIG_MODULES_GYRO_FFT=y
|
||||
|
||||
@ -38,8 +38,7 @@ CONFIG_MODULES_EVENTS=y
|
||||
CONFIG_MODULES_FLIGHT_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_ATT_CONTROL=y
|
||||
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y
|
||||
CONFIG_MODULES_FW_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y
|
||||
CONFIG_MODULES_FW_POS_CONTROL=y
|
||||
CONFIG_MODULES_FW_RATE_CONTROL=y
|
||||
CONFIG_MODULES_GYRO_CALIBRATION=y
|
||||
CONFIG_MODULES_GYRO_FFT=y
|
||||
|
||||
@ -49,8 +49,7 @@ CONFIG_MODULES_EVENTS=y
|
||||
CONFIG_MODULES_FLIGHT_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_ATT_CONTROL=y
|
||||
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y
|
||||
CONFIG_MODULES_FW_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y
|
||||
CONFIG_MODULES_FW_POS_CONTROL=y
|
||||
CONFIG_MODULES_FW_RATE_CONTROL=y
|
||||
CONFIG_MODULES_GIMBAL=y
|
||||
CONFIG_MODULES_GYRO_CALIBRATION=y
|
||||
|
||||
@ -40,8 +40,7 @@ CONFIG_MODULES_EVENTS=y
|
||||
CONFIG_MODULES_FLIGHT_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_ATT_CONTROL=y
|
||||
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y
|
||||
CONFIG_MODULES_FW_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y
|
||||
CONFIG_MODULES_FW_POS_CONTROL=y
|
||||
CONFIG_MODULES_FW_RATE_CONTROL=y
|
||||
CONFIG_MODULES_GIMBAL=y
|
||||
CONFIG_MODULES_GYRO_CALIBRATION=y
|
||||
|
||||
@ -46,8 +46,7 @@ CONFIG_MODULES_EVENTS=y
|
||||
CONFIG_MODULES_FLIGHT_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_ATT_CONTROL=y
|
||||
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y
|
||||
CONFIG_MODULES_FW_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y
|
||||
CONFIG_MODULES_FW_POS_CONTROL=y
|
||||
CONFIG_MODULES_FW_RATE_CONTROL=y
|
||||
CONFIG_MODULES_GIMBAL=y
|
||||
CONFIG_MODULES_GYRO_CALIBRATION=y
|
||||
|
||||
@ -44,8 +44,7 @@ CONFIG_MODULES_EVENTS=y
|
||||
CONFIG_MODULES_FLIGHT_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_ATT_CONTROL=y
|
||||
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y
|
||||
CONFIG_MODULES_FW_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y
|
||||
CONFIG_MODULES_FW_POS_CONTROL=y
|
||||
CONFIG_MODULES_FW_RATE_CONTROL=y
|
||||
CONFIG_MODULES_GIMBAL=y
|
||||
CONFIG_MODULES_GYRO_CALIBRATION=y
|
||||
|
||||
@ -44,8 +44,7 @@ CONFIG_MODULES_EVENTS=y
|
||||
CONFIG_MODULES_FLIGHT_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_ATT_CONTROL=y
|
||||
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y
|
||||
CONFIG_MODULES_FW_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y
|
||||
CONFIG_MODULES_FW_POS_CONTROL=y
|
||||
CONFIG_MODULES_FW_RATE_CONTROL=y
|
||||
CONFIG_MODULES_GIMBAL=y
|
||||
CONFIG_MODULES_GYRO_CALIBRATION=y
|
||||
|
||||
@ -42,8 +42,7 @@ CONFIG_MODULES_EVENTS=y
|
||||
CONFIG_MODULES_FLIGHT_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_ATT_CONTROL=y
|
||||
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y
|
||||
CONFIG_MODULES_FW_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y
|
||||
CONFIG_MODULES_FW_POS_CONTROL=y
|
||||
CONFIG_MODULES_FW_RATE_CONTROL=y
|
||||
CONFIG_MODULES_GIMBAL=y
|
||||
CONFIG_MODULES_GYRO_CALIBRATION=y
|
||||
|
||||
@ -43,8 +43,7 @@ CONFIG_MODULES_EVENTS=y
|
||||
CONFIG_MODULES_FLIGHT_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_ATT_CONTROL=y
|
||||
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y
|
||||
CONFIG_MODULES_FW_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y
|
||||
CONFIG_MODULES_FW_POS_CONTROL=y
|
||||
CONFIG_MODULES_FW_RATE_CONTROL=y
|
||||
CONFIG_MODULES_GIMBAL=y
|
||||
CONFIG_MODULES_GYRO_CALIBRATION=y
|
||||
|
||||
@ -43,8 +43,7 @@ CONFIG_MODULES_EVENTS=y
|
||||
CONFIG_MODULES_FLIGHT_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_ATT_CONTROL=y
|
||||
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y
|
||||
CONFIG_MODULES_FW_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y
|
||||
CONFIG_MODULES_FW_POS_CONTROL=y
|
||||
CONFIG_MODULES_FW_RATE_CONTROL=y
|
||||
CONFIG_MODULES_GIMBAL=y
|
||||
CONFIG_MODULES_GYRO_CALIBRATION=y
|
||||
|
||||
@ -45,8 +45,7 @@ CONFIG_MODULES_EVENTS=y
|
||||
CONFIG_MODULES_FLIGHT_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_ATT_CONTROL=y
|
||||
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y
|
||||
CONFIG_MODULES_FW_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y
|
||||
CONFIG_MODULES_FW_POS_CONTROL=y
|
||||
CONFIG_MODULES_FW_RATE_CONTROL=y
|
||||
CONFIG_MODULES_GIMBAL=y
|
||||
CONFIG_MODULES_GYRO_CALIBRATION=y
|
||||
|
||||
@ -46,8 +46,7 @@ CONFIG_MODULES_EVENTS=y
|
||||
CONFIG_MODULES_FLIGHT_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_ATT_CONTROL=y
|
||||
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y
|
||||
CONFIG_MODULES_FW_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y
|
||||
CONFIG_MODULES_FW_POS_CONTROL=y
|
||||
CONFIG_MODULES_FW_RATE_CONTROL=y
|
||||
CONFIG_MODULES_GIMBAL=y
|
||||
CONFIG_MODULES_GYRO_CALIBRATION=y
|
||||
|
||||
@ -47,8 +47,7 @@ CONFIG_MODULES_EVENTS=y
|
||||
CONFIG_MODULES_FLIGHT_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_ATT_CONTROL=y
|
||||
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y
|
||||
CONFIG_MODULES_FW_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y
|
||||
CONFIG_MODULES_FW_POS_CONTROL=y
|
||||
CONFIG_MODULES_FW_RATE_CONTROL=y
|
||||
CONFIG_MODULES_GIMBAL=y
|
||||
CONFIG_MODULES_GYRO_CALIBRATION=y
|
||||
|
||||
@ -48,8 +48,7 @@ CONFIG_MODULES_EVENTS=y
|
||||
CONFIG_MODULES_FLIGHT_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_ATT_CONTROL=y
|
||||
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y
|
||||
CONFIG_MODULES_FW_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y
|
||||
CONFIG_MODULES_FW_POS_CONTROL=y
|
||||
CONFIG_MODULES_FW_RATE_CONTROL=y
|
||||
CONFIG_MODULES_GIMBAL=y
|
||||
CONFIG_MODULES_GYRO_CALIBRATION=y
|
||||
|
||||
@ -33,8 +33,7 @@ CONFIG_MODULES_EVENTS=y
|
||||
CONFIG_MODULES_FLIGHT_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_ATT_CONTROL=y
|
||||
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y
|
||||
CONFIG_MODULES_FW_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y
|
||||
CONFIG_MODULES_FW_POS_CONTROL=y
|
||||
CONFIG_MODULES_FW_RATE_CONTROL=y
|
||||
CONFIG_MODULES_GYRO_CALIBRATION=y
|
||||
CONFIG_MODULES_GYRO_FFT=y
|
||||
|
||||
@ -20,8 +20,7 @@ CONFIG_MODULES_EVENTS=y
|
||||
CONFIG_MODULES_FLIGHT_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_ATT_CONTROL=y
|
||||
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y
|
||||
CONFIG_MODULES_FW_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y
|
||||
CONFIG_MODULES_FW_POS_CONTROL=y
|
||||
CONFIG_MODULES_FW_RATE_CONTROL=y
|
||||
CONFIG_MODULES_GYRO_CALIBRATION=y
|
||||
CONFIG_MODULES_GYRO_FFT=y
|
||||
|
||||
@ -24,8 +24,7 @@ CONFIG_MODULES_ESC_BATTERY=y
|
||||
CONFIG_MODULES_EVENTS=y
|
||||
CONFIG_MODULES_FW_ATT_CONTROL=y
|
||||
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y
|
||||
CONFIG_MODULES_FW_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y
|
||||
CONFIG_MODULES_FW_POS_CONTROL=y
|
||||
CONFIG_MODULES_FW_RATE_CONTROL=y
|
||||
CONFIG_MODULES_GYRO_CALIBRATION=y
|
||||
CONFIG_MODULES_GYRO_FFT=y
|
||||
|
||||
@ -15,19 +15,15 @@ CONFIG_DRIVERS_CDCACM_AUTOSTART=y
|
||||
CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y
|
||||
CONFIG_COMMON_DISTANCE_SENSOR=y
|
||||
CONFIG_DRIVERS_DSHOT=y
|
||||
CONFIG_DRIVERS_GNSS_SEPTENTRIO=y
|
||||
CONFIG_DRIVERS_GPS=y
|
||||
CONFIG_DRIVERS_IMU_BOSCH_BMI088=y
|
||||
CONFIG_DRIVERS_IMU_INVENSENSE_ICM20948=y
|
||||
CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y
|
||||
CONFIG_DRIVERS_IMU_INVENSENSE_ICM45686=y
|
||||
CONFIG_COMMON_INS=y
|
||||
CONFIG_COMMON_LIGHT=y
|
||||
CONFIG_DRIVERS_LIGHTS_RGBLED_PWM=y
|
||||
CONFIG_COMMON_MAGNETOMETER=y
|
||||
CONFIG_DRIVERS_MAGNETOMETER_BOSCH_BMM350=y
|
||||
CONFIG_COMMON_OPTICAL_FLOW=y
|
||||
CONFIG_COMMON_OSD=y
|
||||
CONFIG_DRIVERS_OSD_MSP_OSD=y
|
||||
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
|
||||
CONFIG_DRIVERS_POWER_MONITOR_INA228=y
|
||||
CONFIG_DRIVERS_POWER_MONITOR_INA238=y
|
||||
|
||||
@ -30,7 +30,7 @@ CONFIG_ARM_MPU=y
|
||||
CONFIG_ARM_MPU_RESET=y
|
||||
CONFIG_BOARDCTL_RESET=y
|
||||
CONFIG_BOARD_ASSERT_RESET_VALUE=0
|
||||
CONFIG_BOARD_LOOPSPERMSEC=115000
|
||||
CONFIG_BOARD_LOOPSPERMSEC=114325
|
||||
CONFIG_BOARD_RESET_ON_ASSERT=2
|
||||
CONFIG_BUILTIN=y
|
||||
CONFIG_CDCACM=y
|
||||
@ -73,7 +73,6 @@ CONFIG_HAVE_CXXINITIALIZE=y
|
||||
CONFIG_I2C=y
|
||||
CONFIG_I2C_RESET=y
|
||||
CONFIG_IDLETHREAD_STACKSIZE=2048
|
||||
CONFIG_IMXRT_DTCM_HEAP=y
|
||||
CONFIG_IMXRT_EDMA=y
|
||||
CONFIG_IMXRT_EDMA_EDBG=y
|
||||
CONFIG_IMXRT_EDMA_ELINK=y
|
||||
@ -141,7 +140,6 @@ CONFIG_MEMSET_64BIT=y
|
||||
CONFIG_MEMSET_OPTSPEED=y
|
||||
CONFIG_MMCSD=y
|
||||
CONFIG_MMCSD_SDIO=y
|
||||
CONFIG_MM_REGIONS=2
|
||||
CONFIG_MTD=y
|
||||
CONFIG_MTD_BYTE_WRITE=y
|
||||
CONFIG_MTD_PARTITION=y
|
||||
|
||||
@ -1,5 +1,5 @@
|
||||
/****************************************************************************
|
||||
* boards/nxp/tropic-community/nuttx-config/scripts/script.ld
|
||||
* boards/arm/imxrt/teensy-4.x/scripts/flash.ld
|
||||
*
|
||||
* Licensed to the Apache Software Foundation (ASF) under one or more
|
||||
* contributor license agreements. See the NOTICE file distributed with
|
||||
@ -67,7 +67,6 @@ SECTIONS
|
||||
_sitcmfuncs = ABSOLUTE(.);
|
||||
FILL(0xFF)
|
||||
. = 0x40 ;
|
||||
*(.ram_vectors)
|
||||
INCLUDE "itcm_static_functions.ld"
|
||||
INCLUDE "itcm_functions_includes.ld"
|
||||
. = ALIGN(8);
|
||||
@ -76,6 +75,19 @@ SECTIONS
|
||||
|
||||
_fitcmfuncs = LOADADDR(.itcmfunc);
|
||||
|
||||
/* The RAM vector table (if present) should lie at the beginning of SRAM */
|
||||
|
||||
.ram_vectors (COPY) : {
|
||||
*(.ram_vectors)
|
||||
} > dtcm
|
||||
|
||||
|
||||
/* Workaround for ethernet issue, by placing g_desc_pool into DTCM,
|
||||
which effectively puts it into a no-cache region */
|
||||
.dtcm : {
|
||||
*(.bss.g_desc_pool)
|
||||
} > dtcm
|
||||
|
||||
.text :
|
||||
{
|
||||
_stext = ABSOLUTE(.);
|
||||
|
||||
@ -8,6 +8,5 @@ CONFIG_DRIVERS_DISTANCE_SENSOR_LIGHTWARE_LASER_I2C=y
|
||||
CONFIG_DRIVERS_DISTANCE_SENSOR_LIGHTWARE_LASER_SERIAL=y
|
||||
CONFIG_MODULES_AIRSPEED_SELECTOR=y
|
||||
CONFIG_MODULES_FW_ATT_CONTROL=y
|
||||
CONFIG_MODULES_FW_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y
|
||||
CONFIG_MODULES_FW_POS_CONTROL=y
|
||||
CONFIG_MODULES_FW_RATE_CONTROL=y
|
||||
|
||||
@ -51,8 +51,7 @@ CONFIG_MODULES_EVENTS=y
|
||||
CONFIG_MODULES_FLIGHT_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_ATT_CONTROL=y
|
||||
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y
|
||||
CONFIG_MODULES_FW_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y
|
||||
CONFIG_MODULES_FW_POS_CONTROL=y
|
||||
CONFIG_MODULES_FW_RATE_CONTROL=y
|
||||
CONFIG_MODULES_GIMBAL=y
|
||||
CONFIG_MODULES_GYRO_CALIBRATION=y
|
||||
|
||||
@ -52,8 +52,7 @@ CONFIG_MODULES_EVENTS=y
|
||||
CONFIG_MODULES_FLIGHT_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_ATT_CONTROL=y
|
||||
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y
|
||||
CONFIG_MODULES_FW_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y
|
||||
CONFIG_MODULES_FW_POS_CONTROL=y
|
||||
CONFIG_MODULES_FW_RATE_CONTROL=y
|
||||
CONFIG_MODULES_GIMBAL=y
|
||||
CONFIG_MODULES_GYRO_CALIBRATION=y
|
||||
|
||||
@ -47,8 +47,7 @@ CONFIG_MODULES_EVENTS=y
|
||||
CONFIG_MODULES_FLIGHT_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_ATT_CONTROL=y
|
||||
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y
|
||||
CONFIG_MODULES_FW_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y
|
||||
CONFIG_MODULES_FW_POS_CONTROL=y
|
||||
CONFIG_MODULES_FW_RATE_CONTROL=y
|
||||
CONFIG_MODULES_GIMBAL=y
|
||||
CONFIG_MODULES_GYRO_CALIBRATION=y
|
||||
|
||||
@ -55,8 +55,7 @@ CONFIG_MODULES_EVENTS=y
|
||||
CONFIG_MODULES_FLIGHT_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_ATT_CONTROL=y
|
||||
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y
|
||||
CONFIG_MODULES_FW_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y
|
||||
CONFIG_MODULES_FW_POS_CONTROL=y
|
||||
CONFIG_MODULES_FW_RATE_CONTROL=y
|
||||
CONFIG_MODULES_GIMBAL=y
|
||||
CONFIG_MODULES_GYRO_CALIBRATION=y
|
||||
|
||||
@ -17,8 +17,7 @@ CONFIG_MODULES_CAMERA_FEEDBACK=n
|
||||
CONFIG_MODULES_ESC_BATTERY=n
|
||||
CONFIG_MODULES_FW_ATT_CONTROL=n
|
||||
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=n
|
||||
CONFIG_MODULES_FW_MODE_MANAGER=n
|
||||
CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=n
|
||||
CONFIG_MODULES_FW_POS_CONTROL=n
|
||||
CONFIG_MODULES_ROVER_POS_CONTROL=n
|
||||
CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=n
|
||||
CONFIG_MODULES_TEMPERATURE_COMPENSATION=n
|
||||
|
||||
@ -4,8 +4,7 @@ CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=n
|
||||
CONFIG_MODULES_FLIGHT_MODE_MANAGER=n
|
||||
CONFIG_MODULES_FW_ATT_CONTROL=n
|
||||
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=n
|
||||
CONFIG_MODULES_FW_MODE_MANAGER=n
|
||||
CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=n
|
||||
CONFIG_MODULES_FW_POS_CONTROL=n
|
||||
CONFIG_MODULES_FW_RATE_CONTROL=n
|
||||
CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=n
|
||||
CONFIG_MODULES_MC_ATT_CONTROL=n
|
||||
|
||||
@ -29,8 +29,7 @@ CONFIG_MODULES_ESC_BATTERY=n
|
||||
CONFIG_MODULES_EVENTS=n
|
||||
CONFIG_MODULES_FW_ATT_CONTROL=n
|
||||
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=n
|
||||
CONFIG_MODULES_FW_MODE_MANAGER=n
|
||||
CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=n
|
||||
CONFIG_MODULES_FW_POS_CONTROL=n
|
||||
CONFIG_MODULES_FW_RATE_CONTROL=n
|
||||
CONFIG_MODULES_GIMBAL=n
|
||||
CONFIG_MODULES_GYRO_CALIBRATION=n
|
||||
|
||||
@ -59,8 +59,7 @@ CONFIG_MODULES_EVENTS=y
|
||||
CONFIG_MODULES_FLIGHT_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_ATT_CONTROL=y
|
||||
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y
|
||||
CONFIG_MODULES_FW_MODE_MANAGER=y
|
||||
CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=y
|
||||
CONFIG_MODULES_FW_POS_CONTROL=y
|
||||
CONFIG_MODULES_FW_RATE_CONTROL=y
|
||||
CONFIG_MODULES_GIMBAL=y
|
||||
CONFIG_MODULES_GYRO_CALIBRATION=y
|
||||
|
||||
Some files were not shown because too many files have changed in this diff Show More
Loading…
x
Reference in New Issue
Block a user