Compare commits

...

56 Commits

Author SHA1 Message Date
Daniel Agar 94cb201279 drivers/gps: warn if gps_inject_data publications have been missed 2025-11-10 00:55:16 -05:00
Daniel Agar 216fd858e8 drivers/gps: prioritize non-blocking reads over injection (#25535) 2025-11-10 00:55:16 -05:00
Jacob Dahl 399512571b platform: serial: add bytesAvailable() function 2025-11-10 00:55:16 -05:00
Matthew Berk 42dccca8fc flight_modes_fw/return.md: remove warning about now-fixed bug in mission RTLs in FW 2025-11-03 21:26:46 -09:00
Matthew Berk 6b5cfcce70 [Backport 1.16] Navigator: Fix mission RTL for fixed-wing by setting previous waypoint correctly(#25861)
This aligns setActiveMissionItems() in rtl_direct_mission_land.cpp and in rtl_mission_fast.cpp with what was already in mission.cpp. It probably was on oversight when the RTL restructure happened. The FW landing requires the previous waypoint to be correctly set, that's why it was only noticeable there.

* Fix position setpoint update logic in Mission RTL

Currently, when proceeding to the landing point the previous setpoint is not updated, which results in an unexpected and off course landing pattern in fixed wing. (see #25436)

* Change to work more like `mission.cpp`

* Fix rtl_direct_misssion_land formatting for style guide

* rtl_mission_fast: fix FW landing by setting previous wp in landing

Signed-off-by: Silvan <silvan@auterion.com>

---------

Signed-off-by: Silvan <silvan@auterion.com>
Co-authored-by: Silvan <silvan@auterion.com>
2025-11-03 21:34:27 +01:00
Jacob Dahl 06ec43629a mission: delay until: mark next setpoint invalid
Fixes bug with the NAV_CMD_DELAY where the copter would "pace" back and forth while waiting at the delay waypoint
2025-10-29 14:12:31 -08:00
Jacob Dahl 162b7d6372 serial: nuttx: revert tcdrain back to fsync (#25538)
* serial: nuttx: revert tcdrain back to fsync

* serial: do not print error on EAGAIN

---------

Co-authored-by: Alexander Lerach <alexander@auterion.com>
2025-10-29 12:42:06 -04:00
airpixel-cz 5141b40e79 mavlink: parameters: fix camera and cannode param message routing 2025-10-29 05:02:00 -08:00
Luka Filipović f3979c0fcf mission_base: on mission end, set loiter position from previous position type setpoint 2025-10-15 17:04:43 -04:00
Jacob Dahl 150dd0bff0 flight task auto: fix offtrack mission landing bug
During a mission the last waypoint is often a LAND. If the previous waypoint is not directly above the land waypoint the offtrack calculation is incorrect. This regression was introduced when the offtrack calculation switched from 2D to 3D.
2025-10-15 17:03:14 -04:00
Ramon Roche 09eda9ed3f ci: pull emscripten v4.0.15 to avoid c++17 errors (#25739)
https://github.com/emscripten-core/emscripten/issues/24850

Signed-off-by: Ramon Roche <mrpollo@gmail.com>
2025-10-15 12:26:27 -04:00
Peter van der Perk b4aeee5099 fmu-v6xrt: Enable lis2dml and bmm350 magnetometer 2025-10-15 11:15:46 -04:00
Peter van der Perk 4c02f799aa fmu-v6xrt: Add V6XRT001 and V6XRT002 sensor set 2025-10-15 11:15:46 -04:00
Hamish Willee 762a4189c5 [v1.16 backport] Enable clean URLs in VitePress config (#25759)
* [v1.16 backport] Enable clean URLs in VitePress config

* Remove the front page warning that only belongs on main
2025-10-14 16:51:14 -08:00
Liu1 9f27676c55 cuav_7-nano:use new sensors (#25098) (#25546) 2025-10-13 20:58:59 -08:00
Jacob Dahl 089887f232 mavlink: add message spacing for AVAILABLE_MODES, for low bandwidth (#25662)
* mavlink: add message spacing for AVAILABLE_MODES, for low bandwidth links

* calculate delay based on rate

* fixed transmit time calc & not delay single mode send



---------

Co-authored-by: Alexander Lerach <alexander@auterion.com>
Co-authored-by: bkueng <beat-kueng@gmx.net>
2025-10-01 13:25:27 -08:00
Jacob Dahl 2574e03cb2 uavcan: esc: init msg to avoid publishing random values (#25656) 2025-10-01 13:24:30 -08:00
Hamish Willee 2cbfe76308 AWS docs deployment - add back paths revert runner (#25690)
* AWS docs deployment - add back paths rever t runner

* touch doc
2025-10-01 15:27:41 +10:00
Hamish Willee f2b630256a AWS docs deployment - revert runs-on from ubuntu for test (#25689) 2025-10-01 15:04:03 +10:00
Hamish Willee 7008112da8 Update GitHub Actions output setting syntax to use envfile (#25687) 2025-10-01 14:28:50 +10:00
Hamish Willee 1aa783dc8b Change runner to ubuntu-latest for deployment (#25686)
* Change runner to ubuntu-latest for deployment

* Add actions permission to docs deployment workflow
2025-10-01 13:48:25 +10:00
Ramon Roche 81d97cc81d docs: fix deploy variables (#25685)
* ci: docs try again

Signed-off-by: Ramon Roche <mrpollo@gmail.com>

* ci: try to fix docs deploy syntax

Signed-off-by: Ramon Roche <mrpollo@gmail.com>

* ci: test for main and release/1.16

Signed-off-by: Ramon Roche <mrpollo@gmail.com>

---------

Signed-off-by: Ramon Roche <mrpollo@gmail.com>
2025-10-01 12:30:51 +10:00
Ramon Roche 12601ac1c4 ci: docs deploy branchname for build step (#25684)
Signed-off-by: Ramon Roche <mrpollo@gmail.com>
2025-10-01 12:08:43 +10:00
Hamish Willee c3b5a83d3e Restore to nearly working 2025-10-01 11:13:44 +10:00
Hamish Willee 767a765ddd Trigger v1.16 docs build 3 (#25682) 2025-10-01 11:05:06 +10:00
Hamish Willee 939ff4002d Update AWS deployment workflow for documentation 2025-10-01 11:01:48 +10:00
Hamish Willee 777dbe2926 Refactor AWS docs deployment workflow 2025-10-01 10:57:40 +10:00
Hamish Willee 835dac80c6 Trigger v1.16 docs build (#25681)
Removed an unnecessary line break in the index guide.
2025-10-01 10:49:54 +10:00
Hamish Willee 80f163760e Log BRANCH_NAME during VitePress build step 2025-10-01 10:38:42 +10:00
Hamish Willee 150757c43b Add debug step for manual workflow runs
Added a debug step to print environment variables during manual runs.
2025-10-01 10:31:09 +10:00
Hamish Willee a03386316f Fix up v1.16 docs version. Trigger docs build. Undo deploy by default to github (#25679) 2025-10-01 09:27:58 +10:00
Hamish Willee 0cc68650e9 AWS docs deploy workflow - modify release branch to same form (#25678)
Added a step to derive the branch name for deployment.
2025-10-01 08:25:02 +10:00
Ramon Roche ac5ed50b37 [backport] macos ci fixes for v1.16 (#25672)
* ci: lockdown gcc v9 for macos

Signed-off-by: Ramon Roche <mrpollo@gmail.com>

* pxh: do not use variable sized array on the stack

This is a compiler-specific extension

* ci: macos build on older gcc

Signed-off-by: Ramon Roche <mrpollo@gmail.com>

---------

Signed-off-by: Ramon Roche <mrpollo@gmail.com>
Co-authored-by: Beat Küng <beat-kueng@gmx.net>
2025-09-30 13:49:26 -08:00
Jacob Dahl 1c181fa8ec disable CONFIG_MODULES_VTOL_ATT_CONTROL on encrypted_logs target 2025-09-28 11:34:07 -06:00
Alex Klimaj 72d99c7214 [backport] boards: ark_fpv add vtol att control 2025-09-28 11:34:07 -06:00
Hamish Willee 23c49a2095 Fix formatting to trigger v1.16 release build for testing (#25643) 2025-09-26 08:44:34 +10:00
Hamish Willee 575514e6a1 Docs deploy AWS to v1.16 branch (#25641) 2025-09-26 07:50:27 +10:00
Hamish Willee 69bea3a3af [Docs] PX4 v1.16 Add warning for RTL mode issues in return.md (#25623)
* [Docs] PX4 v1.16 Add warning for RTL mode issues in return.md

Added a warning about known issues with RTL mode during fixed-wing approaches and landings.

* Apply suggestion from @hamishwillee

* Apply suggestion from @hamishwillee
2025-09-26 06:41:42 +10:00
Daniel Agar 5d6d973549 commander: accel cal rotate offsets and scales from body frame back into sensor frame before saving (#25626) (#25639)
- fixes https://github.com/PX4/PX4-Autopilot/issues/25606

Co-authored-by: Jacob Dahl <37091262+dakejahl@users.noreply.github.com>
2025-09-25 10:33:14 -08:00
Hamish Willee 26cb1aafb3 [v1.16] Add relnote etc 2025-08-07 15:04:20 +10:00
Eric Katzfey 21c3732e09 VOXL2: Updated startup script to patch EKF2_EV_CTRL set default value issue 2025-08-06 10:14:14 -07:00
Sandesh Sharma 61079bd08b fix: let UXRCE DDS agent IP to be set via parameter in SITL (#25231)
* Read XRCE_DDS IP from ENV

* just remove the -h flag from the launch command

* add 127.0.0.1 as default IP

* add default value for IP
2025-08-06 08:20:43 -07:00
Ramon Roche 6ea3539157 [backport] v1.16 fix gazebo install on ROS integration tests (#25344)
* ci: update rosdistro apt keys (#25060)

Signed-off-by: Ramon Roche <mrpollo@gmail.com>

* ci: use release/1.16 branch for px4-ros2-interface-lib integration tests

---------

Signed-off-by: Ramon Roche <mrpollo@gmail.com>
Co-authored-by: Beat Küng <beat-kueng@gmx.net>
2025-08-05 14:54:48 -08:00
Vasily 7fc5393afc Update px4-rc.gzsim. Fix gz_world checking for PX4_GZ_STANDALONE=1 mode. Priority of gz_world (really running) over PX4_GZ_WORLD (#25346) 2025-08-01 01:14:09 -08:00
Mahima Yoga 740521ae08 MC PositionControl: Add timeout for invalid TrajectorySetpoint (#25283) (#25341)
* MulticopterPositionControl: Add timeout before triggering emergency setpoint on invalid TrajectorySetpoint

* Apply suggestions from code review



* Cleanup & address review comments

* Safegaurd against using old setpoint if states aren't valid anymore

---------

Co-authored-by: Jacob Dahl <37091262+dakejahl@users.noreply.github.com>
2025-07-30 10:21:17 -08:00
PX4BuildBot aa745f2949 [1.16 backport] MAV_CMD_DO_SET_MODE - add support 2025-07-30 13:36:14 +10:00
Jacob Dahl 0294b608d3 [BACKPORT 1.16] ark: fpv: enable PAYLOAD_DELIVERER (#25323)
* payload deliverer: remove PD_GRIPPER_EN as unnecessary, reduce gripper timeout to 1s

* ark: fpv: enable payload deliverer module
2025-07-28 14:13:00 -06:00
Jacob Dahl 2471afd423 payload deliverer: remove PD_GRIPPER_EN as unnecessary, reduce gripper timeout to 1s 2025-07-28 12:08:15 -08:00
Jacob Dahl aab5ed8e0d ark: v6x: enable payload deliverer 2025-07-28 12:08:15 -08:00
Jacob Dahl 2902bea299 ark: v6x: encrypted: remove FW and VTOL modules to save flash (#25320) 2025-07-28 13:46:31 -06:00
Jacob Dahl 171d2c98ef ark_fpv: flash savings: remove FW and VTOL from encrypted_logs.px4board (#25321) 2025-07-28 11:45:06 -08:00
Matthias Grob af99ebce81 commander failsafe: never override user intended termination + unit test 2025-07-28 13:38:57 +02:00
Jacob Dahl b67c65bfe6 dshot: fix bidirectional dshot stream sharing (#24996)
Freeing the DMA stream in the hrt callback causes other peripherals on that DMA controller to lock up (namely GPS). Moving the free back into thread context, right before allocation, solves the problem
2025-07-09 12:19:24 -06:00
Jacob Dahl e3fecd96d5 dshot: fix scaling (#25001) 2025-07-09 12:19:24 -06:00
Jacob Dahl f244b4835b dshot: add perf counter for hrt callback (15us avg) (#24976) 2025-07-09 12:19:24 -06:00
Jacob Dahl 4858a20dfa ark_fpv: cleanup board_dma_map.h (#24975) 2025-07-09 12:19:24 -06:00
64 changed files with 740 additions and 354 deletions
+5 -2
View File
@@ -16,7 +16,7 @@ on:
jobs:
build:
runs-on: macos-latest
runs-on: macos-14
strategy:
matrix:
config: [
@@ -32,7 +32,8 @@ jobs:
- uses: actions/checkout@v4
- name: setup
run: ./Tools/setup/macos.sh; ./Tools/setup/macos.sh
run: |
./Tools/setup/macos.sh
- name: Prepare ccache timestamp
id: ccache_cache_timestamp
@@ -40,12 +41,14 @@ jobs:
run: |
string(TIMESTAMP current_date "%Y-%m-%d-%H;%M;%S" UTC)
message("::set-output name=timestamp::${current_date}")
- name: ccache cache files
uses: actions/cache@v4
with:
path: ~/.ccache
key: macos_${{matrix.config}}-ccache-${{steps.ccache_cache_timestamp.outputs.timestamp}}
restore-keys: macos_${{matrix.config}}-ccache-
- name: setup ccache
run: |
mkdir -p ~/.ccache
-12
View File
@@ -1,18 +1,6 @@
name: Docs - Deploy PX4 User Guide
on:
push:
branches:
- 'main'
- 'release/**'
paths:
- 'docs/en/**'
pull_request:
branches:
- '**'
paths:
- 'docs/en/**'
# Allows you to run this workflow manually from the Actions tab
workflow_dispatch:
+114
View File
@@ -0,0 +1,114 @@
name: Docs - Deploy PX4 User Guide to AWS
on:
push:
branches:
- "main"
- "release/**"
paths:
- "docs/en/**"
- "docs/zh/**"
- "docs/uk/**"
- "docs/ko/**"
pull_request:
paths:
- "docs/en/**"
- "docs/zh/**"
- "docs/uk/**"
- "docs/ko/**"
permissions:
contents: read
actions: read
id-token: write # for AWS OIDC
concurrency:
group: docs-deploy
cancel-in-progress: false
jobs:
build:
runs-on: [runs-on,runner=8cpu-linux-x64,image=ubuntu24-full-x64,"run-id=${{ github.run_id }}",spot=false,extras=s3-cache]
outputs:
branchname: ${{ steps.set-branch.outputs.branchname }}
releaseversion: ${{ steps.set-version.outputs.releaseversion }}
steps:
- uses: runs-on/action@v1
- name: Checkout
uses: actions/checkout@v4
- id: set-branch
run: echo "branchname=${GITHUB_HEAD_REF:-${GITHUB_REF#refs/heads/}}" >> $GITHUB_OUTPUT
- id: set-version
run: |
branch="${{ steps.set-branch.outputs.branchname }}"
if [[ "$branch" == "main" ]]; then
version="main"
else
version="v${branch#release/}"
fi
echo "releaseversion=$version" >> $GITHUB_OUTPUT
- name: Setup Node
uses: actions/setup-node@v4
with:
node-version: 20
cache: npm
cache-dependency-path: ./docs/yarn.lock
- name: Install dependencies
run: yarn install --frozen-lockfile --cwd ./docs
- name: Build with VitePress
working-directory: ./docs
env:
BRANCH_NAME: ${{ steps.set-version.outputs.releaseversion }}
run: |
npm run docs:build_ubuntu
touch .vitepress/dist/.nojekyll
npm run docs:sitemap
- name: Upload artifact
if: ${{ github.event_name == 'push' || (github.event_name == 'pull_request' && github.event.pull_request.merged) || github.event_name == 'workflow_dispatch' }}
uses: actions/upload-artifact@v4
with:
name: px4_docs_build
path: docs/.vitepress/dist/
retention-days: 1
deploy:
if: ${{ github.event_name == 'push' || (github.event_name == 'pull_request' && github.event.pull_request.merged) || github.event_name == 'workflow_dispatch' }}
needs: build
runs-on: ubuntu-latest
steps:
- name: Download Artifact
uses: actions/download-artifact@v4
with:
name: px4_docs_build
path: ~/_book
- name: Configure AWS from OIDC
uses: aws-actions/configure-aws-credentials@v4
with:
role-to-assume: ${{ secrets.AWS_ROLE_ARN }}
aws-region: us-west-2
- name: Sanity check AWS credentials
run: aws sts get-caller-identity
- name: Upload HTML with short cache
run: |
aws s3 sync ~/_book/ s3://px4-docs/${{ needs.build.outputs.releaseversion }}/ \
--delete \
--exclude "*" --include "*.html" \
--cache-control "public, max-age=60"
- name: Upload assets with long cache
run: |
aws s3 sync ~/_book/ s3://px4-docs/${{ needs.build.outputs.releaseversion }}/ \
--delete \
--exclude "*.html" \
--cache-control "public, max-age=86400, immutable"
+1
View File
@@ -43,6 +43,7 @@ jobs:
run: |
git clone https://github.com/emscripten-core/emsdk.git _emscripten_sdk
cd _emscripten_sdk
git checkout 4.0.15
./emsdk install latest
./emsdk activate latest
+7 -3
View File
@@ -11,13 +11,11 @@ on:
- 'main'
paths-ignore:
- 'docs/**'
- '.github/**'
pull_request:
branches:
- '**'
paths-ignore:
- 'docs/**'
- '.github/**'
jobs:
build:
@@ -33,6 +31,12 @@ jobs:
- name: Git Ownership Workaround
run: git config --system --add safe.directory '*'
- name: Update ROS Keys
run: |
sudo rm /etc/apt/sources.list.d/ros2.list && \
sudo curl -sSL https://raw.githubusercontent.com/ros/rosdistro/master/ros.key -o /usr/share/keyrings/ros-archive-keyring.gpg && \
echo "deb [arch=$(dpkg --print-architecture) signed-by=/usr/share/keyrings/ros-archive-keyring.gpg] http://packages.ros.org/ros2/ubuntu $(. /etc/os-release && echo $UBUNTU_CODENAME) main" | sudo tee /etc/apt/sources.list.d/ros2.list > /dev/null
- name: Install gazebo
run: |
apt update && apt install -y gazebo11 libgazebo11-dev gstreamer1.0-plugins-bad gstreamer1.0-plugins-base gstreamer1.0-plugins-good gstreamer1.0-plugins-ugly libgstreamer-plugins-base1.0-dev
@@ -81,7 +85,7 @@ jobs:
. /opt/ros/galactic/setup.bash
mkdir -p /opt/px4_ws/src
cd /opt/px4_ws/src
git clone --recursive https://github.com/Auterion/px4-ros2-interface-lib.git
git clone --recursive --branch release/1.16 https://github.com/Auterion/px4-ros2-interface-lib.git
cd ..
# Copy messages to ROS workspace
"${PX4_DIR}/Tools/copy_to_ros_ws.sh" "$(pwd)"
+13 -2
View File
@@ -28,11 +28,15 @@ else
exit 1
fi
# Look for an already running world
get_gz_world() {
gz_world=$( ${gz_command} topic -l | grep -m 1 -e "^/world/.*/clock" | sed 's/\/world\///g; s/\/clock//g' )
}
# If not standalone
if [ -z "${PX4_GZ_STANDALONE}" ]; then
# Look for an already running world
gz_world=$( ${gz_command} topic -l | grep -m 1 -e "^/world/.*/clock" | sed 's/\/world\///g; s/\/clock//g' )
get_gz_world
# shellcheck disable=SC2153
if [ -z "${gz_world}" ] && [ -n "${PX4_GZ_WORLD}" ]; then
@@ -66,6 +70,13 @@ fi
# Wait for Gazebo world to be ready before proceeding
check_scene_info() {
get_gz_world
if [ -n "${PX4_GZ_STANDALONE}" ] && [ -n "${gz_world}" ]; then
PX4_GZ_WORLD=${gz_world}
fi
SERVICE_INFO=$(${gz_command} service -i --service "/world/${PX4_GZ_WORLD}/scene/info" 2>&1)
if echo "$SERVICE_INFO" | grep -q "Service providers"; then
return 0
+5 -6
View File
@@ -190,6 +190,9 @@ param set-default SYS_FAILURE_EN 1
# does not go below 50% by default, but failure injection can trigger failsafes.
param set-default COM_LOW_BAT_ACT 3
# set default IP to localhost
param set-default UXRCE_DDS_AG_IP 2130706433 # 127.0.0.1
# Adapt timeout parameters if simulation runs faster or slower than realtime.
if [ -n "$PX4_SIM_SPEED_FACTOR" ]; then
@@ -314,7 +317,7 @@ then
uxrce_dds_port="$PX4_UXRCE_DDS_PORT"
fi
uxrce_dds_client start -t udp -h 127.0.0.1 -p $uxrce_dds_port $uxrce_dds_ns
uxrce_dds_client start -t udp -p $uxrce_dds_port $uxrce_dds_ns
if param greater -s MNT_MODE_IN -1
then
@@ -337,11 +340,7 @@ then
gyro_calibration start
fi
# Payload deliverer module if gripper is enabled
if param compare -s PD_GRIPPER_EN 1
then
payload_deliverer start
fi
payload_deliverer start
if param compare -s ICE_EN 1
then
+1 -5
View File
@@ -560,11 +560,7 @@ else
px4flow start -X &
fi
# Payload deliverer module if gripper is enabled
if param compare -s PD_GRIPPER_EN 1
then
payload_deliverer start
fi
payload_deliverer start
if param compare -s ICE_EN 1
then
+2
View File
@@ -42,6 +42,8 @@ else
echo "Installing PX4 general dependencies (homebrew px4-dev)"
brew tap PX4/px4
brew install px4-dev
# lock down gcc to v9 for v1.16 branch
brew install gcc-arm-none-eabi
brew install ncurses
brew install python-tk
fi
+1
View File
@@ -76,6 +76,7 @@ CONFIG_MODULES_MC_POS_CONTROL=y
CONFIG_MODULES_MC_RATE_CONTROL=y
CONFIG_MODULES_NAVIGATOR=y
CONFIG_NUM_MISSION_ITMES_SUPPORTED=1000
CONFIG_MODULES_PAYLOAD_DELIVERER=y
CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_ROVER_POS_CONTROL=y
CONFIG_MODULES_SENSORS=y
@@ -6,3 +6,8 @@ CONFIG_DRIVERS_SW_CRYPTO=y
# CONFIG_EKF2_AUX_GLOBAL_POSITION is not set
CONFIG_PUBLIC_KEY0="../../../Tools/test_keys/key0.pub"
CONFIG_PUBLIC_KEY1="../../../Tools/test_keys/rsa2048.pub"
CONFIG_MODULES_FW_ATT_CONTROL=n
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=n
CONFIG_MODULES_FW_POS_CONTROL=n
CONFIG_MODULES_FW_RATE_CONTROL=n
CONFIG_MODULES_VTOL_ATT_CONTROL=n
+3
View File
@@ -56,9 +56,12 @@ CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y
CONFIG_MODULES_MC_POS_CONTROL=y
CONFIG_MODULES_MC_RATE_CONTROL=y
CONFIG_MODULES_NAVIGATOR=y
CONFIG_MODULES_PAYLOAD_DELIVERER=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
+5
View File
@@ -5,3 +5,8 @@ CONFIG_DRIVERS_SW_CRYPTO=y
# CONFIG_EKF2_AUX_GLOBAL_POSITION is not set
CONFIG_PUBLIC_KEY0="../../../Tools/test_keys/key0.pub"
CONFIG_PUBLIC_KEY1="../../../Tools/test_keys/rsa2048.pub"
CONFIG_MODULES_FW_ATT_CONTROL=n
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=n
CONFIG_MODULES_FW_POS_CONTROL=n
CONFIG_MODULES_FW_RATE_CONTROL=n
CONFIG_MODULES_VTOL_ATT_CONTROL=n
@@ -34,75 +34,25 @@
#pragma once
// DMAMUX1 Using at most 8 Channels on DMA1 -------- Assigned
// V
// Timer 4 Channel 1 /* DMA1:29 TIM4CH1 */
#define DMAMAP_SPI1_RX DMAMAP_DMA12_SPI1RX_0 /* 1 DMA1:37 IIM-42653 */
#define DMAMAP_SPI1_TX DMAMAP_DMA12_SPI1TX_0 /* 2 DMA1:38 IIM-42653 */
//#define DMAMAP_SPI2_RX DMAMAP_DMA12_SPI2RX_0 /* 3 DMA1:39 ICM-42688-P */
//#define DMAMAP_SPI2_TX DMAMAP_DMA12_SPI2TX_0 /* 4 DMA1:40 ICM-42688-P */
#define DMAMAP_USART1_RX DMAMAP_DMA12_USART1RX_0 /* DMA1:41 GPS1 */
#define DMAMAP_USART1_TX DMAMAP_DMA12_USART1TX_0 /* DMA1:42 GPS1 */
//#define DMAMAP_USART3_RX DMAMAP_DMA12_USART3RX_0 /* DMA1:45 DEBUG */
//#define DMAMAP_USART3_TX DMAMAP_DMA12_USART3TX_0 /* DMA1:46 DEBUG */
// Timer 8 Channel 1 /* DMA1:47 TIM8CH1 */
// Timer 8 Channel 2 /* DMA1:48 TIM8CH2 */
// Timer 8 Channel 3 /* DMA1:49 TIM8CH3 */
// Timer 8 Channel 4 /* DMA1:50 TIM8CH4 */
// Timer 5 Channel 1 /* DMA1:55 TIM5CH1 */
// Timer 5 Channel 2 /* DMA1:56 TIM5CH2 */
// Timer 5 Channel 3 /* DMA1:57 TIM5CH3 */
// Timer 5 Channel 4 /* DMA1:58 TIM5CH4 */
// #define DMAMAP_UART4_RX DMAMAP_DMA12_UART4RX_0 /* DMA1:63 UART4 */
// #define DMAMAP_UART4_TX DMAMAP_DMA12_UART4TX_0 /* DMA1:64 UART4 */
#define DMAMAP_USART6_RX DMAMAP_DMA12_USART6RX_0 /* 5 DMA1:71 RC */
// #define DMAMAP_USART6_TX DMAMAP_DMA12_USART6TX_0 /* 6 DMA1:72 RC */
// Assigned in timer_config.cpp
// Timer 4 /* 7 DMA1:32 TIM4UP */
// Timer 5 /* 8 DMA1:50 TIM5UP */
#define DMAMAP_SPI1_RX DMAMAP_DMA12_SPI1RX_0 // 1 DMA1:37 IIM-42653
#define DMAMAP_SPI1_TX DMAMAP_DMA12_SPI1TX_0 // 2 DMA1:38 IIM-42653
#define DMAMAP_USART1_RX DMAMAP_DMA12_USART1RX_0 // 3 DMA1:41 GPS1
#define DMAMAP_USART1_TX DMAMAP_DMA12_USART1TX_0 // 4 DMA1:42 GPS1
#define DMAMAP_USART6_RX DMAMAP_DMA12_USART6RX_0 // 5 DMA1:71 RC
#define DMAMAP_USART6_TX DMAMAP_DMA12_USART6TX_0 // 6 DMA1:72 RC
// Timer 4 (DMAMAP_DMA12_TIM4UP_0) // 7 DMA1:32 TIM4UP/TIM4CH1-4
// Timer 5 (DMAMAP_DMA12_TIM5UP_0) // 8 DMA1:50 TIM5UP/TIM5CH1-4
// DMAMUX2 Using at most 8 Channels on DMA2 -------- Assigned
// V
// Timer 4 Channel 1 /* DMA2:29 TIM4CH1 */
#define DMAMAP_USART2_RX DMAMAP_DMA12_USART2RX_1 /* 3 DMA2:43 TELEM3 */
#define DMAMAP_USART2_TX DMAMAP_DMA12_USART2TX_1 /* 4 DMA2:44 TELEM3 */
#define DMAMAP_USART3_RX DMAMAP_DMA12_USART3RX_1 /* 3 DMA2:45 DEBUG */
#define DMAMAP_USART3_TX DMAMAP_DMA12_USART3TX_1 /* 4 DMA2:46 DEBUG */
// Timer 8 Channel 1 /* DMA2:47 TIM8CH1 */
// Timer 8 Channel 2 /* DMA2:48 TIM8CH2 */
// Timer 8 Channel 3 /* DMA2:49 TIM8CH3 */
// Timer 8 Channel 4 /* DMA2:50 TIM8CH4 */
// Timer 5 Channel 1 /* DMA2:55 TIM5CH1 */
// Timer 5 Channel 2 /* DMA2:56 TIM5CH2 */
// Timer 5 Channel 3 /* DMA2:57 TIM5CH3 */
// Timer 5 Channel 4 /* DMA2:58 TIM5CH4 */
//#define DMAMAP_SPI3_RX DMAMAP_DMA12_SPI3RX_1 /* 1 DMA2:61 BMI088 */
//#define DMAMAP_SPI3_TX DMAMAP_DMA12_SPI3TX_1 /* 2 DMA2:62 BMI088 */
#define DMAMAP_UART5_RX DMAMAP_DMA12_UART5RX_1 /* 5 DMA2:65 TELEM2 */
#define DMAMAP_UART5_TX DMAMAP_DMA12_UART5TX_1 /* 6 DMA2:66 TELEM2 */
#define DMAMAP_UART7_RX DMAMAP_DMA12_UART7RX_1 /* 7 DMA1:79 TELEM1 */
#define DMAMAP_UART7_TX DMAMAP_DMA12_UART7TX_1 /* 8 DMA1:80 TELEM1 */
#define DMAMAP_USART2_RX DMAMAP_DMA12_USART2RX_1 // 1 DMA2:43 VTX
#define DMAMAP_UART5_RX DMAMAP_DMA12_UART5RX_1 // 2 DMA2:65 VTX
#define DMAMAP_UART5_TX DMAMAP_DMA12_UART5TX_1 // 3 DMA2:66 VTX
#define DMAMAP_UART7_RX DMAMAP_DMA12_UART7RX_1 // 4 DMA2:79 TELEM1
#define DMAMAP_UART7_TX DMAMAP_DMA12_UART7TX_1 // 5 DMA2:80 TELEM1
#define DMAMAP_USART3_RX DMAMAP_DMA12_USART3RX_1 // 6 DMA2:45 DEBUG
#define DMAMAP_USART3_TX DMAMAP_DMA12_USART3TX_1 // 7 DMA2:46 DEBUG
// available
// DMAMUX2 Using at most 8 Channels on BDMA -------- Assigned
// V
#define DMAMAP_SPI6_RX DMAMAP_BDMA_SPI6_RX /* 1 BDMA:11 SPI J11 */
#define DMAMAP_SPI6_TX DMAMAP_BDMA_SPI6_TX /* 2 BDMA:12 SPI J11 */
#define DMAMAP_SPI6_RX DMAMAP_BDMA_SPI6_RX // 1 BDMA:11 SPI J11
#define DMAMAP_SPI6_TX DMAMAP_BDMA_SPI6_TX // 2 BDMA:12 SPI J11
+1 -2
View File
@@ -260,8 +260,6 @@ CONFIG_USART1_TXDMA=y
CONFIG_USART2_BAUD=57600
CONFIG_USART2_RXBUFSIZE=600
CONFIG_USART2_RXDMA=y
CONFIG_USART2_TXBUFSIZE=1500
CONFIG_USART2_TXDMA=y
CONFIG_USART3_BAUD=57600
CONFIG_USART3_RXBUFSIZE=180
CONFIG_USART3_RXDMA=y
@@ -272,6 +270,7 @@ CONFIG_USART6_BAUD=57600
CONFIG_USART6_RXBUFSIZE=600
CONFIG_USART6_RXDMA=y
CONFIG_USART6_TXBUFSIZE=1500
CONFIG_USART6_TXDMA=y
CONFIG_USBDEV=y
CONFIG_USBDEV_BUSPOWERED=y
CONFIG_USBDEV_MAXPOWER=500
+1
View File
@@ -20,6 +20,7 @@ CONFIG_DRIVERS_GPS=y
CONFIG_DRIVERS_IMU_BOSCH_BMI088=y
CONFIG_DRIVERS_IMU_INVENSENSE_ICM20948=y
CONFIG_DRIVERS_IMU_INVENSENSE_IIM42652=y
CONFIG_DRIVERS_IMU_INVENSENSE_IIM42653=y
CONFIG_COMMON_INS=y
CONFIG_COMMON_LIGHT=y
CONFIG_COMMON_MAGNETOMETER=y
+10 -3
View File
@@ -12,10 +12,17 @@ else
fi
iim42652 -s -R 22 start
bmi088 -A -R 29 -s start
bmi088 -G -R 29 -s start
ist8310 -I -R 18 start
bmi088 -A -R 29 -s start
if ! bmi088 -G -R 29 -s start
then
iim42653 -s -b 2 -R 22 start
fi
if ! ist8310 -I -R 18 start
then
iis2mdc -I -R 37 start
fi
bmp581 -s start
icp201xx -I start
+1
View File
@@ -42,6 +42,7 @@ constexpr px4_spi_bus_t px4_spi_buses[SPI_BUS_MAX_BUS_ITEMS] = {
initSPIBus(SPI::Bus::SPI2, {
initSPIDevice(DRV_GYR_DEVTYPE_BMI088, SPI::CS{GPIO::PortG, GPIO::Pin2}, SPI::DRDY{GPIO::PortG, GPIO::Pin3}),
initSPIDevice(DRV_ACC_DEVTYPE_BMI088, SPI::CS{GPIO::PortH, GPIO::Pin5}, SPI::DRDY{GPIO::PortA, GPIO::Pin10}),
initSPIDevice(DRV_IMU_DEVTYPE_IIM42653, SPI::CS{GPIO::PortD, GPIO::Pin12}, SPI::DRDY{GPIO::PortA, GPIO::Pin10}),
}, {GPIO::PortI, GPIO::Pin11}),
// initSPIBus(SPI::Bus::SPI3,{
// // no devices
+9 -2
View File
@@ -59,12 +59,19 @@ fi
param select /data/px4/param/parameters
# Load in all of the parameters that have been saved in the file
param load
# Change defaults before loading in updated parameters from the file
# This was the default pre-v1.16.0 and for folks relying on that
# we set it up here
param set-default EKF2_EV_CTRL 15
# Shouldn't need to do it separately with qshell but set-default
# implementation needs to be updated to set it on DSP as well. Until
# then need to do it as a separate step.
qshell param set-default EKF2_EV_CTRL 15
# Load in all of the parameters that have been saved in the file
# after updating any default values
param load
# IMU (accelerometer / gyroscope)
if [ "$PLATFORM" == "M0104" ]; then
+2
View File
@@ -32,6 +32,8 @@ CONFIG_DRIVERS_IMU_INVENSENSE_IIM42652=y
CONFIG_COMMON_INS=y
CONFIG_COMMON_LIGHT=y
CONFIG_COMMON_MAGNETOMETER=y
CONFIG_DRIVERS_MAGNETOMETER_BOSCH_BMM350=y
CONFIG_DRIVERS_MAGNETOMETER_LIS2MDL=y
CONFIG_DRIVERS_OSD_MSP_OSD=y
CONFIG_DRIVERS_POWER_MONITOR_INA226=y
CONFIG_DRIVERS_POWER_MONITOR_INA228=y
+33 -9
View File
@@ -85,19 +85,43 @@ else
fi
fi
# Internal SPI bus ICM42686p (hard-mounted)
icm42688p -6 -R 12 -b 1 -s start
if ver hwtypecmp V6XRT000 V6XRT001
then
# Internal SPI bus ICM42686p (hard-mounted)
icm42688p -6 -R 12 -b 1 -s start
# Internal on IMU SPI BMI088
bmi088 -A -R 4 -s start
bmi088 -G -R 4 -s start
# Internal on IMU SPI BMI088
bmi088 -A -R 4 -s start
bmi088 -G -R 4 -s start
# Internal on IMU SPI bus ICM42688p
icm42688p -R 6 -b 2 -s start
# Internal on IMU SPI bus ICM42688p
icm42688p -R 6 -b 2 -s start
fi
# Internal magnetometer on I2c
bmm150 -I start
if ver hwtypecmp V6XRT002
then
# Internal SPI bus icm45686 (hard-mounted)
icm45686 -R 12 -b 1 -s start
# Internal on IMU SPI BMI088
bmi088 -A -R 4 -s start
bmi088 -G -R 4 -s start
# Internal on IMU SPI bus icm45686
icm45686 -R 6 -b 2 -s start
fi
if ver hwtypecmp V6XRT000
then
# Internal magnetometer on I2c
bmm150 -I start
fi
if ver hwtypecmp V6XRT001 V6XRT002
then
# Internal magnetometer on I2c
bmm350 -I start
fi
# External compass on GPS1/I2C1 (the 3rd external bus): standard Holybro Pixhawk 4 or CUAV V5 GPS/compass puck (with lights, safety button, and buzzer)
ist8310 -X -b 1 -R 10 start
+2 -1
View File
@@ -297,9 +297,10 @@
#define GPIO_HW_VER_SENSE /* GPIO_AD_23 GPIO9 Pin 22 */ ADC_GPIO(5, 22)
#define HW_INFO_INIT_PREFIX "V6XRT"
#define BOARD_NUM_SPI_CFG_HW_VERSIONS 2 // Rev 0 & 1
#define BOARD_NUM_SPI_CFG_HW_VERSIONS 3 // Rev 0, 1 & 2
#define V6XRT_0 HW_FMUM_ID(0x0) // First Release
#define V6XRT_1 HW_FMUM_ID(0x1) // Next Release
#define V6XRT_2 HW_FMUM_ID(0x2) // Next Release
#define BOARD_I2C_LATEINIT 1 /* See Note about SE550 Eanable */
+20
View File
@@ -81,6 +81,26 @@ constexpr px4_spi_bus_all_hw_t px4_spi_buses_all_hw[BOARD_NUM_SPI_CFG_HW_VERSION
initSPIConfigExternal(SPI::CS{GPIO::Port6, GPIO::Pin8}, SPI::DRDY{GPIO::Port1, GPIO::Pin7}), /* GPIO_LPSR_08 GPIO6_IO08 GPIO_EMC_B1_07 GPIO1_IO07*/
}),
}),
initSPIFmumID(V6XRT_2, {
initSPIBus(SPI::Bus::LPSPI1, {
initSPIDevice(DRV_IMU_DEVTYPE_ICM45686, SPI::CS{GPIO::Port2, GPIO::Pin11}, SPI::DRDY{GPIO::Port3, GPIO::Pin19}), /* GPIO_EMC_B2_01 GPIO2_IO11, GPIO_AD_20, GPIO3_IO19 */
}, {GPIO::Port2, GPIO::Pin1}), // Power GPIO_EMC_B1_33 GPIO2_IO01
initSPIBus(SPI::Bus::LPSPI2, {
initSPIDevice(DRV_IMU_DEVTYPE_ICM45686, SPI::CS{GPIO::Port3, GPIO::Pin24}, SPI::DRDY{GPIO::Port2, GPIO::Pin7}), /* GPIO_AD_25 GPIO3_IO24, GPIO_EMC_B1_39 GPIO2_IO07 */
}, {GPIO::Port1, GPIO::Pin22}), // Power GPIO_EMC_B1_22 GPIO1_IO22
initSPIBus(SPI::Bus::LPSPI3, {
initSPIDevice(DRV_GYR_DEVTYPE_BMI088, SPI::CS{GPIO::Port2, GPIO::Pin18}, SPI::DRDY{GPIO::Port2, GPIO::Pin28}), /* GPIO_EMC_B2_08 GPIO2_IO18, GPIO_EMC_B2_18 GPIO2_IO28 */
initSPIDevice(DRV_ACC_DEVTYPE_BMI088, SPI::CS{GPIO::Port2, GPIO::Pin15}), /* GPIO_EMC_B2_05 GPIO2_IO15 */
}, {GPIO::Port1, GPIO::Pin14}), // Power GPIO_EMC_B1_14 GPIO1_IO14
initSPIBusExternal(SPI::Bus::LPSPI6, {
initSPIConfigExternal(SPI::CS{GPIO::Port6, GPIO::Pin9}, SPI::DRDY{GPIO::Port1, GPIO::Pin5}), /* GPIO_LPSR_09 GPIO6_IO09 GPIO_EMC_B1_05 GPIO1_IO05*/
initSPIConfigExternal(SPI::CS{GPIO::Port6, GPIO::Pin8}, SPI::DRDY{GPIO::Port1, GPIO::Pin7}), /* GPIO_LPSR_08 GPIO6_IO08 GPIO_EMC_B1_07 GPIO1_IO07*/
}),
}),
};
static constexpr bool unused = validateSPIConfig(px4_spi_buses_all_hw);
+7 -3
View File
@@ -8,7 +8,7 @@ import tabsPlugin from "@red-asuka/vitepress-plugin-tabs";
// https://vitepress.dev/reference/site-config
export default defineConfig({
title: "PX4 Guide (main)",
title: "PX4 Guide (v1.16)",
description: "PX4 User and Developer Guide",
base: process.env.BRANCH_NAME
? "/" + process.env.BRANCH_NAME + "/"
@@ -31,6 +31,7 @@ export default defineConfig({
tabsPlugin(md); //https://github.com/Red-Asuka/vitepress-plugin-tabs
},
},
cleanUrls: true,
vite: {
plugins: [
@@ -197,11 +198,14 @@ export default defineConfig({
text: "Version",
items: [
{ text: "main", link: "https://docs.px4.io/main/en/" },
{ text: "v1.15 (stable)", link: "https://docs.px4.io/v1.15/en/" },
{
text: "v1.16 (stable)",
link: "https://docs.px4.io/v1.16/en/",
},
{ text: "v1.15", link: "https://docs.px4.io/v1.15/en/" },
{ text: "v1.14", link: "https://docs.px4.io/v1.14/en/" },
{ text: "v1.13", link: "https://docs.px4.io/v1.13/en/" },
{ text: "v1.12", link: "https://docs.px4.io/v1.12/en/" },
{ text: "v1.11", link: "https://docs.px4.io/v1.11/en/" },
],
},
],
+4 -9
View File
@@ -1,9 +1,7 @@
- [Introduction](index.md)
- [Basic Concepts](getting_started/px4_basic_concepts.md)
- [Multicopters](frames_multicopter/index.md)
- [Features](features_mc/index.md)
- [Flight Modes](flight_modes_mc/index.md)
- [Position Mode (MC)](flight_modes_mc/position.md)
@@ -56,7 +54,6 @@
- [DJI F450 (CUAV v5 nano)](frames_multicopter/dji_f450_cuav_5nano.md)
- [Planes (Fixed-Wing)](frames_plane/index.md)
- [Assembly](assembly/assembly_fw.md)
- [Config/Tuning](config_fw/index.md)
- [Auto-tune](config/autotune_fw.md)
@@ -84,7 +81,6 @@
- [Wing Wing Z84 (Pixracer)](frames_plane/wing_wing_z84.md)
- [VTOL](frames_vtol/index.md)
- [Assembly](assembly/assembly_vtol.md)
- [VTOL Config/Tuning](config_vtol/index.md)
- [Auto-tune](config/autotune_vtol.md)
@@ -109,7 +105,6 @@
- [Complete Vehicles](complete_vehicles_vtol/index.md)
- [Operations](config/operations.md)
- [Safety](config/safety_intro.md)
- [Safety Configuration (Failsafes)](config/safety.md)
- [Failsafe Simulation](config/safety_simulation.md)
@@ -130,7 +125,6 @@
- [QGroundControl Flight-Readiness Status](flying/pre_flight_checks.md)
- [Hardware Selection & Setup](hardware/drone_parts.md)
- [Flight Controllers (Autopilots)](flight_controller/index.md)
- [Flight Controller Selection](getting_started/flight_controller_selection.md)
- [Pixhawk Series](flight_controller/pixhawk_series.md)
@@ -333,6 +327,7 @@
- [FrSky Telemetry](peripherals/frsky_telemetry.md)
- [TBS Crossfire (CRSF) Telemetry](telemetry/crsf_telemetry.md)
- [Satellite Comms (Iridium/RockBlock)](advanced_features/satcom_roadblock.md)
- [Power Systems](power_systems/index.md)
- [Battery Estimation Tuning](config/battery.md)
- [Battery Chemistry Overview](power_systems/battery_chemistry.md)
@@ -399,7 +394,6 @@
- [Full Parameter Reference](advanced_config/parameter_reference.md)
- [Other Vehicles](airframes/index.md)
- [Airships (experimental)](frames_airship/index.md)
- [Autogyros (experimental)](frames_autogyro/index.md)
- [ThunderFly Auto-G2 (Holybro pix32)](frames_autogyro/thunderfly_auto_g2.md)
@@ -841,8 +835,9 @@
- [Terminology/Notation](contribute/notation.md)
- [Licenses](contribute/licenses.md)
- [Releases](releases/index.md)
- [main (alpha)](releases/main.md)
- [1.15 (stable)](releases/1.15.md)
- [main (alpha)](https://docs.px4.io/main/en/releases/main.html)
- [1.16 (stable)](releases/1.15.md)
- [1.15](releases/1.15.md)
- [1.14](releases/1.14.md)
- [1.13](releases/1.13.md)
- [1.12](releases/1.12.md)
+14 -13
View File
@@ -1,10 +1,8 @@
<!-- GENERATED CONTENT: DO NOT EDIT -->
- [Introduction](/index.md)
- [Basic Concepts](/getting_started/px4_basic_concepts.md)
- [Multicopters](/frames_multicopter/index.md)
- [Features](/features_mc/index.md)
- [Flight Modes](/flight_modes_mc/index.md)
- [Position Mode (MC)](/flight_modes_mc/position.md)
@@ -57,7 +55,6 @@
- [DJI F450 (CUAV v5 nano)](/frames_multicopter/dji_f450_cuav_5nano.md)
- [Planes (Fixed-Wing)](/frames_plane/index.md)
- [Assembly](/assembly/assembly_fw.md)
- [Config/Tuning](/config_fw/index.md)
- [Auto-tune](/config/autotune_fw.md)
@@ -85,7 +82,6 @@
- [Wing Wing Z84 (Pixracer)](/frames_plane/wing_wing_z84.md)
- [VTOL](/frames_vtol/index.md)
- [Assembly](/assembly/assembly_vtol.md)
- [VTOL Config/Tuning](/config_vtol/index.md)
- [Auto-tune](/config/autotune_vtol.md)
@@ -110,7 +106,6 @@
- [Complete Vehicles](/complete_vehicles_vtol/index.md)
- [Operations](/config/operations.md)
- [Safety](/config/safety_intro.md)
- [Safety Configuration (Failsafes)](/config/safety.md)
- [Failsafe Simulation](/config/safety_simulation.md)
@@ -131,7 +126,6 @@
- [QGroundControl Flight-Readiness Status](/flying/pre_flight_checks.md)
- [Hardware Selection & Setup](/hardware/drone_parts.md)
- [Flight Controllers (Autopilots)](/flight_controller/index.md)
- [Flight Controller Selection](/getting_started/flight_controller_selection.md)
- [Pixhawk Series](/flight_controller/pixhawk_series.md)
@@ -166,7 +160,7 @@
- [AirMind MindPX](/flight_controller/mindpx.md)
- [AirMind MindRacer](/flight_controller/mindracer.md)
- [ARK Electronics ARKV6X](/flight_controller/ark_v6x.md)
- [ARK FPV Flight Controller](/flight_controller/ark_fpv.md)
- [ARK FPV Flight Controller](/flight_controller/ark_fpv.md)
- [ARK Pi6X Flow Flight Controller](/flight_controller/ark_pi6x.md)
- [CUAV X7](/flight_controller/cuav_x7.md)
- [CUAV Nora](/flight_controller/cuav_nora.md)
@@ -182,7 +176,7 @@
- [Holybro Kakute H7v2](/flight_controller/kakuteh7v2.md)
- [Holybro Kakute H7mini](/flight_controller/kakuteh7mini.md)
- [Holybro Kakute H7](/flight_controller/kakuteh7.md)
- [Holybro Kakute H7 Wing](flight_controller/kakuteh7-wing.md)
- [Holybro Kakute H7 Wing](/flight_controller/kakuteh7-wing.md)
- [Holybro Durandal](/flight_controller/durandal.md)
- [Wiring Quickstart](/assembly/quick_start_durandal.md)
- [Holybro Pix32 v5](/flight_controller/holybro_pix32_v5.md)
@@ -255,7 +249,7 @@
- [GNSS (GPS)](/gps_compass/index.md)
- [ARK GPS (CAN)](/dronecan/ark_gps.md)
- [ARK SAM GPS](/gps_compass/ark_sam_gps.md)
- [ARK TESEO GPS](/dronecan/ark_teseo_gps.md)
- [ARK TESEO GPS](/dronecan/ark_teseo_gps.md)
- [CUAV NEO 3 GPS](/gps_compass/gps_cuav_neo_3.md)
- [CUAV NEO 3 Pro GPS (CAN)](/gps_compass/gps_cuav_neo_3pro.md)
- [CUAV NEO 3X GPS (CAN)](/gps_compass/gps_cuav_neo_3x.md)
@@ -328,10 +322,13 @@
- [ARK Electron Microhard Serial Telemetry Radio](/telemetry/ark_microhard_serial.md)
- [Holybro Microhard P900 Telemetry Radio](/telemetry/holybro_microhard_p900_radio.md)
- [CUAV P8 Telemetry Radio](/telemetry/cuav_p8_radio.md)
- [J.Fi Wireless Telemetry Module](/telemetry/jfi_telemetry.md)
- [HolyBro XBP9X - Discontinued](/telemetry/holybro_xbp9x_radio.md)
- [FrSky Telemetry](/peripherals/frsky_telemetry.md)
- [TBS Crossfire (CRSF) Telemetry](/telemetry/crsf_telemetry.md)
- [Satellite Comms (Iridium/RockBlock)](/advanced_features/satcom_roadblock.md)
- [Power Systems](/power_systems/index.md)
- [Battery Estimation Tuning](/config/battery.md)
- [Battery Chemistry Overview](/power_systems/battery_chemistry.md)
@@ -398,7 +395,6 @@
- [Full Parameter Reference](/advanced_config/parameter_reference.md)
- [Other Vehicles](/airframes/index.md)
- [Airships (experimental)](/frames_airship/index.md)
- [Autogyros (experimental)](/frames_autogyro/index.md)
- [ThunderFly Auto-G2 (Holybro pix32)](/frames_autogyro/thunderfly_auto_g2.md)
@@ -713,6 +709,10 @@
- [YawEstimatorStatus](/msg_docs/YawEstimatorStatus.md)
- [VehicleStatusV0](/msg_docs/VehicleStatusV0.md)
- [MAVLink Messaging](/middleware/mavlink.md)
- [Adding Messages](/mavlink/adding_messages.md)
- [Streaming Messages](/mavlink/streaming_messages.md)
- [Receiving Messages](/mavlink/receiving_messages.md)
- [Custom MAVLink Messages](/mavlink/custom_messages.md)
- [Standard Modes Protocol](/mavlink/standard_modes.md)
- [uXRCE-DDS (PX4-ROS 2/DDS Bridge)](/middleware/uxrce_dds.md)
- [Modules & Commands](/modules/modules_main.md)
@@ -836,8 +836,9 @@
- [Terminology/Notation](/contribute/notation.md)
- [Licenses](/contribute/licenses.md)
- [Releases](/releases/index.md)
- [main (alpha)](/releases/main.md)
- [1.15 (stable)](/releases/1.15.md)
- [main (alpha)](/https://docs.px4.io/main/en/releases/main.html)
- [1.16 (stable)](/releases/1.15.md)
- [1.15](/releases/1.15.md)
- [1.14](/releases/1.14.md)
- [1.13](/releases/1.13.md)
- [1.12](/releases/1.12.md)
- [1.12](/releases/1.12.md)
+1 -2
View File
@@ -3,10 +3,9 @@
This section contains topics about the core actuators used for flight control (ESC/motors, and servos), and how they are assigned to the flight controller outputs, configured, and calibrated.
- [Actuator Allocation](../config/actuators.md) — Configure flight controller outputs for specific functions and ESC/servo types.
- [ESCs & Motors](../peripherals/esc_motors.md) — ESCs such as [DShot](../peripherals/dshot.md) (recommended) and DroneCAN.
- [ESC Calibration](../advanced_config/esc_calibration.md) — Calibration for PWM ESC (not required for DShot/CAN ESC/servos).
## See Also
- [Peripherals](../peripherals/index.md) - includes non-core actuators such as grippers, parachutes, etc.
- [Peripherals](../peripherals/index.md) - includes non-core actuators such as grippers, parachutes, etc.
+1 -10
View File
@@ -9,14 +9,6 @@ Developed by world-class developers from industry and academia, and supported by
:::tip
This guide contains everything you need to assemble, configure, and safely fly a PX4-based vehicle. Interested in contributing? Check out the [Development](development/development.md) section.
:::
:::warning
This guide is for the _development_ version of PX4 (`main` branch).
Use the **Version** selector to find the current _stable_ version.
Documented changes since the stable release are captured in the evolving [release note](releases/main.md).
:::
## How Do I Get Started?
@@ -97,7 +89,7 @@ You can access these from the Languages menu (top right):
![Language Selector](../assets/vuepress/language_selector.png)
<!--@include: _contributors.md-->
<!--@include: _contributors.md -->
## License
@@ -116,7 +108,6 @@ Select the links below to display the calendar in your timezone (and to add it t
:::tip
The calendar default timezone is Central European Time (CET).
:::
<iframe src="https://calendar.google.com/calendar/embed?title=Dronecode%20Calendar&amp;mode=WEEK&amp;height=600&amp;wkst=1&amp;bgcolor=%23FFFFFF&amp;src=linuxfoundation.org_g21tvam24m7pm7jhev01bvlqh8%40group.calendar.google.com&amp;color=%23691426&amp;ctz=Europe%2FZurich" style="border-width:0" width="800" height="600" frameborder="0" scrolling="no"></iframe>
+1 -1
View File
@@ -38,7 +38,7 @@ MAVLink applications, such as ground stations, can also control the gripper usin
PX4 gripper support is tied to the package delivery feature, which must be enabled and configured in order to be able to use a gripper.
1. Set [PD_GRIPPER_EN](../advanced_config/parameter_reference.md#PD_GRIPPER_EN) parameter to 1 (reboot required after change).
1. Ensure your board has the Payload Deliverer module enabled: CONFIG_MODULES_PAYLOAD_DELIVERER.
1. Set [PD_GRIPPER_TYPE](../advanced_config/parameter_reference.md#PD_GRIPPER_TYPE) to match your gripper.
For example, set to `Servo` for a [Servo Gripper](gripper_servo.md).
-2
View File
@@ -1,7 +1,5 @@
# PX4-Autopilot v1.15 Release Notes
<Badge type="tip" text="Stable"/>
The v1.15 release brings lots of new upgrades and fixes, thanks in part to the tremendous community response to the 1.14 release.
In particular, PX4 v1.15 brings significant improvements for developers and integrators using PX4 as a target through [ROS 2](../ros2/index.md) and the [uXRCE-DDS middleware](../middleware/uxrce_dds.md).
In addition to networking and middleware updates, the new [PX4 ROS 2 Interface Library](../ros2/px4_ros2_interface_lib.md) allows flight modes written as ROS 2 applications to be peers of PX4 flight modes.
+193
View File
@@ -0,0 +1,193 @@
# PX4-Autopilot v1.16.0 Release Notes
<Badge type="info" text="Stable" />
PX4 v1.16 builds on the momentum of v1.15 with significant new features and expanded hardware support thanks to our community contributions.
This release introduces bidirectional DShot support sponsored by ARK, a full rover rework with dedicated firmware builds and modular control modes for Ackermann, differential and mecanum rovers, and a switch to Gazebo Harmonic LTS for more reliable simulation.
Developers will benefit from the new ROS 2 Message Translation Node for dynamic message versioning and integrated log encryption that embeds decryption keys directly in logs.
We also added fresh sensor drivers and board support across our partner ecosystem alongside dozens of improvements in control, estimation and safety.
PX4 v1.16 raises the bar for performance and usability. Upgrade today and let us know your feedback on GitHub.
## Read Before Upgrading
Please continue reading for [upgrade instructions](#upgrade-guide).
## Major Changes
- [Bidirectional DShot](../peripherals/dshot.md#bidirectional-dshot-telemetry) - [Sponsored by ARK] ([PX4-Autopilot#23863](https://github.com/PX4/PX4-Autopilot/pull/23863))
- **[Rover](../frames_rover/index.md) support rework**
- New dedicated firmware build for rovers (airframe IDs 5000052000)
- Separate modules for Ackermann, differential and mecanum rovers, each with manual, acro, stabilized, position and auto modes
- Shared pure-pursuit guidance library for all rover modules
- Legacy rover position control module deprecated in favor of the new modules
- Gazebo Harmonic LTS release replaces Gazebo Garden as the version supported by PX4.
- [ROS 2 Message Translation Node](../ros2/px4_ros2_msg_translation_node.md) to translate PX4 messages from one definition version to another dynamically. ([PX4-Autopilot#24113](https://github.com/PX4/PX4-Autopilot/pull/24113))
- [Log Encryption](../dev_log/log_encryption.md) now generates an encrypted log that contains the public-key-encrypted symmetric key that can be used to decrypt it, instead of putting the key into a separate file.
## Upgrade Guide
- VOXL 2 boards now explicitly set EKF2_EV_CTRL=15 (it had fallen back to 0 globally), so event-based optical flow keeps running ([PX4-Autopilot#24648](https://github.com/PX4/PX4-Autopilot/pull/24648))
- Ethernet static IP changed from 192.168.0.3 to 10.41.10.2 to avoid common network conflicts ([PX4-Autopilot#22517](https://github.com/PX4/PX4-Autopilot/pull/22517))
- SF45 lidar no longer auto-starts on TELEM2—add serial_port: TELEM2 (or your preferred port) in its module config if you still want it there ([PX4-Autopilot#24602](https://github.com/PX4/PX4-Autopilot/pull/24602))
## Other changes
### Hardware Support
- **[New Hardware]** Boards: ARK FPV FC ([PX4-Autopilot#23830](https://github.com/PX4/PX4-Autopilot/pull/23830))
- **[New Hardware]** board: add cuav 7-nano ([PX4-Autopilot#23414](https://github.com/PX4/PX4-Autopilot/pull/23414))
- **[New Hardware]** add new board corvon743v1 ([PX4-Autopilot#24769](https://github.com/PX4/PX4-Autopilot/pull/24769))
- **[New Hardware]** boards: bluerobotics: navigator: Add initial support ([PX4-Autopilot#24018](https://github.com/PX4/PX4-Autopilot/pull/24018))
- **[New Hardware]** boards: add new board micoair743-v2 ([PX4-Autopilot#24147](https://github.com/PX4/PX4-Autopilot/pull/24147))
- **[New Hardware]** boards: add new board micoair h743 ([PX4-Autopilot#23218](https://github.com/PX4/PX4-Autopilot/pull/23218))
- **[New Hardware]** boards: Add FMUv6s target ([PX4-Autopilot#24512](https://github.com/PX4/PX4-Autopilot/pull/24512))
- **[New Hardware]** manifest: Add Skynode S baseboard ([PX4-Autopilot#23927](https://github.com/PX4/PX4-Autopilot/pull/23927))
- **[New Hardware]** Add Tropic VMU board support (Baseboard for Teensy 4.1) ([PX4-Autopilot#23257](https://github.com/PX4/PX4-Autopilot/pull/23257))
- **[New Hardware]** boards: add new board X-MAV AP-H743v2 ([PX4-Autopilot#23697](https://github.com/PX4/PX4-Autopilot/pull/23697))
- **[New Hardware]** 3DR boards: Support for 3DR Control Zero H7 OEM Rev G ([PX4-Autopilot#23551](https://github.com/PX4/PX4-Autopilot/pull/23551))
- **[New Hardware]** new board support ZeroOne x6 ([PX4-Autopilot#23623](https://github.com/PX4/PX4-Autopilot/pull/23623))
### Common
- [Optical flow scaling factor - SENS_FLOW_SCALE](../sensor/optical_flow.md#scale-factor). ([PX4-Autopilot#23936](https://github.com/PX4/PX4-Autopilot/pull/23936)).
- Reintroduce optional parameter versioning mechanism for airframe maintainers ([PX4-Autopilot#22813](https://github.com/PX4/PX4-Autopilot/pull/22813))
- [Battery level estimation improvements](../config/battery.md). ([PX4-Autopilot#23205](https://github.com/PX4/PX4-Autopilot/pull/23205)).
- [Voltage-based estimation with load compensation](../config/battery.md#voltage-based-estimation-with-load-compensation) now uses a real-time estimate of the internal resistance of the battery to compensate voltage drops under load (with increased current), providing a better capacity estimate than with the raw measured voltage.
- Thrust-based load compensation has been removed (along with the `BATn_V_LOAD_DROP` parameters, where `n` is the battery number).
- The [Position (GNSS) loss failsafe](../config/safety.md#position-gnss-loss-failsafe) configurable delay (`COM_POS_FS_DELAY`) has been removed.
The failsafe will now trigger 1 second after position has been lost. ([PX4-Autopilot#24063](https://github.com/PX4/PX4-Autopilot/pull/24063)).
- [Log Encryption](../dev_log/log_encryption.md) now generates an encrypted log that contains the public-key-encrypted symmetric key that can be used to decrypt it, instead of putting the key into a separate file.
This makes log decryption much easier, as there is no need to download or identify a separate key file.
([PX4-Autopilot#24024](https://github.com/PX4/PX4-Autopilot/pull/24024)).
- The generic mission command timeout [MIS_COMMAND_TOUT](../advanced_config/parameter_reference.md#MIS_COMMAND_TOUT) parameter replaces the delivery-specific `MIS_PD_TO` parameter.
Mission commands that may take some time to complete, such as those for controlling gimbals, winches, and grippers, will progress to the next item when either feedback is received or the timeout expires.
This is often used to provide a minimum delay for hardware that does not provide completion feedback, so that it can reach the commanded state before the mission progresses.
([PX4-Autopilot#23960](https://github.com/PX4/PX4-Autopilot/pull/23960)).
- **[uORB]** Introduce a [version field](../middleware/uorb.md#message-versioning) for a subset of uORB messages ([PX4-Autopilot#23850](https://github.com/PX4/PX4-Autopilot/pull/23850))
- [Compass calibration](../config/compass.md) disables internal compasses if an external compass is available.
This typically reduces false warnings due to magnetometer inconsistencies.
([PX4-Autopilot#24316](https://github.com/PX4/PX4-Autopilot/pull/24316)).
### Control
- [Sponsored by ARK] [Bidirectional DShot](../peripherals/dshot.md#bidirectional-dshot-telemetry) ([PX4-Autopilot#23863](https://github.com/PX4/PX4-Autopilot/pull/23863))
- Make control allocation and actuator effectiveness a non-module-specific library ([PX4-Autopilot#24196](https://github.com/PX4/PX4-Autopilot/pull/24196))
- Spacecraft Build and Bare Control Allocator ([PX4-Autopilot#24221](https://github.com/PX4/PX4-Autopilot/pull/24221))
- Configurable multicopter orbit-mode yaw via `MC_ORBIT_YAW_MOD` ([PX4-Autopilot#23358](https://github.com/PX4/PX4-Autopilot/pull/23358))
- Collision prevention now works in manual (acceleration-based) flight mode (`MPC_POS_MODE`) ([PX4-Autopilot#23507](https://github.com/PX4/PX4-Autopilot/pull/23507))
### Estimation
- EKF2: ellipsoidal earth navigation ([PX4-Autopilot#23854](https://github.com/PX4/PX4-Autopilot/pull/23854))
- EKF2: Terrain state ([PX4-Autopilot#23263](https://github.com/PX4/PX4-Autopilot/pull/23263))
- ekf2: add mag type init ([PX4-Autopilot#23185](https://github.com/PX4/PX4-Autopilot/pull/23185))
- ekf2: Optical flow enabled by default ([PX4-Autopilot#23436](https://github.com/PX4/PX4-Autopilot/pull/23436))
- Position-loss failsafe delay removed; triggers 1 s after loss (see Common)
### Sensors
- Implemented AUAV absolute/differential pressure sensor support ([PX4-Autopilot#23656](https://github.com/PX4/PX4-Autopilot/pull/23656))
- Implemented temperature sensor support for INA228 / INA238 ([PX4-Autopilot#23639](https://github.com/PX4/PX4-Autopilot/pull/23639))
- Add Ublox ZED-F9P-15B ([PX4-Autopilot#22744](https://github.com/PX4/PX4-Autopilot/pull/22744))
- Mag cal: automatically disable internal mags if external ones are available ([PX4-Autopilot#24316](https://github.com/PX4/PX4-Autopilot/pull/24316))
- BMP581: Add Bosch BMP581 barometer ([PX4-Autopilot#23064](https://github.com/PX4/PX4-Autopilot/pull/23064))
- Murata SCH16T IMU driver ([PX4-Autopilot#22914](https://github.com/PX4/PX4-Autopilot/pull/22914))
- ST IIS2MDC Magnetometer driver ([PX4-Autopilot#23023](https://github.com/PX4/PX4-Autopilot/pull/23023))
- Include distance sensor in dds topics ([PX4-Autopilot#24121](https://github.com/PX4/PX4-Autopilot/pull/24121))
- drivers: magnetometer: mmc5983ma: Add SPI support ([PX4-Autopilot#23925](https://github.com/PX4/PX4-Autopilot/pull/23925))
- drivers/magnetometer/ak09916: Add support to AK09915 ([PX4-Autopilot#23909](https://github.com/PX4/PX4-Autopilot/pull/23909))
- Add Bosch BMM350 magnetometer ([PX4-Autopilot#23362](https://github.com/PX4/PX4-Autopilot/pull/23362))
- Compass calibration now disables internal compass when external unit present, reducing false warnings ([PX4-Autopilot#24316](https://github.com/PX4/PX4-Autopilot/pull/24316))
### Simulation
- **SIH**:
- The SIH on SITL [custom takeoff location](../sim_sih/index.md#set-custom-takeoff-location) in now set using the normal unscaled GPS position values, where previously the value needed to be multiplied by 1E7.
([PX4-Autopilot#23363](https://github.com/PX4/PX4-Autopilot/pull/23363)).
- SIH now supports the standard VTOL airframe
([PX4-Autopilot#24175](https://github.com/PX4/PX4-Autopilot/pull/24175)).
- **Gazebo**:
- Gazebo Harmonic LTS release replaces Gazebo Garden as the version supported by PX4.
The default installer scripts (used for CI) and documentation have been updated.
This is required because Garden end-of-life is Nov 2024.
([PX4-Autopilot#23603](https://github.com/PX4/PX4-Autopilot/pull/23603))
- New vehicle model `x500_lidar_2d` — [x500 Quadrotor with 2D Lidar](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-2d-lidar). ([PX4-Autopilot#22418](https://github.com/PX4/PX4-Autopilot/pull/22418), [PX4-gazebo-models#41](https://github.com/PX4/PX4-gazebo-models/pull/41)).
- New vehicle model `x500_lidar_front` — [X500 Quadrotor with 1D LIDAR (Front-facing)](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-1d-lidar-front-facing). ([PX4-Autopilot#23879](https://github.com/PX4/PX4-Autopilot/pull/23879), [PX4-gazebo-models#62](https://github.com/PX4/PX4-gazebo-models/pull/62/files)).
- New vehicle model `x500_lidar_down` — [X500 Quadrotor with 1D LIDAR (Down-facing)](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-1d-lidar-down-facing). ([PX4-Autopilot#23879](https://github.com/PX4/PX4-Autopilot/pull/23879), [PX4-gazebo-models#62](https://github.com/PX4/PX4-gazebo-models/pull/62/files)).
- New vehicle model `r1_rover` — [Aion Robotics R1 Rover](../sim_gazebo_gz/vehicles.md#differential-rover) ([PX4-Autopilot#22402](https://github.com/PX4/PX4-Autopilot/pull/22402) and [PX4-gazebo-models#21](https://github.com/PX4/PX4-gazebo-models/pull/21)).
- New vehicle model `rover_ackermann` — [Ackermann Rover](../sim_gazebo_gz/vehicles.md#ackermann-rover) ([PX4-Autopilot#23383](https://github.com/PX4/PX4-Autopilot/pull/23383) and [PX4-gazebo-models#46](https://github.com/PX4/PX4-gazebo-models/pull/46)).
- New vehicle model `x500_gimbal` — [Quadrotor(x500) with gimbal (Front-facing) in Gazebo](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-gimbal-front-facing) ([PX4-Autopilot#23382](https://github.com/PX4/PX4-Autopilot/pull/23382) and [PX4-gazebo-models#47](https://github.com/PX4/PX4-gazebo-models/pull/47) and [PX4-gazebo-models#70](https://github.com/PX4/PX4-gazebo-models/pull/70)).
- New vehicle model `quadtailsitter` — [Quad Tailsitter VTOL](../sim_gazebo_gz/vehicles.md#quad-tailsitter-vtol) ([PX4-Autopilot#23943](https://github.com/PX4/PX4-Autopilot/pull/23943) and [PX4-gazebo-models#65](https://github.com/PX4/PX4-gazebo-models/pull/65)).
- New vehicle model `tiltrotor` — [Tiltrotor VTOL](../sim_gazebo_gz/vehicles.md#tiltrotor-vtol) ([PX4-Autopilot#24028](https://github.com/PX4/PX4-Autopilot/pull/24028) and [PX4-gazebo-models#66](https://github.com/PX4/PX4-gazebo-models/pull/66)).
- [Faster than Real-time Simulation](../simulation/index.md#simulation_speed) ([PX4-Autopilot#24421](https://github.com/PX4/PX4-Autopilot/pull/24421), [PX4-Autopilot#23783](https://github.com/PX4/PX4-Autopilot/pull/23783))
- [PX4-Autopilot#24471](https://github.com/PX4/PX4-Autopilot/pull/24471): Gazebo: Moving platform
### uXRCE-DDS / ROS2
- [PX4-Autopilot#24113](https://github.com/PX4/PX4-Autopilot/pull/24113): <Badge type="warning" text="Experimental"/> [ROS 2 Message Translation Node](../ros2/px4_ros2_msg_translation_node.md) to translate PX4 messages from one definition version to another dynamically
- dds_topics: add vtol_vehicle_status ([PX4-Autopilot#24582](https://github.com/PX4/PX4-Autopilot/pull/24582))
- dds_topics: add home_position ([PX4-Autopilot#24583](https://github.com/PX4/PX4-Autopilot/pull/24583))
### MAVLink
- mavlink_ftp: handle relative paths correctly. ([PX4-Autopilot#22980](https://github.com/PX4/PX4-Autopilot/pull/22980))
- Parameter to always start mavlink stream via USB. ([PX4-Autopilot#22234](https://github.com/PX4/PX4-Autopilot/pull/22234))
- Refactor: MAVLink message handling in one function, reference instead of pointer to main instance ([PX4-Autopilo#23219](https://github.com/PX4/PX4-Autopilot/pull/22234))
- mavlink log handler rewrite for improved effeciency ([PX4-Autopilo#23219](https://github.com/PX4/PX4-Autopilot/pull/22234))
### Multi-Rotor
- [Multirotor] add yaw torque low pass filter ([PX4-Autopilot#24173](https://github.com/PX4/PX4-Autopilot/pull/24173))
- Add gz model for quadtailsitter ([PX4-Autopilot#23943](https://github.com/PX4/PX4-Autopilot/pull/23943))
- Allow system-default [multicopter orbit mode](../flight_modes_mc/orbit.md) yaw behaviour to be configured, using the parameter [MC_ORBIT_YAW_MOD](../advanced_config/parameter_reference.md#MC_ORBIT_YAW_MOD) ([PX4-Autopilot#23358](https://github.com/PX4/PX4-Autopilot/pull/23358))
- Adapted the [Collision Prevention](../computer_vision/collision_prevention.md) implementation to work in the default manual flight mode (Acceleration Based) [MPC_POS_MODE](../advanced_config/parameter_reference.md#MPC_POS_MODE). ([PX4-Autopilot#23507](https://github.com/PX4/PX4-Autopilot/pull/23507))
### VTOL
- vtol_type: Added position feedback to VTOL backward transition. ([PX4-Autopilo#23731](https://github.com/PX4/PX4-Autopilot/pull/23731))
- dds_topics: add vtol_vehicle_status. ([PX4-Autopilo#24582](https://github.com/PX4/PX4-Autopilot/pull/24582))
- vtol: reduce schedule frequency, which causes DSHOT150 problems. ([PX4-Autopilo#24727](https://github.com/PX4/PX4-Autopilot/pull/24727))
### Fixed-wing
- Fixedwing: fix wheel controller ([PX4-Autopilot#24167](https://github.com/PX4/PX4-Autopilot/pull/24167))
- FixedWing: allow position control without valid global position ([PX4-Autopilot#23520](https://github.com/PX4/PX4-Autopilot/pull/23520))
- Improvement: Fixed-wing auto takeoff: enable setting takeoff flaps for hand/catapult launch. [PX4-Autopilot#23460](https://github.com/PX4/PX4-Autopilot/pull/23460)
### Rover
This release contains a major rework for the rover support in PX4:
- Complete restructure of the [rover related documentation](../frames_rover/index.md).
- New firmware build specifically for [rovers](../config_rover/index.md#flashing-the-rover-build).
- New module dedicated to [Ackermann rovers](../frames_rover/index.md#ackermann):
- The module currently supports [manual mode](../flight_modes_rover/manual.md#manual-mode), [acro mode](../flight_modes_rover/manual.md#acro-mode), [stabilized mode](../flight_modes_rover/manual.md#stabilized-mode), [position mode](../flight_modes_rover/manual.md#position-mode) and [auto modes](../flight_modes_rover/auto.md).
- New module dedicated to [differential rovers](../frames_rover/index.md#differential):
- The module currently supports [manual mode](../flight_modes_rover/manual.md#manual-mode), [acro mode](../flight_modes_rover/manual.md#acro-mode), [stabilized mode](../flight_modes_rover/manual.md#stabilized-mode), [position mode](../flight_modes_rover/manual.md#position-mode) and [auto modes](../flight_modes_rover/auto.md).
- New module dedicated to [mecanum rovers](../frames_rover/index.md#mecanum):
- The module currently supports [manual mode](../flight_modes_rover/manual.md#manual-mode), [acro mode](../flight_modes_rover/manual.md#acro-mode), [stabilized mode](../flight_modes_rover/manual.md#stabilized-mode), [position mode](../flight_modes_rover/manual.md#position-mode) and [auto modes](../flight_modes_rover/auto.md).
- Added rover-specific firmware build (`5000052000`) for Ackermann, differential and mecanum rovers
- Restructure of the [rover airframe](../airframes/airframe_reference.md#rover) numbering convention ([PX4-Autopilot#23506](https://github.com/PX4/PX4-Autopilot/pull/23506)).
This also introduces several [new rover airframes](../airframes/airframe_reference.md#rover):
- Generic Differential Rover `50000`.
- Generic Ackermann Rover `51000`.
- Axial SCX10 2 Trail Honcho `51001`.
- Generic Mecanum Rover `52000`.
- Library for the [pure pursuit guidance algorithm](../config_rover/position_tuning.md#pure-pursuit-guidance-logic-info-only) that is shared by all the rover modules.
- [Simulation](../frames_rover/index.md#simulation) for differential-steering and Ackermann rovers in gazebo (for release notes see `r1_rover` and `rover_ackermann` in [simulation](#simulation)).
- Deprecation of the `rover position control` module: Note that the legacy rover module still exists but has been superseded by the new dedicated modules.
### Infrastructure
- standard_modes: add vehicle-type specific standard modes. ([PX4-Autopilot#24011](https://github.com/PX4/PX4-Autopilot/pull/24011))
- ci: build all upload to releases. ([PX4-Autopilot#24020](https://github.com/PX4/PX4-Autopilot/pull/24020))
- ci: px4-dev container. ([PX4-Autopilot#24002](https://github.com/PX4/PX4-Autopilot/pull/24002))
- ci: workflow for ubuntu 24.04. ([PX4-Autopilot#23937](https://github.com/PX4/PX4-Autopilot/pull/23937))
- ci: add test for Ubuntu 22.04. ([PX4-Autopilot#23869](https://github.com/PX4/PX4-Autopilot/pull/23869))
- ci: try runs-on Dronecode Infra (AWS). ([PX4-Autopilot#23574](https://github.com/PX4/PX4-Autopilot/pull/23574))
- ci: replace build workflows. ([PX4-Autopilot#23550](https://github.com/PX4/PX4-Autopilot/pull/23550))
+2 -1
View File
@@ -2,7 +2,8 @@
A list of PX4 release notes, they contain a list of the changes that went into each release, explaining the included features, bug fixes, deprecations and updates in detail.
- [main](../releases/main.md) (changes since v1.15)
- [main](https://docs.px4.io/main/en/releases/main.html) (changes since v1.16)
- [v1.16](../releases/1.16.md)
- [v1.15](../releases/1.15.md)
- [v1.14](../releases/1.14.md)
- [v1.13](../releases/1.13.md)
+2 -130
View File
@@ -1,132 +1,4 @@
# PX4-Autopilot Main Release Notes
<Badge type="danger" text="Alpha" />
This contains changes to PX4 `main` branch since the last major release ([PX v1.15](../releases/1.15.md)).
::: warning
The PX4 v1.15 release is in beta testing, pending release.
Update these notes with features that are going to be in `main` but not the PX4 v1.15 release.
:::
## Read Before Upgrading
TBD …
Please continue reading for [upgrade instructions](#upgrade-guide).
## Major Changes
- TBD
## Upgrade Guide
## Other changes
### Hardware Support
- TBD
### Common
- [Battery level estimation improvements](../config/battery.md). ([PX4-Autopilot#23205](https://github.com/PX4/PX4-Autopilot/pull/23205)).
- [Voltage-based estimation with load compensation](../config/battery.md#voltage-based-estimation-with-load-compensation) now uses a real-time estimate of the internal resistance of the battery to compensate voltage drops under load (with increased current), providing a better capacity estimate than with the raw measured voltage.
- Thrust-based load compensation has been removed (along with the `BATn_V_LOAD_DROP` parameters, where `n` is the battery number).
- The [Position (GNSS) loss failsafe](../config/safety.md#position-gnss-loss-failsafe) configurable delay (`COM_POS_FS_DELAY`) has been removed.
The failsafe will now trigger 1 second after position has been lost. ([PX4-Autopilot#24063](https://github.com/PX4/PX4-Autopilot/pull/24063)).
- [Log Encryption](../dev_log/log_encryption.md) now generates an encrypted log that contains the public-key-encrypted symmetric key that can be used to decrypt it, instead of putting the key into a separate file.
This makes log decryption much easier, as there is no need to download or identify a separate key file.
([PX4-Autopilot#24024](https://github.com/PX4/PX4-Autopilot/pull/24024)).
- The generic mission command timeout [MIS_COMMAND_TOUT](../advanced_config/parameter_reference.md#MIS_COMMAND_TOUT) parameter replaces the delivery-specific `MIS_PD_TO` parameter.
Mission commands that may take some time to complete, such as those for controlling gimbals, winches, and grippers, will progress to the next item when either feedback is received or the timeout expires.
This is often used to provide a minimum delay for hardware that does not provide completion feedback, so that it can reach the commanded state before the mission progresses.
([PX4-Autopilot#23960](https://github.com/PX4/PX4-Autopilot/pull/23960)).
- **[uORB]** Introduce a [version field](../middleware/uorb.md#message-versioning) for a subset of uORB messages ([PX4-Autopilot#23850](https://github.com/PX4/PX4-Autopilot/pull/23850))
- [Compass calibration](../config/compass.md) disables internal compasses if an external compass is available.
This typically reduces false warnings due to magnetometer inconsistencies.
([PX4-Autopilot#24316](https://github.com/PX4/PX4-Autopilot/pull/24316)).
### Control
- TBD
### Estimation
- TBD
### Sensors
- TBD
### Simulation
- [SIH]:
- The SIH on SITL [custom takeoff location](../sim_sih/index.md#set-custom-takeoff-location) in now set using the normal unscaled GPS position values, where previously the value needed to be multiplied by 1E7.
([PX4-Autopilot#23363](https://github.com/PX4/PX4-Autopilot/pull/23363)).
- SIH now supports the standard VTOL airframe
([PX4-Autopilot#24175](https://github.com/PX4/PX4-Autopilot/pull/24175)).
- [Gazebo]:
- Gazebo Harmonic LTS release replaces Gazebo Garden as the version supported by PX4.
The default installer scripts (used for CI) and documentation have been updated.
This is required because Garden end-of-life is Nov 2024.
([PX4-Autopilot#23603](https://github.com/PX4/PX4-Autopilot/pull/23603))
- New vehicle model `x500_lidar_2d` — [x500 Quadrotor with 2D Lidar](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-2d-lidar). ([PX4-Autopilot#22418](https://github.com/PX4/PX4-Autopilot/pull/22418), [PX4-gazebo-models#41](https://github.com/PX4/PX4-gazebo-models/pull/41)).
- New vehicle model `x500_lidar_front` — [X500 Quadrotor with 1D LIDAR (Front-facing)](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-1d-lidar-front-facing). ([PX4-Autopilot#23879](https://github.com/PX4/PX4-Autopilot/pull/23879), [PX4-gazebo-models#62](https://github.com/PX4/PX4-gazebo-models/pull/62/files)).
- New vehicle model `x500_lidar_down` — [X500 Quadrotor with 1D LIDAR (Down-facing)](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-1d-lidar-down-facing). ([PX4-Autopilot#23879](https://github.com/PX4/PX4-Autopilot/pull/23879), [PX4-gazebo-models#62](https://github.com/PX4/PX4-gazebo-models/pull/62/files)).
- New vehicle model `r1_rover` — [Aion Robotics R1 Rover](../sim_gazebo_gz/vehicles.md#differential-rover) ([PX4-Autopilot#22402](https://github.com/PX4/PX4-Autopilot/pull/22402) and [PX4-gazebo-models#21](https://github.com/PX4/PX4-gazebo-models/pull/21)).
- New vehicle model `rover_ackermann` — [Ackermann Rover](../sim_gazebo_gz/vehicles.md#ackermann-rover) ([PX4-Autopilot#23383](https://github.com/PX4/PX4-Autopilot/pull/23383) and [PX4-gazebo-models#46](https://github.com/PX4/PX4-gazebo-models/pull/46)).
- New vehicle model `x500_gimbal` — [Quadrotor(x500) with gimbal (Front-facing) in Gazebo](../sim_gazebo_gz/vehicles.md#x500-quadrotor-with-gimbal-front-facing) ([PX4-Autopilot#23382](https://github.com/PX4/PX4-Autopilot/pull/23382) and [PX4-gazebo-models#47](https://github.com/PX4/PX4-gazebo-models/pull/47) and [PX4-gazebo-models#70](https://github.com/PX4/PX4-gazebo-models/pull/70)).
- New vehicle model `quadtailsitter` — [Quad Tailsitter VTOL](../sim_gazebo_gz/vehicles.md#quad-tailsitter-vtol) ([PX4-Autopilot#23943](https://github.com/PX4/PX4-Autopilot/pull/23943) and [PX4-gazebo-models#65](https://github.com/PX4/PX4-gazebo-models/pull/65)).
- New vehicle model `tiltrotor` — [Tiltrotor VTOL](../sim_gazebo_gz/vehicles.md#tiltrotor-vtol) ([PX4-Autopilot#24028](https://github.com/PX4/PX4-Autopilot/pull/24028) and [PX4-gazebo-models#66](https://github.com/PX4/PX4-gazebo-models/pull/66)).
- [Faster than Real-time Simulation](../simulation/index.md#simulation_speed) ([PX4-Autopilot#24421](https://github.com/PX4/PX4-Autopilot/pull/24421), [PX4-Autopilot#23783](https://github.com/PX4/PX4-Autopilot/pull/23783))
### Ethernet
- TBD
### uXRCE-DDS / ROS2
- **[Feature]** <Badge type="warning" text="Experimental"/> [ROS 2 Message Translation Node](../ros2/px4_ros2_msg_translation_node.md) to translate PX4 messages from one definition version to another dynamically ([PX4-Autopilot#24113](https://github.com/PX4/PX4-Autopilot/pull/24113))
### MAVLink
- TBD
### Multi-Rotor
- Allow system-default [multicopter orbit mode](../flight_modes_mc/orbit.md) yaw behaviour to be configured, using the parameter [MC_ORBIT_YAW_MOD](../advanced_config/parameter_reference.md#MC_ORBIT_YAW_MOD) ([PX4-Autopilot#23358](https://github.com/PX4/PX4-Autopilot/pull/23358))
- Adapted the [Collision Prevention](../computer_vision/collision_prevention.md) implementation to work in the default manual flight mode (Acceleration Based) [MPC_POS_MODE](../advanced_config/parameter_reference.md#MPC_POS_MODE). ([PX4-Autopilot#23507](https://github.com/PX4/PX4-Autopilot/pull/23507)
### VTOL
- TBD
### Fixed-wing
- Improvement: Fixed-wing auto takeoff: enable setting takeoff flaps for hand/catapult launch. [PX4-Autopilot#23460](https://github.com/PX4/PX4-Autopilot/pull/23460)
### Rover
This release contains a major rework for the rover support in PX4:
- Complete restructure of the [rover related documentation](../frames_rover/index.md).
- New firmware build specifically for [rovers](../frames_rover/index.md#flashing-the-rover-build).
- New module dedicated to [Ackermann rovers](../frames_rover/ackermann.md):
- The module currently supports [manual mode](../flight_modes_rover/ackermann.md#manual-mode), [acro mode](../flight_modes_rover/ackermann.md#acro-mode), [position mode](../flight_modes_rover/ackermann.md#position-mode) and [auto modes](../flight_modes_rover/ackermann.md#auto-modes).
- New module dedicated to [differential rovers](../frames_rover/differential.md):
- The module currently supports [manual mode](../flight_modes_rover/differential.md#manual-mode), [acro mode](../flight_modes_rover/differential.md#acro-mode), [stabilized mode](../flight_modes_rover/differential.md#stabilized-mode), [position mode](../flight_modes_rover/differential.md#position-mode) and [auto modes](../flight_modes_rover/differential.md#auto-modes).
- New module dedicated to [mecanum rovers](../frames_rover/mecanum.md):
- The module currently supports [manual mode](../flight_modes_rover/mecanum.md#manual-mode), [acro mode](../flight_modes_rover/mecanum.md#acro-mode), [stabilized mode](../flight_modes_rover/mecanum.md#stabilized-mode), [position mode](../flight_modes_rover/mecanum.md#position-mode) and [auto modes](../flight_modes_rover/mecanum.md#auto-modes).
- Restructure of the [rover airframe](../airframes/airframe_reference.md#rover) numbering convention ([PX4-Autopilot#23506](https://github.com/PX4/PX4-Autopilot/pull/23506)).
This also introduces several [new rover airframes](../airframes/airframe_reference.md#rover):
- Generic Differential Rover `50000`.
- Generic Ackermann Rover `51000`.
- Axial SCX10 2 Trail Honcho `51001`.
- Generic Mecanum Rover `52000`.
- Library for the [pure pursuit guidance algorithm](../config_rover/differential.md#pure-pursuit-guidance-logic) that is shared by all the rover modules.
- [Simulation](../frames_rover/index.md#simulation) for differential-steering and Ackermann rovers in gazebo (for release notes see `r1_rover` and `rover_ackermann` in [simulation](#simulation)).
- Deprecation of the [rover position control](../frames_rover/rover_position_control.md) module: Note that the legacy rover module still exists but has been superseded by the new dedicated modules.
### ROS 2
- TBD
This page is on a release branch.
<a href="https://docs.px4.io/main/en/releases/main.html">See the latest version here.</a>
+12 -1
View File
@@ -253,6 +253,7 @@
- [Avionics Anonymous Laser Altimeter UAVCAN Interface (CAN)](/dronecan/avanon_laser_interface.md)
- [GNSS (GPS)](/gps_compass/index.md)
- [ARK GPS (CAN)](/dronecan/ark_gps.md)
- [ARK SAM GPS](/gps_compass/ark_sam_gps.md)
- [ARK TESEO GPS](/dronecan/ark_teseo_gps.md)
- [CUAV NEO 3 GPS](/gps_compass/gps_cuav_neo_3.md)
- [CUAV NEO 3 Pro GPS (CAN)](/gps_compass/gps_cuav_neo_3pro.md)
@@ -314,6 +315,7 @@
- [Joysticks](/config/joystick.md)
- [Data Links](/data_links/index.md)
- [MAVLink 텔레메트리(OSD/GCS) ](/peripherals/mavlink_peripherals.md)
- [텔레메트리 무선통신](/telemetry/index.md)
- [SiK 무선통신](/telemetry/sik_radio.md)
- [RFD900 (SiK) 텔레메트리](/telemetry/rfd900_telemetry.md)
@@ -326,9 +328,13 @@
- [ARK Electron Microhard Serial Telemetry Radio](/telemetry/ark_microhard_serial.md)
- [Holybro Microhard P900 Telemetry Radio](/telemetry/holybro_microhard_p900_radio.md)
- [CUAV P8 Telemetry Radio](/telemetry/cuav_p8_radio.md)
- [J.Fi Wireless Telemetry Module](/telemetry/jfi_telemetry.md)
- [HolyBro XBP9X - Discontinued](/telemetry/holybro_xbp9x_radio.md)
- [FrSky 텔레메트리](/peripherals/frsky_telemetry.md)
- [TBS Crossfire (CRSF) Telemetry](/telemetry/crsf_telemetry.md)
- [Satellite Comms (Iridium/RockBlock)](/advanced_features/satcom_roadblock.md)
- [Power Systems](/power_systems/index.md)
- [Battery Estimation Tuning](/config/battery.md)
@@ -637,6 +643,7 @@
- [PowerButtonState](/msg_docs/PowerButtonState.md)
- [PowerMonitor](/msg_docs/PowerMonitor.md)
- [PpsCapture](/msg_docs/PpsCapture.md)
- [PurePursuitStatus](/msg_docs/PurePursuitStatus.md)
- [PwmInput](/msg_docs/PwmInput.md)
- [Px4ioStatus](/msg_docs/Px4ioStatus.md)
- [QshellReq](/msg_docs/QshellReq.md)
@@ -710,6 +717,10 @@
- [YawEstimatorStatus](/msg_docs/YawEstimatorStatus.md)
- [VehicleStatusV0](/msg_docs/VehicleStatusV0.md)
- [MAVLink Messaging](/middleware/mavlink.md)
- [Adding Messages](/mavlink/adding_messages.md)
- [Streaming Messages](/mavlink/streaming_messages.md)
- [Receiving Messages](/mavlink/receiving_messages.md)
- [Custom MAVLink Messages](/mavlink/custom_messages.md)
- [Standard Modes Protocol](/mavlink/standard_modes.md)
- [uXRCE-DDS (PX4-ROS 2/DDS Bridge)](/middleware/uxrce_dds.md)
- [모듈과 명령어](/modules/modules_main.md)
@@ -840,4 +851,4 @@
- [1.15 (stable)](/releases/1.15.md)
- [1.14](/releases/1.14.md)
- [1.13](/releases/1.13.md)
- [1.12](/releases/1.12.md)
- [1.12](/releases/1.12.md)
+8 -1
View File
@@ -253,6 +253,7 @@
- [Avionics Anonymous Laser Altimeter UAVCAN Interface (CAN)](/dronecan/avanon_laser_interface.md)
- [GNSS (GPS)](/gps_compass/index.md)
- [ARK GPS (CAN)](/dronecan/ark_gps.md)
- [ARK SAM GPS](/gps_compass/ark_sam_gps.md)
- [ARK TESEO GPS](/dronecan/ark_teseo_gps.md)
- [CUAV NEO 3 GPS](/gps_compass/gps_cuav_neo_3.md)
- [CUAV NEO 3 Pro GPS (CAN)](/gps_compass/gps_cuav_neo_3pro.md)
@@ -314,6 +315,7 @@
- [Джойстики](/config/joystick.md)
- [Посилання даних](/data_links/index.md)
- [MAVLink Telemetry (OSD/GCS)](/peripherals/mavlink_peripherals.md)
- [Телеметричні радіостанції](/telemetry/index.md)
- [SiK Radio](/telemetry/sik_radio.md)
- [Телеметричне радіо RFD900 (SiK)](/telemetry/rfd900_telemetry.md)
@@ -326,9 +328,13 @@
- [ARK Electron Microhard Серійне Телеметрійне Радіо](/telemetry/ark_microhard_serial.md)
- [Holybro Microhard P900 Телеметрійне Радіо](/telemetry/holybro_microhard_p900_radio.md)
- [CUAV P8 Телеметрійне радіо](/telemetry/cuav_p8_radio.md)
- [J.Fi Wireless Telemetry Module](/telemetry/jfi_telemetry.md)
- [Holybro XBP9X - Припинено](/telemetry/holybro_xbp9x_radio.md)
- [FrSky телеметрія](/peripherals/frsky_telemetry.md)
- [TBS Crossfire (CRSF) телеметрія](/telemetry/crsf_telemetry.md)
- [Супутниковий зв'язок (Iridium/RockBlock)](/advanced_features/satcom_roadblock.md)
- [Енергетичні системи](/power_systems/index.md)
- [Налаштування оцінки батареї](/config/battery.md)
@@ -637,6 +643,7 @@
- [PowerButtonState](/msg_docs/PowerButtonState.md)
- [PowerMonitor](/msg_docs/PowerMonitor.md)
- [PpsCapture](/msg_docs/PpsCapture.md)
- [PurePursuitStatus](/msg_docs/PurePursuitStatus.md)
- [PwmInput](/msg_docs/PwmInput.md)
- [Px4ioStatus](/msg_docs/Px4ioStatus.md)
- [QshellReq](/msg_docs/QshellReq.md)
@@ -840,4 +847,4 @@
- [1.15 (stable)](/releases/1.15.md)
- [1.14](/releases/1.14.md)
- [1.13](/releases/1.13.md)
- [1.12](/releases/1.12.md)
- [1.12](/releases/1.12.md)
+12 -1
View File
@@ -253,6 +253,7 @@
- [Avionics Anonymous Laser Altimeter UAVCAN Interface (CAN)](/dronecan/avanon_laser_interface.md)
- [GNSS (GPS)](/gps_compass/index.md)
- [ARK GPS (CAN)](/dronecan/ark_gps.md)
- [ARK SAM GPS](/gps_compass/ark_sam_gps.md)
- [ARK TESEO GPS](/dronecan/ark_teseo_gps.md)
- [CUAV NEO 3 GPS](/gps_compass/gps_cuav_neo_3.md)
- [CUAV NEO 3 Pro GPS (CAN)](/gps_compass/gps_cuav_neo_3pro.md)
@@ -314,6 +315,7 @@
- [Joysticks](/config/joystick.md)
- [Data Links](/data_links/index.md)
- [MAVLink 回传(OSD/GCS](/peripherals/mavlink_peripherals.md)
- [数传电台](/telemetry/index.md)
- [SiK 电台](/telemetry/sik_radio.md)
- [RFD900 (SiK) 数传电台](/telemetry/rfd900_telemetry.md)
@@ -326,9 +328,13 @@
- [ARK Electron Microhard Serial Telemetry Radio](/telemetry/ark_microhard_serial.md)
- [Holybro Microhard P900 Telemetry Radio](/telemetry/holybro_microhard_p900_radio.md)
- [CUAV P8 Telemetry Radio](/telemetry/cuav_p8_radio.md)
- [J.Fi Wireless Telemetry Module](/telemetry/jfi_telemetry.md)
- [HolyBro XBP9X - Discontinued](/telemetry/holybro_xbp9x_radio.md)
- [睿思凯数传](/peripherals/frsky_telemetry.md)
- [TBS Crossfire (CRSF) Telemetry](/telemetry/crsf_telemetry.md)
- [Satellite Comms (Iridium/RockBlock)](/advanced_features/satcom_roadblock.md)
- [Power Systems](/power_systems/index.md)
- [Battery Estimation Tuning](/config/battery.md)
@@ -637,6 +643,7 @@
- [PowerButtonState](/msg_docs/PowerButtonState.md)
- [PowerMonitor](/msg_docs/PowerMonitor.md)
- [PpsCapture](/msg_docs/PpsCapture.md)
- [PurePursuitStatus](/msg_docs/PurePursuitStatus.md)
- [PwmInput](/msg_docs/PwmInput.md)
- [Px4ioStatus](/msg_docs/Px4ioStatus.md)
- [QshellReq](/msg_docs/QshellReq.md)
@@ -710,6 +717,10 @@
- [YawEstimatorStatus](/msg_docs/YawEstimatorStatus.md)
- [VehicleStatusV0](/msg_docs/VehicleStatusV0.md)
- [MAVLink通讯](/middleware/mavlink.md)
- [Adding Messages](/mavlink/adding_messages.md)
- [Streaming Messages](/mavlink/streaming_messages.md)
- [Receiving Messages](/mavlink/receiving_messages.md)
- [Custom MAVLink Messages](/mavlink/custom_messages.md)
- [Standard Modes Protocol](/mavlink/standard_modes.md)
- [uXRCE-DDS (PX4-ROS 2/DDS Bridge)](/middleware/uxrce_dds.md)
- [模块 & 命令](/modules/modules_main.md)
@@ -840,4 +851,4 @@
- [1.15 (stable)](/releases/1.15.md)
- [1.14](/releases/1.14.md)
- [1.13](/releases/1.13.md)
- [1.12](/releases/1.12.md)
- [1.12](/releases/1.12.md)
+5
View File
@@ -69,6 +69,11 @@ bool Serial::close()
return _impl.close();
}
ssize_t Serial::bytesAvailable()
{
return _impl.bytesAvailable();
}
ssize_t Serial::read(uint8_t *buffer, size_t buffer_size)
{
return _impl.read(buffer, buffer_size);
@@ -61,6 +61,7 @@ public:
bool close();
ssize_t bytesAvailable();
ssize_t read(uint8_t *buffer, size_t buffer_size);
ssize_t readAtLeast(uint8_t *buffer, size_t buffer_size, size_t character_count = 1, uint32_t timeout_ms = 0);
+17 -2
View File
@@ -259,6 +259,18 @@ bool SerialImpl::close()
return true;
}
ssize_t SerialImpl::bytesAvailable()
{
if (!_open) {
PX4_ERR("Device not open!");
return -1;
}
ssize_t bytes_available = 0;
int ret = ioctl(_serial_fd, FIONREAD, &bytes_available);
return ret >= 0 ? bytes_available : 0;
}
ssize_t SerialImpl::read(uint8_t *buffer, size_t buffer_size)
{
if (!_open) {
@@ -339,12 +351,15 @@ ssize_t SerialImpl::write(const void *buffer, size_t buffer_size)
}
int written = ::write(_serial_fd, buffer, buffer_size);
tcdrain(_serial_fd); // Wait until all output is transmitted
if (written < 0) {
PX4_ERR("%s write error %d", _port, written);
if (errno != EAGAIN) {
PX4_ERR("%s write error %d", _port, written);
}
}
::fsync(_serial_fd);
return written;
}
@@ -59,6 +59,7 @@ public:
bool close();
ssize_t bytesAvailable();
ssize_t read(uint8_t *buffer, size_t buffer_size);
ssize_t readAtLeast(uint8_t *buffer, size_t buffer_size, size_t character_count = 1, uint32_t timeout_us = 0);
@@ -48,6 +48,8 @@
#include <stdio.h>
#include <drivers/drv_input_capture.h>
#include <lib/perf/perf_counter.h>
// This can be overriden for a specific board.
#ifndef BOARD_DMA_NUM_DSHOT_CHANNELS
#define BOARD_DMA_NUM_DSHOT_CHANNELS 1
@@ -137,6 +139,8 @@ static uint32_t read_fail_nibble[MAX_NUM_CHANNELS_PER_TIMER] = {};
static uint32_t read_fail_crc[MAX_NUM_CHANNELS_PER_TIMER] = {};
static uint32_t read_fail_zero[MAX_NUM_CHANNELS_PER_TIMER] = {};
static perf_counter_t hrt_callback_perf = NULL;
static void init_timer_config(uint32_t channel_mask)
{
// Mark timers in use, channels in use, and timers for bidir dshot
@@ -202,20 +206,24 @@ static void init_timers_dma_up(void)
timer_configs[timer_index].dma_handle = stm32_dmachannel(io_timers[timer_index].dshot.dma_map_up);
if (timer_configs[timer_index].dma_handle == NULL) {
PX4_DEBUG("Failed to allocate Timer %u DMA UP", timer_index);
PX4_WARN("Failed to allocate Timer %u DMA UP", timer_index);
continue;
}
PX4_DEBUG("Allocated DMA UP Timer Index %u", timer_index);
PX4_INFO("Allocated DMA UP Timer Index %u", timer_index);
timer_configs[timer_index].initialized = true;
}
// Free the allocated DMA channels
for (uint8_t timer_index = 0; timer_index < MAX_IO_TIMERS; timer_index++) {
if (timer_configs[timer_index].dma_handle != NULL) {
stm32_dmafree(timer_configs[timer_index].dma_handle);
timer_configs[timer_index].dma_handle = NULL;
PX4_DEBUG("Freed DMA UP Timer Index %u", timer_index);
// Bidirectional DShot will free/allocate DMA stream on every update event. This is required
// in order to reconfigure the DMA stream between Timer Burst and CaptureCompare.
if (_bidirectional) {
// Free the allocated DMA channels
for (uint8_t timer_index = 0; timer_index < MAX_IO_TIMERS; timer_index++) {
if (timer_configs[timer_index].dma_handle != NULL) {
stm32_dmafree(timer_configs[timer_index].dma_handle);
timer_configs[timer_index].dma_handle = NULL;
PX4_INFO("Freed DMA UP Timer Index %u", timer_index);
}
}
}
}
@@ -275,6 +283,7 @@ int up_dshot_init(uint32_t channel_mask, unsigned dshot_pwm_freq, bool enable_bi
if (_bidirectional) {
PX4_INFO("Bidirectional DShot enabled, only one timer will be used");
hrt_callback_perf = perf_alloc(PC_ELAPSED, "dshot: callback perf");
}
// NOTE: if bidirectional is enabled only 1 timer can be used. This is because Burst mode uses 1 DMA channel per timer
@@ -336,8 +345,15 @@ void up_dshot_trigger()
io_timer_set_dshot_burst_mode(timer_index, _dshot_frequency, channel_count);
// Allocate DMA
if (timer_configs[timer_index].dma_handle == NULL) {
if (_bidirectional) {
// Deallocate DMA from previous transaction
if (timer_configs[timer_index].dma_handle != NULL) {
stm32_dmastop(timer_configs[timer_index].dma_handle);
stm32_dmafree(timer_configs[timer_index].dma_handle);
timer_configs[timer_index].dma_handle = NULL;
}
// Allocate DMA
timer_configs[timer_index].dma_handle = stm32_dmachannel(io_timers[timer_index].dshot.dma_map_up);
if (timer_configs[timer_index].dma_handle == NULL) {
@@ -485,6 +501,8 @@ void dma_burst_finished_callback(DMA_HANDLE handle, uint8_t status, void *arg)
static void capture_complete_callback(void *arg)
{
perf_begin(hrt_callback_perf);
uint8_t timer_index = *((uint8_t *)arg);
// Unallocate the timer as CaptureDMA
@@ -495,11 +513,8 @@ static void capture_complete_callback(void *arg)
// Disable capture DMA
io_timer_capture_dma_req(timer_index, capture_channel, false);
if (timer_configs[timer_index].dma_handle != NULL) {
stm32_dmastop(timer_configs[timer_index].dma_handle);
stm32_dmafree(timer_configs[timer_index].dma_handle);
timer_configs[timer_index].dma_handle = NULL;
}
// Stop DMA (should already be finished)
stm32_dmastop(timer_configs[timer_index].dma_handle);
// Re-initialize all output channels on this timer
for (uint8_t output_channel = 0; output_channel < MAX_TIMER_IO_CHANNELS; output_channel++) {
@@ -525,6 +540,8 @@ static void capture_complete_callback(void *arg)
// Enable all channels configured as DShotInverted
io_timer_set_enable(true, IOTimerChanMode_DshotInverted, IO_TIMER_ALL_MODES_CHANNELS);
perf_end(hrt_callback_perf);
}
void process_capture_results(uint8_t timer_index, uint8_t channel_index)
@@ -544,7 +561,7 @@ void process_capture_results(uint8_t timer_index, uint8_t channel_index)
} else {
// Convert the period to eRPM
_erpms[output_channel] = (1000000 * 60) / period;
_erpms[output_channel] = (1000000 * 60 / 100 + period / 2) / period;
}
// We set it ready anyway, not to hold up other channels when used in round robin.
+1
View File
@@ -59,6 +59,7 @@ public:
bool close();
ssize_t bytesAvailable();
ssize_t read(uint8_t *buffer, size_t buffer_size);
ssize_t readAtLeast(uint8_t *buffer, size_t buffer_size, size_t character_count = 1, uint32_t timeout_us = 0);
+17 -3
View File
@@ -251,6 +251,18 @@ bool SerialImpl::close()
return true;
}
ssize_t SerialImpl::bytesAvailable()
{
if (!_open) {
PX4_ERR("Device not open!");
return -1;
}
ssize_t bytes_available = 0;
int ret = ioctl(_serial_fd, FIONREAD, &bytes_available);
return ret >= 0 ? bytes_available : 0;
}
ssize_t SerialImpl::read(uint8_t *buffer, size_t buffer_size)
{
if (!_open) {
@@ -325,13 +337,15 @@ ssize_t SerialImpl::write(const void *buffer, size_t buffer_size)
}
int written = ::write(_serial_fd, buffer, buffer_size);
::fsync(_serial_fd);
if (written < 0) {
PX4_ERR("%s write error %d", _port, written);
if (errno != EAGAIN) {
PX4_ERR("%s write error %d", _port, written);
}
}
::fsync(_serial_fd);
return written;
}
@@ -101,7 +101,7 @@ int Pxh::process_line(const std::string &line, bool silently_fail)
// Note that argv[argc] always needs to be a nullptr.
// Therefore add one more entry.
const char *arg[words.size() + 1];
char **arg = new char *[words.size() + 1];
for (unsigned i = 0; i < words.size(); ++i) {
arg[i] = (char *)words[i].c_str();
@@ -110,7 +110,7 @@ int Pxh::process_line(const std::string &line, bool silently_fail)
// Explicitly set this nullptr.
arg[words.size()] = nullptr;
int retval = _apps[command](words.size(), (char **)arg);
int retval = _apps[command](words.size(), arg);
if (retval) {
if (!silently_fail) {
@@ -118,6 +118,8 @@ int Pxh::process_line(const std::string &line, bool silently_fail)
}
}
delete[] arg;
return retval;
} else if (command == "help") {
+1
View File
@@ -58,6 +58,7 @@ public:
bool close();
ssize_t bytesAvailable();
ssize_t read(uint8_t *buffer, size_t buffer_size);
ssize_t readAtLeast(uint8_t *buffer, size_t buffer_size, size_t character_count = 1, uint32_t timeout_us = 0);
+7
View File
@@ -158,6 +158,13 @@ bool SerialImpl::close()
return true;
}
ssize_t SerialImpl::bytesAvailable()
{
// TODO:
PX4_WARN("bytesAvailable not implemented!");
return 0;
}
ssize_t SerialImpl::read(uint8_t *buffer, size_t buffer_size)
{
if (!_open) {
+22 -4
View File
@@ -472,10 +472,16 @@ int GPS::pollOrRead(uint8_t *buf, size_t buf_length, int timeout)
const int max_timeout = 50;
int timeout_adjusted = math::min(max_timeout, timeout);
handleInjectDataTopic();
if (_interface == GPSHelper::Interface::UART) {
ret = _uart.readAtLeast(buf, buf_length, math::min(character_count, buf_length), timeout_adjusted);
const ssize_t read_at_least = math::min(character_count, buf_length);
// handle injection data before read if caught up
if (_uart.bytesAvailable() < read_at_least) {
handleInjectDataTopic();
}
ret = _uart.readAtLeast(buf, buf_length, read_at_least, timeout_adjusted);
if (ret > 0) {
_num_bytes_read += ret;
@@ -486,6 +492,8 @@ int GPS::pollOrRead(uint8_t *buf, size_t buf_length, int timeout)
} else if ((_interface == GPSHelper::Interface::SPI) && (_spi_fd >= 0)) {
handleInjectDataTopic();
//Poll only for the SPI data. In the same thread we also need to handle orb messages,
//so ideally we would poll on both, the SPI fd and orb subscription. Unfortunately the
//two pollings use different underlying mechanisms (at least under posix), which makes this
@@ -593,7 +601,17 @@ void GPS::handleInjectDataTopic()
}
}
updated = _orb_inject_data_sub[_selected_rtcm_instance].update(&msg);
auto &gps_inject_data_sub = _orb_inject_data_sub[_selected_rtcm_instance];
const unsigned last_generation = gps_inject_data_sub.get_last_generation();
updated = gps_inject_data_sub.update(&msg);
if (updated) {
if (gps_inject_data_sub.get_last_generation() != last_generation + 1) {
PX4_WARN("gps_inject_data lost, generation %u -> %u", last_generation, gps_inject_data_sub.get_last_generation());
}
}
} while (updated && num_injections < max_num_injections);
}
+1 -5
View File
@@ -84,11 +84,7 @@ UavcanEscController::update_outputs(bool stop_motors, uint16_t outputs[MAX_ACTUA
_prev_cmd_pub = timestamp;
/*
* Fill the command message
* If unarmed, we publish an empty message anyway
*/
uavcan::equipment::esc::RawCommand msg;
uavcan::equipment::esc::RawCommand msg = {};
for (unsigned i = 0; i < num_outputs; i++) {
if (stop_motors || outputs[i] == DISARMED_OUTPUT_VALUE) {
@@ -366,17 +366,24 @@ int do_accel_calibration(orb_advert_t *mavlink_log_pub)
const Matrix3f accel_T = mat_A.I() * CONSTANTS_ONE_G;
// update calibration
worker_data.calibration[i].set_offset(offset);
worker_data.calibration[i].set_scale(accel_T.diag());
const Dcmf &R = worker_data.calibration[i].rotation();
const Vector3f sensor_frame_offsets{R.transpose() *offset};
const Matrix3f sensor_frame_scale{R.transpose() *accel_T * R};
worker_data.calibration[i].set_offset(sensor_frame_offsets);
worker_data.calibration[i].set_scale(sensor_frame_scale.diag());
#if defined(DEBUD_BUILD)
PX4_INFO("accel %d: offset", i);
offset.print();
sensor_frame_offsets.print();
PX4_INFO("accel %d: mat_A", i);
mat_A.print();
PX4_INFO("accel %d: accel_T", i);
accel_T.print();
PX4_INFO("accel %d: scale matrix", i);
sensor_frame_scale.print();
#endif // DEBUD_BUILD
worker_data.calibration[i].PrintStatus();
@@ -392,3 +392,28 @@ TEST_F(FailsafeTest, skip_failsafe)
ASSERT_EQ(updated_user_intented_mode, state.user_intended_mode);
ASSERT_EQ(failsafe.selectedAction(), FailsafeBase::Action::Warn);
}
TEST_F(FailsafeTest, user_termination)
{
FailsafeTester failsafe(nullptr);
failsafe_flags_s failsafe_flags{};
FailsafeBase::State state{};
state.armed = true;
state.user_intended_mode = vehicle_status_s::NAVIGATION_STATE_TERMINATION;
state.vehicle_type = vehicle_status_s::VEHICLE_TYPE_ROTARY_WING;
hrt_abstime time = 5_s;
// User intended termination -> failsafe termination
uint8_t updated_user_intented_mode = failsafe.update(time, state, false, false, failsafe_flags);
EXPECT_EQ(updated_user_intented_mode, state.user_intended_mode);
EXPECT_EQ(failsafe.selectedAction(), FailsafeBase::Action::Terminate);
// Links lost during termination -> stay in termination
failsafe_flags.gcs_connection_lost = true;
failsafe_flags.manual_control_signal_lost = true;
updated_user_intented_mode = failsafe.update(time, state, false, false, failsafe_flags);
EXPECT_EQ(updated_user_intented_mode, state.user_intended_mode);
EXPECT_EQ(failsafe.selectedAction(), FailsafeBase::Action::Terminate);
}
+2 -1
View File
@@ -437,7 +437,8 @@ void FailsafeBase::getSelectedAction(const State &state, const failsafe_flags_s
returned_state.updated_user_intended_mode = state.user_intended_mode;
returned_state.cause = Cause::Generic;
if (_selected_action == Action::Terminate) { // Terminate never clears
if (state.user_intended_mode == vehicle_status_s::NAVIGATION_STATE_TERMINATION
|| _selected_action == Action::Terminate) { // Terminate never clears
returned_state.action = Action::Terminate;
return;
}
@@ -618,6 +618,7 @@ State FlightTaskAuto::_getCurrentState()
const Vector3f u_prev_to_target = (_triplet_target - _triplet_prev_wp).unit_or_zero();
const Vector3f prev_to_pos = _position - _triplet_prev_wp;
const Vector3f pos_to_target = _triplet_target - _position;
// Calculate the closest point to the vehicle position on the line prev_wp - target
_closest_pt = _triplet_prev_wp + u_prev_to_target * (prev_to_pos * u_prev_to_target);
@@ -635,10 +636,9 @@ State FlightTaskAuto::_getCurrentState()
// Previous is in front
return_state = State::previous_infront;
} else if ((_position - _closest_pt).longerThan(_target_acceptance_radius)) {
} else if (_type != WaypointType::land && (_position - _closest_pt).longerThan(_target_acceptance_radius)) {
// Vehicle too far from the track
return_state = State::offtrack;
}
return return_state;
@@ -80,6 +80,7 @@ MavlinkParametersManager::handle_message(const mavlink_message_t *msg)
#if defined(CONFIG_MAVLINK_UAVCAN_PARAMETERS)
if (req_list.target_system == mavlink_system.sysid && req_list.target_component < 127 &&
!(req_list.target_component >= MAV_COMP_ID_CAMERA && req_list.target_component <= MAV_COMP_ID_CAMERA6) &&
(req_list.target_component != mavlink_system.compid || req_list.target_component == MAV_COMP_ID_ALL)) {
// publish list request to UAVCAN driver via uORB.
uavcan_parameter_request_s req{};
@@ -139,6 +140,7 @@ MavlinkParametersManager::handle_message(const mavlink_message_t *msg)
#if defined(CONFIG_MAVLINK_UAVCAN_PARAMETERS)
if (set.target_system == mavlink_system.sysid && set.target_component < 127 &&
!(set.target_component >= MAV_COMP_ID_CAMERA && set.target_component <= MAV_COMP_ID_CAMERA6) &&
(set.target_component != mavlink_system.compid || set.target_component == MAV_COMP_ID_ALL)) {
// publish set request to UAVCAN driver via uORB.
uavcan_parameter_request_s req{};
@@ -217,6 +219,7 @@ MavlinkParametersManager::handle_message(const mavlink_message_t *msg)
#if defined(CONFIG_MAVLINK_UAVCAN_PARAMETERS)
if (req_read.target_system == mavlink_system.sysid && req_read.target_component < 127 &&
!(req_read.target_component >= MAV_COMP_ID_CAMERA && req_read.target_component <= MAV_COMP_ID_CAMERA6) &&
(req_read.target_component != mavlink_system.compid || req_read.target_component == MAV_COMP_ID_ALL)) {
// publish set request to UAVCAN driver via uORB.
uavcan_parameter_request_s req{};
+3
View File
@@ -606,6 +606,9 @@ void MavlinkReceiver::handle_message_command_both(mavlink_message_t *msg, const
send_ack = true;
}
} else if (cmd_mavlink.command == MAV_CMD_DO_SET_MODE) {
_cmd_pub.publish(vehicle_command);
} else if (cmd_mavlink.command == MAV_CMD_DO_AUTOTUNE_ENABLE) {
bool has_module = true;
@@ -58,6 +58,10 @@ public:
}
private:
/* Max 2.5 seconds delay for all possible modes to avoid ACK timeout in ground station */
static constexpr uint32_t MAX_DELAY_US = 2500000 / vehicle_status_s::NAVIGATION_STATE_MAX;
/* Only delay if the transmit of one mode takes at least 1ms, this avoids a lot of fast delay calls */
static constexpr uint32_t MIN_DELAY_THRESHOLD = 1000;
static constexpr int MAX_NUM_EXTERNAL_MODES = vehicle_status_s::NAVIGATION_STATE_EXTERNAL8 -
vehicle_status_s::NAVIGATION_STATE_EXTERNAL1 + 1;
@@ -76,8 +80,13 @@ private:
uint32_t _last_valid_nav_states_mask{0};
uint32_t _last_can_set_nav_states_mask{0};
void send_single_mode(const vehicle_status_s &vehicle_status, int mode_index, int total_num_modes, uint8_t nav_state)
void send_single_mode(const vehicle_status_s &vehicle_status, int mode_index, int total_num_modes, uint8_t nav_state,
uint32_t delay_us = 0)
{
if (delay_us > 0) {
px4_usleep(delay_us);
}
mavlink_available_modes_t available_modes{};
available_modes.mode_index = mode_index;
available_modes.number_modes = total_num_modes;
@@ -139,12 +148,18 @@ private:
int total_num_modes = math::countSetBits(vehicle_status.valid_nav_states_mask);
float mode_transmit_time = (float)(MAVLINK_MSG_ID_AVAILABLE_MODES_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES) /
_mavlink->get_data_rate();
uint32_t delay_us = (uint32_t)(mode_transmit_time * 1e6f);
delay_us = delay_us >= MIN_DELAY_THRESHOLD ? delay_us : 0;
delay_us = delay_us > MAX_DELAY_US ? MAX_DELAY_US : delay_us;
if (mode_index == 0) { // All
int cur_mode_index = 1;
for (uint8_t nav_state = 0; nav_state < vehicle_status_s::NAVIGATION_STATE_MAX; ++nav_state) {
if ((1u << nav_state) & vehicle_status.valid_nav_states_mask) {
send_single_mode(vehicle_status, cur_mode_index, total_num_modes, nav_state);
send_single_mode(vehicle_status, cur_mode_index, total_num_modes, nav_state, delay_us);
++cur_mode_index;
}
}
@@ -565,14 +565,33 @@ void MulticopterPositionControl::Run()
_control.setState(states);
// Run position control
if (!_control.update(dt)) {
// Failsafe
_vehicle_constraints = {0, NAN, NAN, false, {}}; // reset constraints
const hrt_abstime now = hrt_absolute_time();
_control.setInputSetpoint(generateFailsafeSetpoint(vehicle_local_position.timestamp_sample, states, true));
_control.setVelocityLimits(_param_mpc_xy_vel_max.get(), _param_mpc_z_vel_max_up.get(), _param_mpc_z_vel_max_dn.get());
_control.update(dt);
// Run position control
if (_control.update(dt)) {
// Valid control update - store for fallback
_last_valid_setpoint = _setpoint;
} else {
// Initial update failed - Try fallback if within timeout
if (now < _last_valid_setpoint.timestamp + 200_ms) {
// Use last valid setpoint
adjustSetpointForEKFResets(vehicle_local_position, _last_valid_setpoint);
_control.setInputSetpoint(_last_valid_setpoint);
}
// Still failing / not within timeout - Go to failsafe
if (!_control.update(dt)) {
_vehicle_constraints = {0, NAN, NAN, false, {}}; // reset constraints
_control.setInputSetpoint(generateFailsafeSetpoint(vehicle_local_position.timestamp_sample, states, true));
_control.setVelocityLimits(_param_mpc_xy_vel_max.get(), _param_mpc_z_vel_max_up.get(), _param_mpc_z_vel_max_dn.get());
_control.update(dt);
}
}
// Publish internal position control setpoints
@@ -113,6 +113,7 @@ private:
hrt_abstime _time_position_control_enabled{0};
trajectory_setpoint_s _setpoint{PositionControl::empty_trajectory_setpoint};
trajectory_setpoint_s _last_valid_setpoint{PositionControl::empty_trajectory_setpoint};
vehicle_control_mode_s _vehicle_control_mode{};
vehicle_constraints_s _vehicle_constraints {
+4
View File
@@ -263,6 +263,10 @@ void Mission::setActiveMissionItems()
pos_sp_triplet->next.valid = false;
}
} else if (_mission_item.nav_cmd == NAV_CMD_DELAY) {
// Invalidate next waypoint to ensure vehicle holds position and doesn't try to track ahead
pos_sp_triplet->next.valid = false;
} else {
handleVtolTransition(new_work_item_type, next_mission_items, num_found_items);
}
+3 -1
View File
@@ -553,7 +553,9 @@ void MissionBase::setEndOfMissionItems()
_mission_item.nav_cmd = NAV_CMD_IDLE;
} else {
if (pos_sp_triplet->current.valid && pos_sp_triplet->current.type == position_setpoint_s::SETPOINT_TYPE_LOITER) {
if (pos_sp_triplet->current.valid &&
(pos_sp_triplet->current.type == position_setpoint_s::SETPOINT_TYPE_LOITER ||
pos_sp_triplet->current.type == position_setpoint_s::SETPOINT_TYPE_POSITION)) {
setLoiterItemFromCurrentPositionSetpoint(&_mission_item);
} else {
@@ -122,6 +122,7 @@ void RtlDirectMissionLand::setActiveMissionItems()
{
WorkItemType new_work_item_type{WorkItemType::WORK_ITEM_TYPE_DEFAULT};
position_setpoint_triplet_s *pos_sp_triplet = _navigator->get_position_setpoint_triplet();
const position_setpoint_s current_setpoint_copy = pos_sp_triplet->current;
// Climb to altitude
if (_needs_climbing && _work_item_type == WorkItemType::WORK_ITEM_TYPE_DEFAULT) {
@@ -203,8 +204,6 @@ void RtlDirectMissionLand::setActiveMissionItems()
_mission_item.autocontinue = true;
_mission_item.time_inside = 0.0f;
pos_sp_triplet->previous = pos_sp_triplet->current;
}
if (num_found_items > 0) {
@@ -213,6 +212,12 @@ void RtlDirectMissionLand::setActiveMissionItems()
mission_item_to_position_setpoint(_mission_item, &pos_sp_triplet->current);
// Only set the previous position item if the current one really changed
if ((_work_item_type != WorkItemType::WORK_ITEM_TYPE_MOVE_TO_LAND) &&
!position_setpoint_equal(&pos_sp_triplet->current, &current_setpoint_copy)) {
pos_sp_triplet->previous = current_setpoint_copy;
}
// prevent lateral guidance from loitering at a waypoint as part of a mission landing if the altitude
// is not achieved.
const bool fw_on_mission_landing = _vehicle_status_sub.get().vehicle_type == vehicle_status_s::VEHICLE_TYPE_FIXED_WING
+7 -3
View File
@@ -91,6 +91,7 @@ void RtlMissionFast::setActiveMissionItems()
{
WorkItemType new_work_item_type{WorkItemType::WORK_ITEM_TYPE_DEFAULT};
position_setpoint_triplet_s *pos_sp_triplet = _navigator->get_position_setpoint_triplet();
const position_setpoint_s current_setpoint_copy = pos_sp_triplet->current;
/* Skip VTOL/FW Takeoff item if in air, fixed-wing and didn't start the takeoff already*/
if ((_mission_item.nav_cmd == NAV_CMD_VTOL_TAKEOFF || _mission_item.nav_cmd == NAV_CMD_TAKEOFF) &&
@@ -158,17 +159,20 @@ void RtlMissionFast::setActiveMissionItems()
_mission_item.autocontinue = true;
_mission_item.time_inside = 0.0f;
pos_sp_triplet->previous = pos_sp_triplet->current;
}
if (num_found_items > 0) {
mission_item_to_position_setpoint(next_mission_items[0u], &pos_sp_triplet->next);
}
mission_item_to_position_setpoint(_mission_item, &pos_sp_triplet->current);
// Only set the previous position item if the current one really changed
if ((_work_item_type != WorkItemType::WORK_ITEM_TYPE_MOVE_TO_LAND) &&
!position_setpoint_equal(&pos_sp_triplet->current, &current_setpoint_copy)) {
pos_sp_triplet->previous = current_setpoint_copy;
}
if (_vehicle_status_sub.get().vehicle_type == vehicle_status_s::VEHICLE_TYPE_FIXED_WING && isLanding() &&
_mission_item.nav_cmd == NAV_CMD_WAYPOINT) {
pos_sp_triplet->current.alt_acceptance_radius = FLT_MAX;
+1 -8
View File
@@ -5,13 +5,6 @@ parameters:
definitions:
# Gripper configuration
PD_GRIPPER_EN:
description:
short: Enable Gripper actuation in Payload Deliverer
type: boolean
default: 0
reboot_required: true
PD_GRIPPER_TYPE:
description:
short: Type of Gripper (Servo, etc.)
@@ -34,4 +27,4 @@ parameters:
type: float
unit: s
min: 0
default: 3
default: 1
@@ -54,7 +54,7 @@ bool PayloadDeliverer::init()
void PayloadDeliverer::configure_gripper()
{
// If gripper instance is invalid, and user enabled the gripper, try initializing it
if (!_gripper.is_valid() && _param_gripper_enable.get()) {
if (!_gripper.is_valid()) {
GripperConfig config{};
config.type = (GripperConfig::GripperType)_param_gripper_type.get();
config.sensor = GripperConfig::GripperSensorType::NONE; // Feedback sensor isn't supported for now
@@ -104,7 +104,7 @@ private:
/**
* @brief Initialize or deinitialize gripper instance based on parameter settings
*
* Depending on `PD_GRIPPER_EN` and the state of `_gripper` instance, this function will
* Depending on the state of `_gripper` instance, this function will
* either try to initialize or de-initialize the gripper appropriately.
*/
void configure_gripper();
@@ -159,7 +159,6 @@ private:
DEFINE_PARAMETERS(
(ParamFloat<px4::params::PD_GRIPPER_TO>) _param_gripper_timeout_s,
(ParamInt<px4::params::PD_GRIPPER_TYPE>) _param_gripper_type,
(ParamBool<px4::params::PD_GRIPPER_EN>) _param_gripper_enable
(ParamInt<px4::params::PD_GRIPPER_TYPE>) _param_gripper_type
)
};