Merge branch 'main' into pr_boat_decoupling

This commit is contained in:
Tomas Twardzik
2025-03-06 10:47:56 +01:00
committed by GitHub
317 changed files with 8729 additions and 8153 deletions
+1 -1
View File
@@ -96,6 +96,6 @@ jobs:
platforms: |
linux/amd64
provenance: mode=max
push: true
push: ${{ github.event_name != 'pull_request' }}
cache-from: type=s3,blobs_prefix=cache/${{ github.repository }}/,manifests_prefix=cache/${{ github.repository }}/,region=${{ env.RUNS_ON_AWS_REGION }},bucket=${{ env.RUNS_ON_S3_BUCKET_CACHE }}
cache-to: type=s3,blobs_prefix=cache/${{ github.repository }}/,manifests_prefix=cache/${{ github.repository }}/,region=${{ env.RUNS_ON_AWS_REGION }},bucket=${{ env.RUNS_ON_S3_BUCKET_CACHE }},mode=max
+59 -50
View File
@@ -1,5 +1,10 @@
name: FLASH usage analysis
permissions:
contents: read
pull-requests: write
issues: write
on:
push:
branches:
@@ -83,59 +88,63 @@ jobs:
echo '${{ steps.bloaty-step.outputs.bloaty-summary-map }}' >> $GITHUB_OUTPUT
echo "$EOF" >> $GITHUB_OUTPUT
post_pr_comment:
name: Publish Results
runs-on: [runs-on,runner=1cpu-linux-x64,image=ubuntu24-full-x64,"run-id=${{ github.run_id }}",spot=false]
needs: [analyze_flash]
env:
V5X-SUMMARY-MAP-ABS: ${{ fromJSON(fromJSON(needs.analyze_flash.outputs.px4_fmu-v5x-bloaty-summary-map).vm-absolute) }}
V5X-SUMMARY-MAP-PERC: ${{ fromJSON(fromJSON(needs.analyze_flash.outputs.px4_fmu-v5x-bloaty-summary-map).vm-percentage) }}
V6X-SUMMARY-MAP-ABS: ${{ fromJSON(fromJSON(needs.analyze_flash.outputs.px4_fmu-v6x-bloaty-summary-map).vm-absolute) }}
V6X-SUMMARY-MAP-PERC: ${{ fromJSON(fromJSON(needs.analyze_flash.outputs.px4_fmu-v6x-bloaty-summary-map).vm-percentage) }}
if: ${{ github.event.pull_request }}
steps:
- name: Find Comment
uses: peter-evans/find-comment@v3
id: fc
with:
issue-number: ${{ github.event.pull_request.number }}
comment-author: 'github-actions[bot]'
body-includes: FLASH Analysis
# TODO:
# This part of the workflow is causing errors, we should find a way to fix this and enable this test again
# Track this issue https://github.com/PX4/PX4-Autopilot/issues/24408
#
#post_pr_comment:
#name: Publish Results
#runs-on: [runs-on,runner=1cpu-linux-x64,image=ubuntu24-full-x64,"run-id=${{ github.run_id }}",spot=false]
#needs: [analyze_flash]
#env:
#V5X-SUMMARY-MAP-ABS: ${{ fromJSON(fromJSON(needs.analyze_flash.outputs.px4_fmu-v5x-bloaty-summary-map).vm-absolute) }}
#V5X-SUMMARY-MAP-PERC: ${{ fromJSON(fromJSON(needs.analyze_flash.outputs.px4_fmu-v5x-bloaty-summary-map).vm-percentage) }}
#V6X-SUMMARY-MAP-ABS: ${{ fromJSON(fromJSON(needs.analyze_flash.outputs.px4_fmu-v6x-bloaty-summary-map).vm-absolute) }}
#V6X-SUMMARY-MAP-PERC: ${{ fromJSON(fromJSON(needs.analyze_flash.outputs.px4_fmu-v6x-bloaty-summary-map).vm-percentage) }}
#if: ${{ github.event.pull_request }}
#steps:
#- name: Find Comment
#uses: peter-evans/find-comment@v3
#id: fc
#with:
#issue-number: ${{ github.event.pull_request.number }}
#comment-author: 'github-actions[bot]'
#body-includes: FLASH Analysis
- name: Set Build Time
id: bt
run: |
echo "timestamp=$(date +'%Y-%m-%dT%H:%M:%S')" >> $GITHUB_OUTPUT
#- name: Set Build Time
#id: bt
#run: |
#echo "timestamp=$(date +'%Y-%m-%dT%H:%M:%S')" >> $GITHUB_OUTPUT
- name: Create or update comment
# This can't be moved to the job-level conditions, as GH actions don't allow a job-level if condition to access the env.
if: |
steps.fc.outputs.comment-id != '' ||
env.V5X-SUMMARY-MAP-ABS >= fromJSON(env.MIN_FLASH_POS_DIFF_FOR_COMMENT) ||
env.V5X-SUMMARY-MAP-ABS <= fromJSON(env.MIN_FLASH_NEG_DIFF_FOR_COMMENT) ||
env.V6X-SUMMARY-MAP-ABS >= fromJSON(env.MIN_FLASH_POS_DIFF_FOR_COMMENT) ||
env.V6X-SUMMARY-MAP-ABS <= fromJSON(env.MIN_FLASH_NEG_DIFF_FOR_COMMENT)
uses: peter-evans/create-or-update-comment@v4
with:
comment-id: ${{ steps.fc.outputs.comment-id }}
issue-number: ${{ github.event.pull_request.number }}
body: |
## 🔎 FLASH Analysis
<details>
<summary>px4_fmu-v5x [Total VM Diff: ${{ env.V5X-SUMMARY-MAP-ABS }} byte (${{ env.V5X-SUMMARY-MAP-PERC}} %)]</summary>
#- name: Create or update comment
## This can't be moved to the job-level conditions, as GH actions don't allow a job-level if condition to access the env.
#if: |
#steps.fc.outputs.comment-id != '' ||
#env.V5X-SUMMARY-MAP-ABS >= fromJSON(env.MIN_FLASH_POS_DIFF_FOR_COMMENT) ||
#env.V5X-SUMMARY-MAP-ABS <= fromJSON(env.MIN_FLASH_NEG_DIFF_FOR_COMMENT) ||
#env.V6X-SUMMARY-MAP-ABS >= fromJSON(env.MIN_FLASH_POS_DIFF_FOR_COMMENT) ||
#env.V6X-SUMMARY-MAP-ABS <= fromJSON(env.MIN_FLASH_NEG_DIFF_FOR_COMMENT)
#uses: peter-evans/create-or-update-comment@v4
#with:
#comment-id: ${{ steps.fc.outputs.comment-id }}
#issue-number: ${{ github.event.pull_request.number }}
#body: |
### 🔎 FLASH Analysis
#<details>
#<summary>px4_fmu-v5x [Total VM Diff: ${{ env.V5X-SUMMARY-MAP-ABS }} byte (${{ env.V5X-SUMMARY-MAP-PERC}} %)]</summary>
```
${{ needs.analyze_flash.outputs.px4_fmu-v5x-bloaty-output }}
```
</details>
#```
#${{ needs.analyze_flash.outputs.px4_fmu-v5x-bloaty-output }}
#```
#</details>
<details>
<summary>px4_fmu-v6x [Total VM Diff: ${{ env.V6X-SUMMARY-MAP-ABS }} byte (${{ env.V6X-SUMMARY-MAP-PERC }} %)]</summary>
#<details>
#<summary>px4_fmu-v6x [Total VM Diff: ${{ env.V6X-SUMMARY-MAP-ABS }} byte (${{ env.V6X-SUMMARY-MAP-PERC }} %)]</summary>
```
${{ needs.analyze_flash.outputs.px4_fmu-v6x-bloaty-output }}
```
</details>
#```
#${{ needs.analyze_flash.outputs.px4_fmu-v6x-bloaty-output }}
#```
#</details>
**Updated: _${{ steps.bt.outputs.timestamp }}_**
edit-mode: replace
#**Updated: _${{ steps.bt.outputs.timestamp }}_**
#edit-mode: replace
+1 -1
View File
@@ -99,7 +99,7 @@
#
#=============================================================================
cmake_minimum_required(VERSION 3.9 FATAL_ERROR)
cmake_minimum_required(VERSION 3.10 FATAL_ERROR)
set(PX4_SOURCE_DIR "${CMAKE_CURRENT_SOURCE_DIR}" CACHE FILEPATH "PX4 source directory" FORCE)
set(PX4_BINARY_DIR "${CMAKE_CURRENT_BINARY_DIR}" CACHE FILEPATH "PX4 binary directory" FORCE)
Vendored
+2 -2
View File
@@ -235,9 +235,9 @@ pipeline {
sh('rm -f px4_msgs/srv/*.srv')
sh('rm -f px4_msgs/srv/versioned/*.srv')
sh('cp msg/*.msg px4_msgs/msg/')
sh('mkdir -p px4_msgs/msg/versioned && cp msg/versioned/*.msg px4_msgs/msg/versioned/')
sh('cp msg/versioned/*.msg px4_msgs/msg/ || true')
sh('cp srv/*.srv px4_msgs/srv/')
sh('mkdir -p px4_msgs/srv/versioned && cp srv/versioned/*.srv px4_msgs/srv/versioned/')
sh('cp srv/versioned/*.srv px4_msgs/srv/ || true')
sh('cd px4_msgs; git status; git add .; git commit -a -m "Update message definitions `date`" || true')
sh('cd px4_msgs; git push origin main || true')
sh('rm -rf px4_msgs')
-7
View File
@@ -73,13 +73,6 @@ menu "Toolchain"
help
relative path to the ROMFS root directory
config BOARD_ROOTFSDIR
string "Root directory"
depends on PLATFORM_POSIX
default "."
help
Configure the root directory in the file system for PX4 files
config BOARD_IO
string "IO board name"
default "px4_io-v2_default"
+42
View File
@@ -0,0 +1,42 @@
Maintainers
===========
See [the documentation on Maintainers](https://docs.px4.io/main/en/contribute/maintainers.html) to learn about the role of the maintainers and the process to become one.
**Active Maintainers**
| Name | Sector | GitHub | Chat | email
|-------------------------|--------|--------|------|----------------
| Lorenz Meier | Founder | [LorenzMeier][LorenzMeier] | | <lorenz@px4.io>
| Daniel Agar | Architecture | [dagar][dagar] | daniel_agar | <daniel@agar.ca>
| Beat Küng | Architecture | [bkueng][bkueng] | beatkueng | <beat-kueng@gmx.net>
| Ramón Roche | CI / Testing | [mrpollo][mrpollo] | rroche | <rroche@linuxfoundation.org>
| Mathieu Bresciani | State Estimation | [bresch][bresch] | mbresch |
| Paul Riseborough | State Estimation | [priseborough][priseborough] | |
| David Sidrane | RTOS / NuttX | [davids5][davids5] | david_s5 | <David.Sidrane@Nscdg.com>
| Jayoung Lim | Simulation | [Jaeyoung-Lim][Jaeyoung-Lim] | jaeyounglim. | <jalim@ethz.ch>
| Beniamino Pozzan | ROS 2 | [beniaminopozzan][beniaminopozzan] | beniaminopozzan | <beniamino.pozzan@gmail.com>
| Matthias Grob | Multirotor | [MaEtUgR][MaEtUgR] | maetugr |
| Silvan Fuhrer | Fixed-Wing / VTOL | [sfuhrer][sfuhrer] | sfuhrer |
| Christian Friedrich | Rover | [chfriedrich98][chfriedrich98] | christian982564 |
| Pedro Roque | Spacecraft | [Pedro-Roque][Pedro-Roque] | .pedroroque | <padr@kth.se>
**Documentation Maintainers**
| Name | GitHub | Chat | email
|------|--------|------|----------------------
| Hamish Willee | [hamishwillee][hamishwillee] | hamishwillee |
**Release Managers**
| Name | GitHub | Chat | email
|------|--------|------|----------------------
| Ramón Roche | [mrpollo][mrpollo] | rroche | <rroche@linuxfoundation.org>
| Daniel Agar | [dagar][dagar] | daniel_agar | <daniel@agar.ca>
**Retired Maintainers**
| Name | GitHub | Chat | email
|------|--------|------|----------------------
| | | |
+1 -5
View File
@@ -404,7 +404,7 @@ check_newlines:
# Testing
# --------------------------------------------------------------------
.PHONY: tests tests_coverage tests_mission tests_mission_coverage tests_offboard tests_avoidance
.PHONY: tests tests_coverage tests_mission tests_mission_coverage tests_offboard
.PHONY: rostest python_coverage
tests:
@@ -457,10 +457,6 @@ tests_offboard: rostest
@"$(SRC_DIR)"/test/rostest_px4_run.sh mavros_posix_tests_offboard_posctl.test
@"$(SRC_DIR)"/test/rostest_px4_run.sh mavros_posix_tests_offboard_rpyrt_ctl.test
tests_avoidance: rostest
@"$(SRC_DIR)"/test/rostest_avoidance_run.sh mavros_posix_test_avoidance.test
@"$(SRC_DIR)"/test/rostest_avoidance_run.sh mavros_posix_test_safe_landing.test
python_coverage:
@mkdir -p "$(SRC_DIR)"/build/python_coverage
@cd "$(SRC_DIR)"/build/python_coverage && cmake "$(SRC_DIR)" $(CMAKE_ARGS) -G"$(PX4_CMAKE_GENERATOR)" -DCONFIG=px4_sitl_default -DPYTHON_COVERAGE=ON
+11 -88
View File
@@ -17,17 +17,19 @@ PX4 is highly portable, OS-independent and supports Linux, NuttX and MacOS out o
* [VTOL](https://docs.px4.io/main/en/frames_vtol/)
* [Autogyro](https://docs.px4.io/main/en/frames_autogyro/)
* [Rover](https://docs.px4.io/main/en/frames_rover/)
* many more experimental types (Blimps, Boats, Submarines, High altitude balloons, etc)
* many more experimental types (Blimps, Boats, Submarines, High Altitude Balloons, Spacecraft, etc)
* Releases: [Downloads](https://github.com/PX4/PX4-Autopilot/releases)
## Releases
Release notes and supporting information for PX4 releases can be found on the [Developer Guide](https://docs.px4.io/main/en/releases/).
## Building a PX4 based drone, rover, boat or robot
The [PX4 User Guide](https://docs.px4.io/main/en/) explains how to assemble [supported vehicles](https://docs.px4.io/main/en/airframes/airframe_reference.html) and fly drones with PX4.
See the [forum and chat](https://docs.px4.io/main/en/#getting-help) if you need help!
The [PX4 User Guide](https://docs.px4.io/main/en/) explains how to assemble [supported vehicles](https://docs.px4.io/main/en/airframes/airframe_reference.html) and fly drones with PX4. See the [forum and chat](https://docs.px4.io/main/en/#getting-help) if you need help!
## Changing code and contributing
## Changing Code and Contributing
This [Developer Guide](https://docs.px4.io/main/en/development/development.html) is for software developers who want to modify the flight stack and middleware (e.g. to add new flight modes), hardware integrators who want to support new flight controller boards and peripherals, and anyone who wants to get PX4 working on a new (unsupported) airframe/vehicle.
@@ -35,7 +37,7 @@ Developers should read the [Guide for Contributions](https://docs.px4.io/main/en
See the [forum and chat](https://docs.px4.io/main/en/#getting-help) if you need help!
### Weekly Dev Call
## Weekly Dev Call
The PX4 Dev Team syncs up on a [weekly dev call](https://docs.px4.io/main/en/contribute/).
@@ -44,96 +46,17 @@ The PX4 Dev Team syncs up on a [weekly dev call](https://docs.px4.io/main/en/con
## Maintenance Team
Note: This is the source of truth for the active maintainers of PX4 ecosystem.
See the latest list of maintainers on [MAINTAINERS](MAINTAINERS.md) file at the root of the project.
| Sector | Maintainer |
|---|---|
| Founder | [Lorenz Meier](https://github.com/LorenzMeier) |
| Architecture | [Daniel Agar](https://github.com/dagar) / [Beat Küng](https://github.com/bkueng)|
| State Estimation | [Mathieu Bresciani](https://github.com/bresch) / [Paul Riseborough](https://github.com/priseborough) |
| OS/NuttX | [David Sidrane](https://github.com/davids5) |
| Drivers | [Daniel Agar](https://github.com/dagar) |
| Simulation | [Jaeyoung Lim](https://github.com/Jaeyoung-Lim) |
| ROS2 | [Beniamino Pozzan](https://github.com/beniaminopozzan) |
| Community QnA Call | [Ramon Roche](https://github.com/mrpollo) |
| [Documentation](https://docs.px4.io/main/en/) | [Hamish Willee](https://github.com/hamishwillee) |
| Vehicle Type | Maintainer |
|---|---|
| Multirotor | [Matthias Grob](https://github.com/MaEtUgR) |
| Fixed Wing | [Thomas Stastny](https://github.com/tstastny) |
| Hybrid VTOL | [Silvan Fuhrer](https://github.com/sfuhrer) |
| Rover | [Christian Friedrich](https://github.com/chfriedrich98) |
| Boat | x |
See also [maintainers list](https://px4.io/community/maintainers/) (px4.io) and the [contributors list](https://github.com/PX4/PX4-Autopilot/graphs/contributors) (Github). However it may be not up to date.
For the latest stats on contributors please see the latest stats for the Dronecode ecosystem in our project dashboard under [LFX Insights](https://insights.lfx.linuxfoundation.org/foundation/dronecode). For information on how to update your profile and affiliations please see the following support link on how to [Complete Your LFX Profile](https://docs.linuxfoundation.org/lfx/my-profile/complete-your-lfx-profile). Dronecode publishes a yearly snapshot of contributions and achievements on its [website under the Reports section](https://dronecode.org).
## Supported Hardware
Pixhawk standard boards and proprietary boards are shown below (discontinued boards aren't listed).
For the most up to date information, please visit [PX4 user Guide > Autopilot Hardware](https://docs.px4.io/main/en/flight_controller/).
### Pixhawk Standard Boards
These boards fully comply with Pixhawk Standard, and are maintained by the PX4-Autopilot maintainers and Dronecode team
* FMUv6X and FMUv6C
* [CUAV Pixahwk V6X (FMUv6X)](https://docs.px4.io/main/en/flight_controller/cuav_pixhawk_v6x.html)
* [Holybro Pixhawk 6X (FMUv6X)](https://docs.px4.io/main/en/flight_controller/pixhawk6x.html)
* [Holybro Pixhawk 6C (FMUv6C)](https://docs.px4.io/main/en/flight_controller/pixhawk6c.html)
* [Holybro Pix32 v6 (FMUv6C)](https://docs.px4.io/main/en/flight_controller/holybro_pix32_v6.html)
* FMUv5 and FMUv5X (STM32F7, 2019/20)
* [Pixhawk 4 (FMUv5)](https://docs.px4.io/main/en/flight_controller/pixhawk4.html)
* [Pixhawk 4 mini (FMUv5)](https://docs.px4.io/main/en/flight_controller/pixhawk4_mini.html)
* [CUAV V5+ (FMUv5)](https://docs.px4.io/main/en/flight_controller/cuav_v5_plus.html)
* [CUAV V5 nano (FMUv5)](https://docs.px4.io/main/en/flight_controller/cuav_v5_nano.html)
* [Auterion Skynode (FMUv5X)](https://docs.auterion.com/avionics/skynode)
* FMUv4 (STM32F4, 2015)
* [Pixracer](https://docs.px4.io/main/en/flight_controller/pixracer.html)
* [Pixhawk 3 Pro](https://docs.px4.io/main/en/flight_controller/pixhawk3_pro.html)
* FMUv3 (STM32F4, 2014)
* [Pixhawk 2](https://docs.px4.io/main/en/flight_controller/pixhawk-2.html)
* [Pixhawk Mini](https://docs.px4.io/main/en/flight_controller/pixhawk_mini.html)
* [CUAV Pixhack v3](https://docs.px4.io/main/en/flight_controller/pixhack_v3.html)
* FMUv2 (STM32F4, 2013)
* [Pixhawk](https://docs.px4.io/main/en/flight_controller/pixhawk.html)
### Manufacturer supported
These boards are maintained to be compatible with PX4-Autopilot by the Manufacturers.
* [ARK Electronics ARKV6X](https://docs.px4.io/main/en/flight_controller/ark_v6x.html)
* [CubePilot Cube Orange+](https://docs.px4.io/main/en/flight_controller/cubepilot_cube_orangeplus.html)
* [CubePilot Cube Orange](https://docs.px4.io/main/en/flight_controller/cubepilot_cube_orange.html)
* [CubePilot Cube Yellow](https://docs.px4.io/main/en/flight_controller/cubepilot_cube_yellow.html)
* [Holybro Durandal](https://docs.px4.io/main/en/flight_controller/durandal.html)
* [Airmind MindPX V2.8](http://www.mindpx.net/assets/accessories/UserGuide_MindPX.pdf)
* [Airmind MindRacer V1.2](http://mindpx.net/assets/accessories/mindracer_user_guide_v1.2.pdf)
* [Holybro Kakute F7](https://docs.px4.io/main/en/flight_controller/kakutef7.html)
### Community supported
These boards don't fully comply industry standards, and thus is solely maintained by the PX4 public community members.
### Experimental
These boards are not maintained by PX4 team nor Manufacturer, and is not guaranteed to be compatible with up to date PX4 releases.
* [Raspberry PI with Navio 2](https://docs.px4.io/main/en/flight_controller/raspberry_pi_navio2.html)
* [Bitcraze Crazyflie 2.0](https://docs.px4.io/main/en/complete_vehicles/crazyflie2.html)
## Project Roadmap
**Note: Outdated**
A high level project roadmap is available [here](https://github.com/orgs/PX4/projects/25).
For the most up to date information, please visit [PX4 User Guide > Autopilot Hardware](https://docs.px4.io/main/en/flight_controller/).
## Project Governance
The PX4 Autopilot project including all of its trademarks is hosted under [Dronecode](https://www.dronecode.org/), part of the Linux Foundation.
<a href="https://www.dronecode.org/" style="padding:20px" ><img src="https://mavlink.io/assets/site/logo_dronecode.png" alt="Dronecode Logo" width="110px"/></a>
<a href="https://www.linuxfoundation.org/projects" style="padding:20px;"><img src="https://mavlink.io/assets/site/logo_linux_foundation.png" alt="Linux Foundation Logo" width="80px" /></a>
<a href="https://www.dronecode.org/" style="padding:20px" ><img src="https://dronecode.org/wp-content/uploads/sites/24/2020/08/dronecode_logo_default-1.png" alt="Dronecode Logo" width="110px"/></a>
<div style="padding:10px">&nbsp;</div>
@@ -1,6 +1,6 @@
############################################################################
#
# Copyright (c) 2024 PX4 Development Team. All rights reserved.
# Copyright (c) 2025 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
@@ -31,8 +31,4 @@
#
############################################################################
px4_add_library(RoverMecanumGuidance
RoverMecanumGuidance.cpp
)
target_include_directories(RoverMecanumGuidance PUBLIC ${CMAKE_CURRENT_SOURCE_DIR})
add_subdirectory(init.d)
@@ -1,6 +1,6 @@
############################################################################
#
# Copyright (c) 2018 PX4 Development Team. All rights reserved.
# Copyright (c) 2025 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
@@ -31,9 +31,6 @@
#
############################################################################
px4_add_library(bezier
BezierQuad.cpp
BezierN.cpp
px4_add_romfs_files(
rcS
)
px4_add_unit_gtest(SRC BezierNTest.cpp LINKLIBS bezier)
+68
View File
@@ -0,0 +1,68 @@
#!/bin/sh
# Un comment and use set +e to ignore and set -e to enable 'exit on error control'
set +e
# Un comment the line below to help debug scripts by printing a trace of the script commands
#set -x
# PX4FMU startup script.
#
# NOTE: environment variable references:
# If the dollar sign ('$') is followed by a left bracket ('{') then the
# variable name is terminated with the right bracket character ('}').
# Otherwise, the variable name goes to the end of the argument.
#
#
# NOTE: COMMENT LINES ARE REMOVED BEFORE STORED IN ROMFS.
#
#------------------------------------------------------------------------------
set R /
#
# Print full system version.
#
ver all
#
# Set the parameter file the board supports params on
# MTD device.
#
if mft query -q -k MTD -s MTD_PARAMETERS -v /fs/mtd_params
then
set PARAM_FILE /fs/mtd_params
fi
#
# Load parameters.
#
# if the board has a storage for (factory) calibration data
if mft query -q -k MTD -s MTD_CALDATA -v /fs/mtd_caldata
then
param load /fs/mtd_caldata
fi
#
# Load parameters.
#
param select $PARAM_FILE
if ! param load
then
param reset_all
fi
#
# Try to mount the microSD card.
#
mount -t vfat /dev/mmcsd0 /fs/microsd
if [ $? = 0 ]
then
echo "SD card mounted at /fs/microsd"
else
echo "No SD card found"
fi
unset R
echo ""
echo "!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!"
echo "!!!!!! This is the PERFORMANCE TESTING firmware! WARNs and ERRORs are expected! !!!!!"
echo "!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!"
echo ""
@@ -1,32 +0,0 @@
#!/bin/sh
#
# @name 3DR Iris Quadrotor SITL (Obstacle Avoidance)
#
# @type Quadrotor Wide
#
. ${R}etc/init.d/rc.mc_defaults
param set-default CA_AIRFRAME 0
param set-default CA_ROTOR_COUNT 4
param set-default CA_ROTOR0_PX 0.1515
param set-default CA_ROTOR0_PY 0.245
param set-default CA_ROTOR0_KM 0.05
param set-default CA_ROTOR1_PX -0.1515
param set-default CA_ROTOR1_PY -0.1875
param set-default CA_ROTOR1_KM 0.05
param set-default CA_ROTOR2_PX 0.1515
param set-default CA_ROTOR2_PY -0.245
param set-default CA_ROTOR2_KM -0.05
param set-default CA_ROTOR3_PX -0.1515
param set-default CA_ROTOR3_PY 0.1875
param set-default CA_ROTOR3_KM -0.05
param set-default PWM_MAIN_FUNC1 101
param set-default PWM_MAIN_FUNC2 102
param set-default PWM_MAIN_FUNC3 103
param set-default PWM_MAIN_FUNC4 104
param set-default COM_OBS_AVOID 1
@@ -1,2 +0,0 @@
# shellcheck disable=SC2154
mavlink start -x -u 14558 -r 4000000 -m onboard -o 14541 -p # add mavlink stream for SDK
@@ -13,10 +13,6 @@ PX4_SIM_MODEL=${PX4_SIM_MODEL:=x500}
param set-default SIM_GZ_EN 1
param set-default SENS_EN_GPSSIM 1
param set-default SENS_EN_BAROSIM 0
param set-default SENS_EN_MAGSIM 1
param set-default CA_AIRFRAME 0
param set-default CA_ROTOR_COUNT 4
@@ -12,13 +12,8 @@ PX4_SIM_MODEL=${PX4_SIM_MODEL:=rc_cessna}
param set-default SIM_GZ_EN 1
param set-default SENS_EN_GPSSIM 1
param set-default SENS_EN_BAROSIM 0
param set-default SENS_EN_MAGSIM 1
param set-default SENS_EN_ARSPDSIM 1
param set-default FW_LND_ANG 8
param set-default NPFG_PERIOD 12
@@ -13,9 +13,6 @@ PX4_SIM_MODEL=${PX4_SIM_MODEL:=standard_vtol}
param set-default SIM_GZ_EN 1
param set-default SENS_EN_GPSSIM 1
param set-default SENS_EN_BAROSIM 0
param set-default SENS_EN_MAGSIM 1
param set-default SENS_EN_ARSPDSIM 1
# TODO: Enable motor failure detection when the
@@ -14,12 +14,7 @@ PX4_SIM_MODEL=${PX4_SIM_MODEL:=px4vision}
param set-default SIM_GZ_EN 1
param set-default SENS_EN_GPSSIM 1
param set-default SENS_EN_BAROSIM 0
param set-default SENS_EN_MAGSIM 1
# Commander Parameters
param set-default COM_OBS_AVOID 0
param set-default COM_DISARM_LAND 0.5
# EKF2 parameters
@@ -11,8 +11,6 @@ PX4_SIM_MODEL=${PX4_SIM_MODEL:=advanced_plane}
param set-default SIM_GZ_EN 1
param set-default SENS_EN_GPSSIM 1
param set-default SENS_EN_MAGSIM 1
param set-default SENS_EN_ARSPDSIM 1
param set-default FW_LND_ANG 8
@@ -11,35 +11,39 @@ PX4_SIM_MODEL=${PX4_SIM_MODEL:=r1_rover}
param set-default SIM_GZ_EN 1 # Gazebo bridge
# Rover parameters
param set-default NAV_ACC_RAD 0.5
# Differential Parameters
param set-default RD_WHEEL_TRACK 0.3
param set-default RD_MAX_ACCEL 5
param set-default RD_MAX_DECEL 10
param set-default RD_MAX_JERK 30
param set-default RD_MAX_THR_YAW_R 1.5
param set-default RD_YAW_RATE_P 0.25
param set-default RD_YAW_RATE_I 0.01
param set-default RD_YAW_P 5
param set-default RD_YAW_I 0.1
param set-default RD_MAX_SPEED 2
param set-default RD_MAX_THR_SPD 2.15
param set-default RD_SPEED_P 0.1
param set-default RD_SPEED_I 0.01
param set-default RD_MAX_YAW_RATE 180
param set-default RD_TRANS_DRV_TRN 0.349066
param set-default RD_TRANS_TRN_DRV 0.174533
param set-default RD_MAX_YAW_ACCEL 1000
# Pure pursuit parameters
param set-default PP_LOOKAHD_MAX 30
param set-default PP_LOOKAHD_MIN 2
# Rover Control Parameters
param set-default RO_ACCEL_LIM 5
param set-default RO_DECEL_LIM 10
param set-default RO_JERK_LIM 30
param set-default RO_MAX_THR_SPEED 2.1
# Rover Rate Control Parameters
param set-default RO_YAW_RATE_I 0.01
param set-default RO_YAW_RATE_P 0.25
param set-default RO_YAW_RATE_LIM 180
param set-default RO_YAW_ACCEL_LIM 120
param set-default RO_YAW_DECEL_LIM 1000
# Rover Attitude Control Parameters
param set-default RO_YAW_P 5
# Rover Position Control Parameters
param set-default RO_SPEED_LIM 2
param set-default RO_SPEED_I 0.5
param set-default RO_SPEED_P 1
# Pure Pursuit parameters
param set-default PP_LOOKAHD_GAIN 1
# Simulated sensors
param set-default SENS_EN_GPSSIM 1
param set-default SENS_EN_BAROSIM 0
param set-default SENS_EN_MAGSIM 1
param set-default SENS_EN_ARSPDSIM 0
param set-default PP_LOOKAHD_MAX 10
param set-default PP_LOOKAHD_MIN 1
# Actuator mapping
param set-default SIM_GZ_WH_FUNC1 101 # right wheel
@@ -11,11 +11,6 @@ PX4_SIM_MODEL=${PX4_SIM_MODEL:=lawnmower}
param set-default SIM_GZ_EN 1 # Gazebo bridge
# Simulated sensors
param set-default SENS_EN_GPSSIM 1
param set-default SENS_EN_BAROSIM 0
param set-default SENS_EN_MAGSIM 1
param set-default SENS_EN_ARSPDSIM 0
# We can arm and drive in manual mode when it slides and GPS check fails:
param set-default COM_ARM_WO_GPS 1
@@ -44,12 +44,6 @@ param set-default PP_LOOKAHD_GAIN 1
param set-default PP_LOOKAHD_MAX 10
param set-default PP_LOOKAHD_MIN 1
# Simulated sensors
param set-default SENS_EN_GPSSIM 1
param set-default SENS_EN_BAROSIM 0
param set-default SENS_EN_MAGSIM 1
param set-default SENS_EN_ARSPDSIM 0
# Wheels
param set-default SIM_GZ_WH_FUNC1 101
param set-default SIM_GZ_WH_MIN1 0
@@ -11,34 +11,41 @@ PX4_SIM_MODEL=${PX4_SIM_MODEL:=r1_rover_mecanum}
param set-default SIM_GZ_EN 1 # Gazebo bridge
# Rover parameters
param set-default RM_WHEEL_TRACK 0.3
param set-default RM_YAW_RATE_I 0.1
param set-default RM_YAW_RATE_P 0.1
param set-default RM_MAX_ACCEL 3
param set-default RM_MAX_DECEL 5
param set-default RM_MAX_JERK 5
param set-default RM_MAX_SPEED 2
param set-default RM_MAX_THR_SPD 2.2
param set-default RM_MAX_THR_YAW_R 1.2
param set-default RM_YAW_P 5
param set-default RM_YAW_I 0.1
param set-default RM_MAX_YAW_RATE 120
param set-default RM_MAX_YAW_ACCEL 240
param set-default RM_MISS_VEL_GAIN 1
param set-default RM_SPEED_I 0.01
param set-default RM_SPEED_P 0.1
param set-default NAV_ACC_RAD 0.5
# Pure pursuit parameters
# Mecanum Parameters
param set-default RM_WHEEL_TRACK 0.3
param set-default RM_MAX_THR_YAW_R 1.2
param set-default RM_MISS_SPD_GAIN 1
# Rover Control Parameters
param set-default RO_ACCEL_LIM 3
param set-default RO_DECEL_LIM 5
param set-default RO_JERK_LIM 30
param set-default RO_MAX_THR_SPEED 2.1
# Rover Rate Control Parameters
param set-default RO_YAW_RATE_I 0.1
param set-default RO_YAW_RATE_P 0.1
param set-default RO_YAW_RATE_LIM 120
param set-default RO_YAW_ACCEL_LIM 240
param set-default RO_YAW_DECEL_LIM 1000
# Rover Attitude Control Parameters
param set-default RO_YAW_P 5
# Rover Position Control Parameters
param set-default RO_SPEED_LIM 2
param set-default RO_SPEED_I 0.5
param set-default RO_SPEED_P 1
# Pure Pursuit parameters
param set-default PP_LOOKAHD_GAIN 0.5
param set-default PP_LOOKAHD_MAX 10
param set-default PP_LOOKAHD_MIN 1
param set-default PP_LOOKAHD_GAIN 0.5
# Simulated sensors
param set-default SENS_EN_GPSSIM 1
param set-default SENS_EN_BAROSIM 0
param set-default SENS_EN_MAGSIM 1
param set-default SENS_EN_ARSPDSIM 0
# Actuator mapping
param set-default SIM_GZ_WH_FUNC1 102 # right wheel front
@@ -13,12 +13,6 @@ PX4_SIM_MODEL=${PX4_SIM_MODEL:=quadtailsitter}
param set-default SIM_GZ_EN 1 # Gazebo bridge
param set-default SENS_EN_GPSSIM 1
param set-default SENS_EN_BAROSIM 0
param set-default SENS_EN_MAGSIM 1
param set-default SENS_EN_ARSPDSIM 0
param set-default MAV_TYPE 20
param set-default CA_AIRFRAME 4
@@ -13,11 +13,6 @@ PX4_SIM_MODEL=${PX4_SIM_MODEL:=tiltrotor}
param set-default SIM_GZ_EN 1 # Gazebo bridge
param set-default SENS_EN_GPSSIM 1
param set-default SENS_EN_BAROSIM 0
param set-default SENS_EN_MAGSIM 1
param set-default SENS_EN_ARSPDSIM 0
param set-default MAV_TYPE 21
param set-default CA_AIRFRAME 3
@@ -0,0 +1,15 @@
#!/bin/sh
#
# @name Gazebo x500 with downward optical flow and distance sensor
#
# @type Quadrotor
#
PX4_SIM_MODEL=${PX4_SIM_MODEL:=x500_flow}
. ${R}etc/init.d-posix/airframes/4001_gz_x500
echo "Disabling Sim GPS"
param set-default SYS_HAS_GPS 0
param set-default SIM_GPS_USED 0
param set-default EKF2_GPS_CTRL 0
@@ -15,8 +15,6 @@ PX4_SIM_MODEL=${PX4_SIM_MODEL:=spacecraft_2d}
param set-default SIM_GZ_EN 1
param set-default SENS_EN_GPSSIM 1
param set-default SENS_EN_BAROSIM 1
param set-default SENS_EN_MAGSIM 1
param set-default COM_ARM_CHK_ESCS 0 # We don't have ESCs
param set-default FD_ESCS_EN 0 # We don't have ESCs - but maybe we need this later?
@@ -83,9 +83,6 @@ param set-default CA_ROTOR7_AY -0.211325
param set-default CA_ROTOR7_AZ -0.57735
param set-default SIM_GZ_EN 1
param set-default SENS_EN_GPSSIM 1
param set-default SENS_EN_BAROSIM 0
param set-default SENS_EN_MAGSIM 1
param set-default SIM_GZ_EC_FUNC1 101
param set-default SIM_GZ_EC_FUNC2 102
@@ -39,8 +39,6 @@ px4_add_romfs_files(
1012_gazebo-classic_iris_rplidar
1013_gazebo-classic_iris_vision
1013_gazebo-classic_iris_vision.post
1014_gazebo-classic_iris_obs_avoid
1014_gazebo-classic_iris_obs_avoid.post
1015_gazebo-classic_iris_depth_camera
1016_gazebo-classic_iris_downward_depth_camera
1017_gazebo-classic_iris_opt_flow_mockup
@@ -93,6 +91,7 @@ px4_add_romfs_files(
4018_gz_quadtailsitter
4019_gz_x500_gimbal
4020_gz_tiltrotor
4021_gz_x500_flow
6011_gazebo-classic_typhoon_h480
6011_gazebo-classic_typhoon_h480.post
@@ -73,13 +73,13 @@ elif [ "$PX4_SIMULATOR" = "gz" ] || [ "$(param show -q SIM_GZ_EN)" = "1" ]; then
exit 1
fi
# look for running ${gz_command} gazebo world
# 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' )
# shellcheck disable=SC2153
if [ -z "${gz_world}" ] && [ -n "${PX4_GZ_WORLD}" ]; then
# source generated gz_env.sh for GZ_SIM_RESOURCE_PATH
# Setup gz environment variables
if [ -f ./gz_env.sh ]; then
. ./gz_env.sh
@@ -87,62 +87,125 @@ elif [ "$PX4_SIMULATOR" = "gz" ] || [ "$(param show -q SIM_GZ_EN)" = "1" ]; then
. ../gz_env.sh
fi
echo "INFO [init] starting gazebo with world: ${PX4_GZ_WORLDS}/${PX4_GZ_WORLD}.sdf"
echo "INFO [init] Starting gazebo with world: ${PX4_GZ_WORLDS}/${PX4_GZ_WORLD}.sdf"
${gz_command} ${gz_sub_command} --verbose=1 -r -s "${PX4_GZ_WORLDS}/${PX4_GZ_WORLD}.sdf" &
${gz_command} ${gz_sub_command} --verbose=${GZ_VERBOSE:=1} -r -s "${PX4_GZ_WORLDS}/${PX4_GZ_WORLD}.sdf" &
if [ -z "${HEADLESS}" ]; then
# HEADLESS not set, starting gui
${gz_command} ${gz_sub_command} -g &
echo "INFO [init] Starting gz gui"
${gz_command} ${gz_sub_command} -g > /dev/null 2>&1 &
fi
else
# Gazebo is already running, do not start the simulator, nor the GUI
# Gazebo is already running
echo "INFO [init] gazebo already running world: ${gz_world}"
PX4_GZ_WORLD=${gz_world}
fi
else
echo "INFO [init] Standalone PX4 launch, waiting for Gazebo"
fi
# start gz_bridge
# Start gz_bridge - either spawn a model or connect to existing one
if [ -n "${PX4_SIM_MODEL#*gz_}" ] && [ -z "${PX4_GZ_MODEL_NAME}" ]; then
# model specified, gz_bridge will spawn model
# Spawn a model
MODEL_NAME="${PX4_SIM_MODEL#*gz_}"
MODEL_NAME_INSTANCE="${MODEL_NAME}_${px4_instance}"
POSE_ARG=""
if [ -n "${PX4_GZ_MODEL_POSE}" ]; then
# model pose provided: [x, y, z, roll, pitch, yaw]
pos_x=$(echo "${PX4_GZ_MODEL_POSE}" | awk -F',' '{print $1}')
pos_y=$(echo "${PX4_GZ_MODEL_POSE}" | awk -F',' '{print $2}')
pos_z=$(echo "${PX4_GZ_MODEL_POSE}" | awk -F',' '{print $3}')
pos_x=${pos_x:-0}
pos_y=${pos_y:-0}
pos_z=${pos_z:-0}
# Clean potential input line formatting.
model_pose="$( echo "${PX4_GZ_MODEL_POSE}" | sed -e 's/^[ \t]*//; s/[ \t]*$//; s/,/ /g; s/ / /g; s/ /,/g' )"
echo "INFO [init] PX4_GZ_MODEL_POSE set, spawning at: ${model_pose}"
else
# model pose not provided, origin will be used
echo "WARN [init] PX4_GZ_MODEL_POSE not set, spawning at origin."
model_pose="0,0,0,0,0,0"
POSE_ARG=", pose: { position: { x: ${pos_x}, y: ${pos_y}, z: ${pos_z} } }"
echo "INFO [init] Spawning model at position: ${pos_x} ${pos_y} ${pos_z}"
fi
# start gz bridge with pose arg.
if ! gz_bridge start -p "${model_pose}" -m "${PX4_SIM_MODEL#*gz_}" -w "${PX4_GZ_WORLD}" -i "${px4_instance}"; then
echo "INFO [init] Spawning model"
# Spawn model
${gz_command} service -s "/world/${PX4_GZ_WORLD}/create" --reqtype gz.msgs.EntityFactory \
--reptype gz.msgs.Boolean --timeout 5000 \
--req "sdf_filename: \"${PX4_GZ_MODELS}/${MODEL_NAME}\", name: \"${MODEL_NAME_INSTANCE}\", allow_renaming: false${POSE_ARG}" > /dev/null 2>&1
# Start gz_bridge
if ! gz_bridge start -w "${PX4_GZ_WORLD}" -n "${MODEL_NAME_INSTANCE}"; then
echo "ERROR [init] gz_bridge failed to start and spawn model"
exit 1
fi
elif [ -n "${PX4_GZ_MODEL_NAME}" ]; then
# model name specificed, gz_bridge will attach to existing model
# Set physics parameters for faster-than-realtime simulation if needed
check_scene_info() {
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
else
return 1
fi
}
ATTEMPTS=30
while [ $ATTEMPTS -gt 0 ]; do
if check_scene_info; then
echo "INFO [init] Gazebo world is ready"
break
fi
ATTEMPTS=$((ATTEMPTS-1))
if [ $ATTEMPTS -eq 0 ]; then
echo "ERROR [init] Timed out waiting for Gazebo world"
exit 1
fi
echo "INFO [init] Waiting for Gazebo world..."
sleep 1
done
if [ -n "${PX4_SIM_SPEED_FACTOR}" ]; then
echo "INFO [init] Setting simulation speed factor: ${PX4_SIM_SPEED_FACTOR}"
${gz_command} service -s "/world/${PX4_GZ_WORLD}/set_physics" --reqtype gz.msgs.Physics \
--reptype gz.msgs.Boolean --timeout 5000 \
--req "real_time_factor: ${PX4_SIM_SPEED_FACTOR}" > /dev/null 2>&1
fi
# Set up camera to follow the model if requested
if [ -n "${PX4_GZ_FOLLOW}" ]; then
# Wait for model to spawn
sleep 1
echo "INFO [init] Setting camera to follow ${MODEL_NAME_INSTANCE}"
# Set camera to follow the model
${gz_command} service -s "/gui/follow" --reqtype gz.msgs.StringMsg \
--reptype gz.msgs.Boolean --timeout 5000 \
--req "data: \"${MODEL_NAME_INSTANCE}\"" > /dev/null 2>&1
# Set default camera offset if not specified
follow_x=${PX4_GZ_FOLLOW_OFFSET_X:--2.0}
follow_y=${PX4_GZ_FOLLOW_OFFSET_Y:--2.0}
follow_z=${PX4_GZ_FOLLOW_OFFSET_Z:-2.0}
# Set camera offset
${gz_command} service -s "/gui/follow/offset" --reqtype gz.msgs.Vector3d \
--reptype gz.msgs.Boolean --timeout 5000 \
--req "x: ${follow_x}, y: ${follow_y}, z: ${follow_z}" > /dev/null 2>&1
echo "INFO [init] Camera follow offset set to ${follow_x}, ${follow_y}, ${follow_z}"
fi
elif [ -n "${PX4_GZ_MODEL_NAME}" ]; then
# Connect to existing model
echo "INFO [init] PX4_GZ_MODEL_NAME set, PX4 will attach to existing model"
if ! gz_bridge start -n "${PX4_GZ_MODEL_NAME}" -w "${PX4_GZ_WORLD}"; then
if ! gz_bridge start -w "${PX4_GZ_WORLD}" -n "${PX4_GZ_MODEL_NAME}"; then
echo "ERROR [init] gz_bridge failed to start and attach to existing model"
exit 1
fi
else
echo "ERROR [init] failed to pass only PX4_GZ_MODEL_NAME or PX4_SIM_MODEL"
echo "ERROR [init] failed to pass either PX4_GZ_MODEL_NAME or PX4_SIM_MODEL"
exit 1
fi
# Start the sensor simulator modules
if param compare -s SENS_EN_BAROSIM 1
then
+5
View File
@@ -337,6 +337,11 @@ then
payload_deliverer start
fi
if param compare -s ICE_EN 1
then
internal_combustion_engine_control start
fi
#user defined mavlink streams for instances can be in PATH
. px4-rc.mavlink
@@ -12,7 +12,6 @@
. ${R}etc/init.d/rc.mc_defaults
# Commander Parameters
param set-default COM_OBS_AVOID 1
param set-default COM_DISARM_LAND 0.5
# EKF2 parameters
@@ -12,7 +12,6 @@
. ${R}etc/init.d/rc.mc_defaults
# Commander Parameters
param set-default COM_OBS_AVOID 1
param set-default COM_DISARM_LAND 0.5
# EKF2 parameters
@@ -21,26 +21,37 @@ param set-default RBCLW_FUNC1 101
param set-default RBCLW_FUNC2 102
param set-default RBCLW_REV 1 # reverse right wheels
# Rover parameters
param set-default NAV_ACC_RAD 0.5
# Differential Parameters
param set-default RD_WHEEL_TRACK 0.3
param set-default RD_MAX_ACCEL 3
param set-default RD_MAX_DECEL 4
param set-default RD_MAX_JERK 5
param set-default RD_MAX_SPEED 1.6
param set-default RD_MAX_THR_SPD 1.9
param set-default RD_MAX_THR_YAW_R 0.7
param set-default RD_MAX_YAW_ACCEL 600
param set-default RD_MAX_YAW_RATE 250
param set-default RD_SPEED_P 0.1
param set-default RD_SPEED_I 0.01
param set-default RD_TRANS_DRV_TRN 0.785398
param set-default RD_TRANS_TRN_DRV 0.139626
param set-default RD_YAW_P 5
param set-default RD_YAW_I 0.1
param set-default RD_YAW_RATE_P 0.1
param set-default RD_YAW_RATE_I 0.01
# Pure pursuit parameters
# Rover Control Parameters
param set-default RO_ACCEL_LIM 3
param set-default RO_DECEL_LIM 4
param set-default RO_JERK_LIM 5
param set-default RO_MAX_THR_SPEED 1.9
# Rover Rate Control Parameters
param set-default RO_YAW_RATE_I 0.01
param set-default RO_YAW_RATE_P 0.1
param set-default RO_YAW_RATE_LIM 250
param set-default RO_YAW_ACCEL_LIM 600
param set-default RO_YAW_DECEL_LIM 600
# Rover Attitude Control Parameters
param set-default RO_YAW_P 5
# Rover Position Control Parameters
param set-default RO_SPEED_LIM 1.6
param set-default RO_SPEED_I 0.01
param set-default RO_SPEED_P 0.1
# Pure Pursuit parameters
param set-default PP_LOOKAHD_GAIN 1
param set-default PP_LOOKAHD_MAX 10
param set-default PP_LOOKAHD_MIN 1
param set-default PP_LOOKAHD_GAIN 1
+12 -4
View File
@@ -488,11 +488,14 @@ else
rc_input start $RC_INPUT_ARGS
# Manages USB interface
if ! cdcacm_autostart start
if param greater -s SYS_USB_AUTO -1
then
sercon
echo "Starting MAVLink on /dev/ttyACM0"
mavlink start -d /dev/ttyACM0
if ! cdcacm_autostart start
then
sercon
echo "Starting MAVLink on /dev/ttyACM0"
mavlink start -d /dev/ttyACM0
fi
fi
#
@@ -555,6 +558,11 @@ else
payload_deliverer start
fi
if param compare -s ICE_EN 1
then
internal_combustion_engine_control start
fi
#
# Optional board supplied extras: rc.board_extras
#
-3
View File
@@ -136,9 +136,6 @@ class TestHardwareMethods(unittest.TestCase):
def test_atomic_bitset(self):
self.assertTrue(do_test(self.TEST_DEVICE, self.TEST_BAUDRATE, "atomic_bitset"))
def test_bezier(self):
self.assertTrue(do_test(self.TEST_DEVICE, self.TEST_BAUDRATE, "bezier"))
def test_bitset(self):
self.assertTrue(do_test(self.TEST_DEVICE, self.TEST_BAUDRATE, "bitset"))
+9
View File
@@ -26,6 +26,15 @@ do
# - Incrementing the version
# - An old .msg version exists
# - A translation header exists and is included
# Ignore changes to comments or constants
content_a=$(git show "${BASE_COMMIT}:${file}" | grep -o '^[^#]*' | grep -v =)
content_b=$(git show "${HEAD_COMMIT}:${file}" | grep -o '^[^#]*' | grep -v =)
if [ "${content_a}" == "${content_b}" ]; then
echo "No version update required for ${file}"
continue
fi
diff=$(git --no-pager diff --no-color --diff-filter=M "${BASE_COMMIT}"..."${HEAD_COMMIT}" -- "${file}")
old_version=$(echo "${diff}" | sed -n 's/^-uint32 MESSAGE_VERSION = \([0-9]*\).*/\1/p')
new_version=$(echo "${diff}" | sed -n 's/^+uint32 MESSAGE_VERSION = \([0-9]*\).*/\1/p')
+1 -1
View File
@@ -69,7 +69,7 @@ def process_target(px4board_file, target_name):
group = None
if px4board_file.endswith("default.px4board") or \
px4board_file.endswith("recovery.px4board") or \
px4board_file.endswith("performance-test.px4board") or \
px4board_file.endswith("bootloader.px4board"):
kconf.load_config(px4board_file, replace=True)
else: # Merge config with default.px4board
+1 -2
View File
@@ -29,6 +29,5 @@ then
rm -rf "${PX4_MSGS_DIR}"/srv/*.srv
fi
cp -ar "${PX4_SRC_DIR}"/msg/*.msg "${PX4_MSGS_DIR}"/msg
mkdir -p "${PX4_MSGS_DIR}"/msg/versioned
cp -ar "${PX4_SRC_DIR}"/msg/versioned/*.msg "${PX4_MSGS_DIR}"/msg/versioned
cp -ar "${PX4_SRC_DIR}"/msg/versioned/*.msg "${PX4_MSGS_DIR}"/msg
cp -ar "${PX4_SRC_DIR}"/srv/*.srv "${PX4_MSGS_DIR}"/srv
+1 -1
View File
@@ -47,6 +47,7 @@ CCACHE_DIR=${HOME}/.ccache
mkdir -p "${CCACHE_DIR}"
docker run -it --rm -w "${SRC_DIR}" \
--user="$(id -u):$(id -g)" \
--env=AWS_ACCESS_KEY_ID \
--env=AWS_SECRET_ACCESS_KEY \
--env=BRANCH_NAME \
@@ -54,7 +55,6 @@ docker run -it --rm -w "${SRC_DIR}" \
--env=CI \
--env=CODECOV_TOKEN \
--env=COVERALLS_REPO_TOKEN \
--env=LOCAL_USER_ID="$(id -u)" \
--env=PX4_ASAN \
--env=PX4_MSAN \
--env=PX4_TSAN \
+1
View File
@@ -74,6 +74,7 @@ exception_list_sitl = [
'SYSTEMCMDS_I2CDETECT', # Not supported in SITL
'SYSTEMCMDS_DMESG', # Not supported in SITL
'SYSTEMCMDS_USB_CONNECTED', # Not supported in SITL
'SYSTEMCMDS_MFT_CFG', # Not supported in SITL
'MODULES_SPACECRAFT', # Clashes with Control Allocation (mom's spaghetti code)
]
+1 -1
View File
@@ -708,7 +708,7 @@ class uploader:
# https://github.com/PX4/Firmware/blob/master/src/drivers/boards/common/stm32/board_mcu_version.c#L125-L144
if self.fw_maxsize > fw.property('image_maxsize') and not force:
raise RuntimeError(f"Board can accept larger flash images ({self.fw_maxsize} bytes) than board config ({fw.property('image_maxsize')} bytes). Please use the correct board configuration to avoid lacking critical functionality.")
print(f"WARNING: Board can accept larger flash images ({self.fw_maxsize} bytes) than board config ({fw.property('image_maxsize')} bytes)")
else:
# If we're still on bootloader v4 on a Pixhawk, we don't know if we
# have the silicon errata and therefore need to flash px4_fmu-v2
+1 -15
View File
@@ -1,6 +1,5 @@
#!/bin/bash
echo "[docker-entrypoint.sh] Starting entrypoint"
# Start virtual X server in the background
# - DISPLAY default is :99, set in dockerfile
# - Users can override with `-e DISPLAY=` in `docker run` command to avoid
@@ -17,17 +16,4 @@ if [ -n "${ROS_DISTRO}" ]; then
source "/opt/ros/$ROS_DISTRO/setup.bash"
fi
echo "[docker-entrypoint.sh] Working Directory: ${pwd}"
# Use the LOCAL_USER_ID if passed in at runtime
if [ -n "${LOCAL_USER_ID}" ]; then
echo "[docker-entrypoint.sh] Starting with: $LOCAL_USER_ID:user"
# modify existing user's id
usermod -u $LOCAL_USER_ID user
# run as user
# exec gosu user "$@"
exec "$@"
else
exec "$@"
fi
exec "$@"
+1
View File
@@ -116,6 +116,7 @@ if [[ $INSTALL_NUTTX == "true" ]]; then
binutils-dev \
bison \
build-essential \
curl \
flex \
g++-multilib \
gcc-arm-none-eabi \
+1 -1
View File
@@ -4,7 +4,7 @@
#------------------------------------------------------------------------------
param set-default CBRK_IO_SAFETY 0
param set-default MBE_ENABLE 1
param set-default MBE_ENABLE 0
param set-default SENS_IMU_CLPNOTI 0
safety_button start
@@ -7,7 +7,7 @@ param set-default CBRK_IO_SAFETY 0
param set-default CANNODE_SUB_MBD 1
param set-default CANNODE_SUB_RTCM 1
param set-default GPS_1_GNSS 63
param set-default MBE_ENABLE 1
param set-default MBE_ENABLE 0
param set-default SENS_IMU_CLPNOTI 0
safety_button start
@@ -3,6 +3,7 @@
# board specific defaults
#------------------------------------------------------------------------------
param set-default MBE_ENABLE 0
param set-default SENS_IMU_CLPNOTI 0
pwm_out start
@@ -32,7 +32,7 @@ CONFIG_BOARD_LOOPSPERMSEC=95150
CONFIG_BOARD_RESET_ON_ASSERT=2
CONFIG_CDCACM=y
CONFIG_CDCACM_IFLOWCONTROL=y
CONFIG_CDCACM_PRODUCTID=0x0039
CONFIG_CDCACM_PRODUCTID=0x003A
CONFIG_CDCACM_PRODUCTSTR="ARK BL Pi6X.x"
CONFIG_CDCACM_RXBUFSIZE=600
CONFIG_CDCACM_TXBUFSIZE=12000
+1 -1
View File
@@ -76,7 +76,7 @@ CONFIG_BOARD_RESET_ON_ASSERT=2
CONFIG_BUILTIN=y
CONFIG_CDCACM=y
CONFIG_CDCACM_IFLOWCONTROL=y
CONFIG_CDCACM_PRODUCTID=0x0039
CONFIG_CDCACM_PRODUCTID=0x003A
CONFIG_CDCACM_PRODUCTSTR="ARK Pi6X.x"
CONFIG_CDCACM_RXBUFSIZE=600
CONFIG_CDCACM_TXBUFSIZE=12000
@@ -6,7 +6,7 @@
param set-default CBRK_IO_SAFETY 0
param set-default CANNODE_SUB_MBD 1
param set-default CANNODE_SUB_RTCM 1
param set-default MBE_ENABLE 1
param set-default MBE_ENABLE 0
param set-default SENS_IMU_CLPNOTI 0
safety_button start
+1 -1
View File
@@ -6,7 +6,7 @@
param set-default CBRK_IO_SAFETY 0
param set-default CANNODE_SUB_MBD 1
param set-default CANNODE_SUB_RTCM 1
param set-default MBE_ENABLE 1
param set-default MBE_ENABLE 0
param set-default SENS_IMU_CLPNOTI 0
tone_alarm start
@@ -139,7 +139,7 @@ private:
// nrf chip schedules battery updates with SYSLINK_SEND_PERIOD_MS
static constexpr uint32_t SYSLINK_BATTERY_STATUS_INTERVAL_US = 10_ms;
Battery _battery{1, nullptr, SYSLINK_BATTERY_STATUS_INTERVAL_US, battery_status_s::BATTERY_SOURCE_POWER_MODULE};
Battery _battery{1, nullptr, SYSLINK_BATTERY_STATUS_INTERVAL_US, battery_status_s::SOURCE_POWER_MODULE};
int32_t _rssi;
battery_state _bstate;
@@ -13,6 +13,7 @@ CONFIG_DRIVERS_MAGNETOMETER_QMC5883L=y
CONFIG_DRIVERS_POWER_MONITOR_VOXLPM=y
CONFIG_DRIVERS_QSHELL_QURT=y
CONFIG_DRIVERS_RC_CRSF_RC=y
CONFIG_DRIVERS_VOXL2_IO=y
CONFIG_MODULES_COMMANDER=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_EKF2=y
@@ -207,15 +207,15 @@ void GhstRc::Run()
if (new_bytes > 0) {
_bytes_rx += new_bytes;
int8_t ghst_rssi = -1;
bool rc_updated = ghst_parse(cycle_timestamp, &_rcs_buf[0], new_bytes, &_raw_rc_values[0], &ghst_rssi,
ghstLinkStatistics_t link_stats = { .rssi_pct = -1, .rssi_dbm = NAN, .link_quality = 0 };
bool rc_updated = ghst_parse(cycle_timestamp, &_rcs_buf[0], new_bytes, &_raw_rc_values[0], &link_stats,
&_raw_rc_count, GHST_MAX_NUM_CHANNELS);
if (rc_updated) {
_last_packet_seen = time_now_us;
// we have a new GHST frame. Publish it.
_rc_in.input_source = input_rc_s::RC_INPUT_SOURCE_PX4FMU_GHST;
fill_rc_in(_raw_rc_count, _raw_rc_values, cycle_timestamp, false, false, 0, ghst_rssi);
fill_rc_in(_raw_rc_count, _raw_rc_values, cycle_timestamp, false, false, 0, link_stats.rssi_pct);
// ghst telemetry works on fmu-v5
// on other Pixhawk (-related) boards we cannot write to the RC UART
+1 -1
View File
@@ -1,7 +1,7 @@
CONFIG_PLATFORM_POSIX=y
CONFIG_BOARD_LINUX_TARGET=y
CONFIG_BOARD_TOOLCHAIN="aarch64-linux-gnu"
CONFIG_BOARD_ROOTFSDIR="/data/px4"
CONFIG_BOARD_ROOT_PATH="/data/px4"
CONFIG_DRIVERS_ACTUATORS_VOXL_ESC=y
CONFIG_DRIVERS_GPS=y
CONFIG_DRIVERS_OSD_MSP_OSD=y
@@ -0,0 +1,31 @@
CONFIG_BOARD_TOOLCHAIN="arm-none-eabi"
CONFIG_BOARD_ARCHITECTURE="cortex-m7"
CONFIG_BOARD_ETHERNET=y
CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS0"
CONFIG_BOARD_SERIAL_GPS2="/dev/ttyS7"
CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS6"
CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS4"
CONFIG_BOARD_SERIAL_TEL3="/dev/ttyS1"
CONFIG_BOARD_SERIAL_EXT2="/dev/ttyS3"
CONFIG_BOARD_ROMFSROOT="performance-test"
CONFIG_DRIVERS_ADC_BOARD_ADC=y
CONFIG_SYSTEMCMDS_DMESG=y
CONFIG_SYSTEMCMDS_GPIO=y
CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y
CONFIG_SYSTEMCMDS_I2CDETECT=y
CONFIG_SYSTEMCMDS_LED_CONTROL=y
CONFIG_SYSTEMCMDS_MFT=y
CONFIG_SYSTEMCMDS_MTD=y
CONFIG_SYSTEMCMDS_MFT_CFG=y
CONFIG_SYSTEMCMDS_PARAM=y
CONFIG_SYSTEMCMDS_PERF=y
CONFIG_SYSTEMCMDS_REBOOT=y
CONFIG_SYSTEMCMDS_SD_BENCH=y
CONFIG_SYSTEMCMDS_SD_STRESS=y
CONFIG_SYSTEMCMDS_SERIAL_TEST=y
CONFIG_SYSTEMCMDS_SYSTEM_TIME=y
CONFIG_SYSTEMCMDS_TOP=y
CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y
CONFIG_SYSTEMCMDS_UORB=y
CONFIG_SYSTEMCMDS_VER=y
CONFIG_SYSTEMCMDS_WORK_QUEUE=y
@@ -0,0 +1,31 @@
CONFIG_BOARD_TOOLCHAIN="arm-none-eabi"
CONFIG_BOARD_ARCHITECTURE="cortex-m7"
CONFIG_BOARD_ETHERNET=y
CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS0"
CONFIG_BOARD_SERIAL_GPS2="/dev/ttyS7"
CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS6"
CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS4"
CONFIG_BOARD_SERIAL_TEL3="/dev/ttyS1"
CONFIG_BOARD_SERIAL_EXT2="/dev/ttyS3"
CONFIG_BOARD_ROMFSROOT="performance-test"
CONFIG_DRIVERS_ADC_BOARD_ADC=y
CONFIG_SYSTEMCMDS_DMESG=y
CONFIG_SYSTEMCMDS_GPIO=y
CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y
CONFIG_SYSTEMCMDS_I2CDETECT=y
CONFIG_SYSTEMCMDS_LED_CONTROL=y
CONFIG_SYSTEMCMDS_MFT=y
CONFIG_SYSTEMCMDS_MTD=y
CONFIG_SYSTEMCMDS_MFT_CFG=y
CONFIG_SYSTEMCMDS_PARAM=y
CONFIG_SYSTEMCMDS_PERF=y
CONFIG_SYSTEMCMDS_REBOOT=y
CONFIG_SYSTEMCMDS_SD_BENCH=y
CONFIG_SYSTEMCMDS_SD_STRESS=y
CONFIG_SYSTEMCMDS_SERIAL_TEST=y
CONFIG_SYSTEMCMDS_SYSTEM_TIME=y
CONFIG_SYSTEMCMDS_TOP=y
CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y
CONFIG_SYSTEMCMDS_UORB=y
CONFIG_SYSTEMCMDS_VER=y
CONFIG_SYSTEMCMDS_WORK_QUEUE=y
+2
View File
@@ -50,7 +50,9 @@ CONFIG_MODULES_ROVER_MECANUM=y
CONFIG_MODULES_ROVER_POS_CONTROL=y
CONFIG_MODULES_SENSORS=y
CONFIG_COMMON_SIMULATION=y
CONFIG_MODULES_SIMULATION_GZ_MSGS=y
CONFIG_MODULES_SIMULATION_GZ_BRIDGE=y
CONFIG_MODULES_SIMULATION_GZ_PLUGINS=y
CONFIG_MODULES_SIMULATION_SENSOR_AGP_SIM=y
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
CONFIG_MODULES_UUV_ATT_CONTROL=y
+1 -1
View File
@@ -35,7 +35,7 @@ if(EXISTS ${BOARD_DEFCONFIG})
# Depend on BOARD_DEFCONFIG so that we reconfigure on config change
set_property(DIRECTORY APPEND PROPERTY CMAKE_CONFIGURE_DEPENDS ${BOARD_DEFCONFIG})
if(${LABEL} MATCHES "default" OR ${LABEL} MATCHES "recovery" OR ${LABEL} MATCHES "bootloader" OR ${LABEL} MATCHES "canbootloader")
if(${LABEL} MATCHES "default" OR ${LABEL} MATCHES "performance-test" OR ${LABEL} MATCHES "bootloader" OR ${LABEL} MATCHES "canbootloader")
# Generate boardconfig from saved defconfig
execute_process(
COMMAND ${CMAKE_COMMAND} -E env ${COMMON_KCONFIG_ENV_SETTINGS}
@@ -1,88 +0,0 @@
{
"fileType": "Plan",
"geoFence": {
"circles": [
],
"polygons": [
],
"version": 2
},
"groundStation": "QGroundControl",
"mission": {
"cruiseSpeed": 15,
"firmwareType": 12,
"hoverSpeed": 5,
"items": [
{
"AMSLAltAboveTerrain": null,
"Altitude": 4,
"AltitudeMode": 0,
"autoContinue": true,
"command": 22,
"doJumpId": 1,
"frame": 3,
"params": [
0,
0,
0,
null,
47.3977432,
8.5456085,
4
],
"type": "SimpleItem"
},
{
"AMSLAltAboveTerrain": null,
"Altitude": 4,
"AltitudeMode": 0,
"autoContinue": true,
"command": 16,
"doJumpId": 2,
"frame": 3,
"params": [
0,
0,
0,
null,
47.3977432,
8.5458765,
4
],
"type": "SimpleItem"
},
{
"AMSLAltAboveTerrain": null,
"Altitude": -1,
"AltitudeMode": 0,
"autoContinue": true,
"command": 21,
"doJumpId": 3,
"frame": 3,
"params": [
0,
0,
0,
null,
47.3977432,
8.5458812,
-1
],
"type": "SimpleItem"
}
],
"plannedHomePosition": [
47.3977419,
8.5458854,
487.923
],
"vehicleType": 2,
"version": 2
},
"rallyPoints": {
"points": [
],
"version": 2
},
"version": 1
}
-2
View File
@@ -5,6 +5,4 @@ float32 indicated_airspeed_m_s # indicated airspeed in m/s
float32 true_airspeed_m_s # true filtered airspeed in m/s
float32 air_temperature_celsius # air temperature in degrees Celsius, -1000 if unknown
float32 confidence # confidence value from 0 to 1 for this sensor
-8
View File
@@ -1,8 +0,0 @@
uint64 timestamp # time since system start (microseconds)
uint8 len # length of data
uint32 MAX_BUFLEN = 128
uint8[128] data # data
# TOPICS voxl2_io_data
+2 -12
View File
@@ -48,7 +48,6 @@ set(msg_files
AirspeedValidated.msg
AirspeedWind.msg
AutotuneAttitudeControlStatus.msg
Buffer128.msg
ButtonEvent.msg
CameraCapture.msg
CameraStatus.msg
@@ -114,6 +113,7 @@ set(msg_files
HeaterStatus.msg
HoverThrustEstimate.msg
InputRc.msg
InternalCombustionEngineControl.msg
InternalCombustionEngineStatus.msg
IridiumsbdStatus.msg
IrlockReport.msg
@@ -173,17 +173,11 @@ set(msg_files
RcParameterMap.msg
RoverAttitudeSetpoint.msg
RoverAttitudeStatus.msg
RoverVelocityStatus.msg
RoverRateSetpoint.msg
RoverRateStatus.msg
RoverSteeringSetpoint.msg
RoverThrottleSetpoint.msg
RoverDifferentialGuidanceStatus.msg
RoverDifferentialSetpoint.msg
RoverDifferentialStatus.msg
RoverMecanumGuidanceStatus.msg
RoverMecanumSetpoint.msg
RoverMecanumStatus.msg
RoverVelocityStatus.msg
Rpm.msg
RtlStatus.msg
RtlTimeEstimate.msg
@@ -214,8 +208,6 @@ set(msg_files
TelemetryStatus.msg
TiltrotorExtraControls.msg
TimesyncStatus.msg
TrajectoryBezier.msg
TrajectoryWaypoint.msg
TransponderReport.msg
TuneControl.msg
UavcanParameterRequest.msg
@@ -235,8 +227,6 @@ set(msg_files
VehicleRoi.msg
VehicleThrustSetpoint.msg
VehicleTorqueSetpoint.msg
VehicleTrajectoryBezier.msg
VehicleTrajectoryWaypoint.msg
VelocityLimits.msg
WheelEncoders.msg
Wind.msg
+2
View File
@@ -20,3 +20,5 @@ float32[4] q
float32 angular_velocity_x
float32 angular_velocity_y
float32 angular_velocity_z
uint8 ORB_QUEUE_LENGTH = 2
+8
View File
@@ -0,0 +1,8 @@
uint64 timestamp # time since system start (microseconds)
bool ignition_on # activate/deactivate ignition (Spark Plug)
float32 throttle_control # [0,1] - Motor should idle with 0. Includes slew rate if enabled.
float32 choke_control # [0,1] - 1 fully closes the air inlet.
float32 starter_engine_control # [0,1] - control value for electric starter motor.
uint8 user_request # user intent for the ICE being on/off
+3
View File
@@ -18,3 +18,6 @@ uint8 target_system # System ID (can be 0 for broadcast, but this is discou
uint8 target_component # Component ID (can be 0 for broadcast, but this is discouraged)
uint8 payload_length # Length of the data transported in payload
uint8[128] payload # Data itself
# Topic aliases for known payload types
# TOPICS mavlink_tunnel esc_serial_passthru
-2
View File
@@ -7,6 +7,4 @@ float32 target_bearing # Bearing angle from aircraft to current target [rad]
float32 xtrack_error # Signed track error [m]
float32 wp_dist # Distance to active (next) waypoint [m]
float32 acceptance_radius # Current horizontal acceptance radius [m]
float32 yaw_acceptance # Yaw acceptance error[rad]
float32 altitude_acceptance # Current vertical acceptance error [m]
uint8 type # Current (applied) position setpoint type (see PositionSetpoint.msg)
-7
View File
@@ -1,7 +0,0 @@
uint64 timestamp # time since system start (microseconds)
float32 lookahead_distance # [m] Lookahead distance of pure the pursuit controller
float32 heading_error_deg # [deg] Heading error of the pure pursuit controller
uint8 state_machine # Driving state of the rover [0: SPOT_TURNING, 1: DRIVING, 2: GOAL_REACHED]
# TOPICS rover_differential_guidance_status
-9
View File
@@ -1,9 +0,0 @@
uint64 timestamp # time since system start (microseconds)
float32 forward_speed_setpoint # [m/s] Desired forward speed for the rover
float32 forward_speed_setpoint_normalized # [-1, 1] Normalized forward speed for the rover
float32 yaw_rate_setpoint # [rad/s] Desired yaw rate for the rover (Overriden by yaw controller if yaw_setpoint is used)
float32 speed_diff_setpoint_normalized # [-1, 1] Normalized speed difference between the left and right wheels
float32 yaw_setpoint # [rad] Desired yaw (heading) for the rover
# TOPICS rover_differential_setpoint
-14
View File
@@ -1,14 +0,0 @@
uint64 timestamp # time since system start (microseconds)
float32 measured_forward_speed # [m/s] Measured speed in body x direction. Forwards: positiv, Backwards: negativ
float32 adjusted_forward_speed_setpoint # [m/s] Speed setpoint after applying slew rate
float32 measured_yaw # [rad] Measured yaw
float32 adjusted_yaw_setpoint # [rad] Yaw setpoint after applying slew rate
float32 clyaw_yaw_rate_setpoint # [rad/s] Yaw rate setpoint output by the closed loop yaw controller
float32 measured_yaw_rate # [rad/s] Measured yaw rate
float32 adjusted_yaw_rate_setpoint # [rad/s] Yaw rate setpoint from the closed loop yaw controller
float32 pid_yaw_integral # Integral of the PID for the closed loop yaw controller
float32 pid_yaw_rate_integral # Integral of the PID for the closed loop yaw rate controller
float32 pid_throttle_integral # Integral of the PID for the closed loop speed controller
# TOPICS rover_differential_status
-7
View File
@@ -1,7 +0,0 @@
uint64 timestamp # time since system start (microseconds)
float32 lookahead_distance # [m] Lookahead distance of pure the pursuit controller
float32 heading_error # [rad] Heading error of the pure pursuit controller
float32 desired_speed # [m/s] Desired velocity magnitude (speed)
# TOPICS rover_mecanum_guidance_status
-11
View File
@@ -1,11 +0,0 @@
uint64 timestamp # time since system start (microseconds)
float32 forward_speed_setpoint # [m/s] Desired forward speed
float32 forward_speed_setpoint_normalized # [-1, 1] Desired normalized forward speed
float32 lateral_speed_setpoint # [m/s] Desired lateral speed
float32 lateral_speed_setpoint_normalized # [-1, 1] Desired normalized lateral speed
float32 yaw_rate_setpoint # [rad/s] Desired yaw rate
float32 speed_diff_setpoint_normalized # [-1, 1] Normalized speed difference between the left and right wheels
float32 yaw_setpoint # [rad] Desired yaw (heading)
# TOPICS rover_mecanum_setpoint
-17
View File
@@ -1,17 +0,0 @@
uint64 timestamp # time since system start (microseconds)
float32 measured_forward_speed # [m/s] Measured speed in body x direction. Positiv: forwards, Negativ: backwards
float32 adjusted_forward_speed_setpoint # [m/s] Speed setpoint after applying slew rate
float32 measured_lateral_speed # [m/s] Measured speed in body y direction. Positiv: right, Negativ: left
float32 adjusted_lateral_speed_setpoint # [m/s] Speed setpoint after applying slew rate
float32 measured_yaw_rate # [rad/s] Measured yaw rate
float32 clyaw_yaw_rate_setpoint # [rad/s] Yaw rate setpoint output by the closed loop yaw controller
float32 adjusted_yaw_rate_setpoint # [rad/s] Yaw rate setpoint from the closed loop yaw controller
float32 measured_yaw # [rad] Measured yaw
float32 adjusted_yaw_setpoint # [rad] Yaw setpoint after applying slew rate
float32 pid_yaw_rate_integral # Integral of the PID for the closed loop yaw rate controller
float32 pid_yaw_integral # Integral of the PID for the closed loop yaw controller
float32 pid_forward_throttle_integral # Integral of the PID for the closed loop forward speed controller
float32 pid_lateral_throttle_integral # Integral of the PID for the closed loop lateral speed controller
# TOPICS rover_mecanum_status
+1 -1
View File
@@ -3,7 +3,7 @@ uint64 timestamp_sample
uint32 device_id # unique device ID for the sensor that does not change between power cycles
float32[2] pixel_flow # (radians) optical flow in radians where a positive value is produced by a RH rotation about the body axis
float32[2] pixel_flow # (radians) optical flow in radians where a positive value is produced by a RH rotation of the sensor about the body axis
float32[3] delta_angle # (radians) accumulated gyro radians where a positive value is produced by a RH rotation about the body axis. Set to NaN if flow sensor does not have 3-axis gyro data.
bool delta_angle_available
-2
View File
@@ -51,13 +51,11 @@ bool heartbeat_type_open_drone_id # MAV_TYPE_ODID
bool heartbeat_component_telemetry_radio # MAV_COMP_ID_TELEMETRY_RADIO
bool heartbeat_component_log # MAV_COMP_ID_LOG
bool heartbeat_component_osd # MAV_COMP_ID_OSD
bool heartbeat_component_obstacle_avoidance # MAV_COMP_ID_OBSTACLE_AVOIDANCE
bool heartbeat_component_vio # MAV_COMP_ID_VISUAL_INERTIAL_ODOMETRY
bool heartbeat_component_pairing_manager # MAV_COMP_ID_PAIRING_MANAGER
bool heartbeat_component_udp_bridge # MAV_COMP_ID_UDP_BRIDGE
bool heartbeat_component_uart_bridge # MAV_COMP_ID_UART_BRIDGE
# Misc component health
bool avoidance_system_healthy
bool open_drone_id_system_healthy
bool parachute_system_healthy
-8
View File
@@ -1,8 +0,0 @@
# Bezier Trajectory description. See also Mavlink TRAJECTORY msg
# The topic trajectory_bezier describe each waypoint defined in vehicle_trajectory_bezier
uint64 timestamp # time since system start (microseconds)
float32[3] position # local position x,y,z (metres)
float32 yaw # yaw angle (rad)
float32 delta # time it should take to get to this waypoint, if this is the final waypoint (seconds)
-13
View File
@@ -1,13 +0,0 @@
# Waypoint Trajectory description. See also Mavlink TRAJECTORY msg
# The topic trajectory_waypoint describe each waypoint defined in vehicle_trajectory_waypoint
uint64 timestamp # time since system start (microseconds)
float32[3] position
float32[3] velocity
float32[3] acceleration
float32 yaw
float32 yaw_speed
bool point_valid
uint8 type
+2 -2
View File
@@ -6,10 +6,10 @@ uint64 timestamp_sample # the timestamp of the raw data (microseconds)
uint32 baro_device_id # unique device ID for the selected barometer
float32 baro_alt_meter # Altitude above MSL calculated from temperature compensated baro sensor data using an ISA corrected for sea level pressure SENS_BARO_QNH.
float32 baro_temp_celcius # Temperature in degrees Celsius
float32 baro_pressure_pa # Absolute pressure in Pascals
float32 ambient_temperature # Abient temperature in degrees Celsius
uint8 temperature_source # Source of temperature data: 0: Default Temperature (15°C), 1: External Baro, 2: Airspeed
float32 rho # air density
float32 eas2tas # equivalent airspeed to true airspeed conversion factor
uint8 calibration_count # Calibration changed counter. Monotonically increases whenever calibration changes.
+1 -1
View File
@@ -7,7 +7,7 @@ uint32 device_id # unique device ID for the sensor that does not c
float32[2] pixel_flow # (radians) accumulated optical flow in radians where a positive value is produced by a RH rotation about the body axis
float32[3] delta_angle # (radians) accumulated gyro radians where a positive value is produced by a RH rotation about the body axis. (NAN if unavailable)
float32[3] delta_angle # (radians) accumulated gyro radians where a positive value is produced by a RH rotation of the sensor about the body axis. (NAN if unavailable)
float32 distance_m # (meters) Distance to the center of the flow field (NAN if unavailable)
-18
View File
@@ -1,18 +0,0 @@
# Vehicle Waypoints Trajectory description. See also MAVLink MAV_TRAJECTORY_REPRESENTATION msg
# The topic vehicle_trajectory_bezier is used to send a smooth flight path from the
# companion computer / avoidance module to the position controller.
uint64 timestamp # time since system start (microseconds)
uint8 POINT_0 = 0
uint8 POINT_1 = 1
uint8 POINT_2 = 2
uint8 POINT_3 = 3
uint8 POINT_4 = 4
uint8 NUMBER_POINTS = 5
TrajectoryBezier[5] control_points
uint8 bezier_order
# TOPICS vehicle_trajectory_bezier
-21
View File
@@ -1,21 +0,0 @@
# Vehicle Waypoints Trajectory description. See also MAVLink MAV_TRAJECTORY_REPRESENTATION msg
# The topic vehicle_trajectory_waypoint_desired is used to send the user desired waypoints from the position controller to the companion computer / avoidance module.
# The topic vehicle_trajectory_waypoint is used to send the adjusted waypoints from the companion computer / avoidance module to the position controller.
uint64 timestamp # time since system start (microseconds)
uint8 MAV_TRAJECTORY_REPRESENTATION_WAYPOINTS = 0
uint8 type # Type from MAV_TRAJECTORY_REPRESENTATION enum.
uint8 POINT_0 = 0
uint8 POINT_1 = 1
uint8 POINT_2 = 2
uint8 POINT_3 = 3
uint8 POINT_4 = 4
uint8 NUMBER_POINTS = 5
TrajectoryWaypoint[5] waypoints
# TOPICS vehicle_trajectory_waypoint vehicle_trajectory_waypoint_desired
+140
View File
@@ -0,0 +1,140 @@
# Encodes the system state of the vehicle published by commander
uint32 MESSAGE_VERSION = 0
uint64 timestamp # time since system start (microseconds)
uint64 armed_time # Arming timestamp (microseconds)
uint64 takeoff_time # Takeoff timestamp (microseconds)
uint8 arming_state
uint8 ARMING_STATE_DISARMED = 1
uint8 ARMING_STATE_ARMED = 2
uint8 latest_arming_reason
uint8 latest_disarming_reason
uint8 ARM_DISARM_REASON_TRANSITION_TO_STANDBY = 0
uint8 ARM_DISARM_REASON_STICK_GESTURE = 1
uint8 ARM_DISARM_REASON_RC_SWITCH = 2
uint8 ARM_DISARM_REASON_COMMAND_INTERNAL = 3
uint8 ARM_DISARM_REASON_COMMAND_EXTERNAL = 4
uint8 ARM_DISARM_REASON_MISSION_START = 5
uint8 ARM_DISARM_REASON_SAFETY_BUTTON = 6
uint8 ARM_DISARM_REASON_AUTO_DISARM_LAND = 7
uint8 ARM_DISARM_REASON_AUTO_DISARM_PREFLIGHT = 8
uint8 ARM_DISARM_REASON_KILL_SWITCH = 9
uint8 ARM_DISARM_REASON_LOCKDOWN = 10
uint8 ARM_DISARM_REASON_FAILURE_DETECTOR = 11
uint8 ARM_DISARM_REASON_SHUTDOWN = 12
uint8 ARM_DISARM_REASON_UNIT_TEST = 13
uint64 nav_state_timestamp # time when current nav_state activated
uint8 nav_state_user_intention # Mode that the user selected (might be different from nav_state in a failsafe situation)
uint8 nav_state # Currently active mode
uint8 NAVIGATION_STATE_MANUAL = 0 # Manual mode
uint8 NAVIGATION_STATE_ALTCTL = 1 # Altitude control mode
uint8 NAVIGATION_STATE_POSCTL = 2 # Position control mode
uint8 NAVIGATION_STATE_AUTO_MISSION = 3 # Auto mission mode
uint8 NAVIGATION_STATE_AUTO_LOITER = 4 # Auto loiter mode
uint8 NAVIGATION_STATE_AUTO_RTL = 5 # Auto return to launch mode
uint8 NAVIGATION_STATE_POSITION_SLOW = 6
uint8 NAVIGATION_STATE_FREE5 = 7
uint8 NAVIGATION_STATE_FREE4 = 8
uint8 NAVIGATION_STATE_FREE3 = 9
uint8 NAVIGATION_STATE_ACRO = 10 # Acro mode
uint8 NAVIGATION_STATE_FREE2 = 11
uint8 NAVIGATION_STATE_DESCEND = 12 # Descend mode (no position control)
uint8 NAVIGATION_STATE_TERMINATION = 13 # Termination mode
uint8 NAVIGATION_STATE_OFFBOARD = 14
uint8 NAVIGATION_STATE_STAB = 15 # Stabilized mode
uint8 NAVIGATION_STATE_FREE1 = 16
uint8 NAVIGATION_STATE_AUTO_TAKEOFF = 17 # Takeoff
uint8 NAVIGATION_STATE_AUTO_LAND = 18 # Land
uint8 NAVIGATION_STATE_AUTO_FOLLOW_TARGET = 19 # Auto Follow
uint8 NAVIGATION_STATE_AUTO_PRECLAND = 20 # Precision land with landing target
uint8 NAVIGATION_STATE_ORBIT = 21 # Orbit in a circle
uint8 NAVIGATION_STATE_AUTO_VTOL_TAKEOFF = 22 # Takeoff, transition, establish loiter
uint8 NAVIGATION_STATE_EXTERNAL1 = 23
uint8 NAVIGATION_STATE_EXTERNAL2 = 24
uint8 NAVIGATION_STATE_EXTERNAL3 = 25
uint8 NAVIGATION_STATE_EXTERNAL4 = 26
uint8 NAVIGATION_STATE_EXTERNAL5 = 27
uint8 NAVIGATION_STATE_EXTERNAL6 = 28
uint8 NAVIGATION_STATE_EXTERNAL7 = 29
uint8 NAVIGATION_STATE_EXTERNAL8 = 30
uint8 NAVIGATION_STATE_MAX = 31
uint8 executor_in_charge # Current mode executor in charge (0=Autopilot)
uint32 valid_nav_states_mask # Bitmask for all valid nav_state values
uint32 can_set_nav_states_mask # Bitmask for all modes that a user can select
# Bitmask of detected failures
uint16 failure_detector_status
uint16 FAILURE_NONE = 0
uint16 FAILURE_ROLL = 1 # (1 << 0)
uint16 FAILURE_PITCH = 2 # (1 << 1)
uint16 FAILURE_ALT = 4 # (1 << 2)
uint16 FAILURE_EXT = 8 # (1 << 3)
uint16 FAILURE_ARM_ESC = 16 # (1 << 4)
uint16 FAILURE_BATTERY = 32 # (1 << 5)
uint16 FAILURE_IMBALANCED_PROP = 64 # (1 << 6)
uint16 FAILURE_MOTOR = 128 # (1 << 7)
uint8 hil_state
uint8 HIL_STATE_OFF = 0
uint8 HIL_STATE_ON = 1
# If it's a VTOL, then the value will be VEHICLE_TYPE_ROTARY_WING while flying as a multicopter, and VEHICLE_TYPE_FIXED_WING when flying as a fixed-wing
uint8 vehicle_type
uint8 VEHICLE_TYPE_UNKNOWN = 0
uint8 VEHICLE_TYPE_ROTARY_WING = 1
uint8 VEHICLE_TYPE_FIXED_WING = 2
uint8 VEHICLE_TYPE_ROVER = 3
uint8 VEHICLE_TYPE_AIRSHIP = 4
uint8 FAILSAFE_DEFER_STATE_DISABLED = 0
uint8 FAILSAFE_DEFER_STATE_ENABLED = 1
uint8 FAILSAFE_DEFER_STATE_WOULD_FAILSAFE = 2 # Failsafes deferred, but would trigger a failsafe
bool failsafe # true if system is in failsafe state (e.g.:RTL, Hover, Terminate, ...)
bool failsafe_and_user_took_over # true if system is in failsafe state but the user took over control
uint8 failsafe_defer_state # one of FAILSAFE_DEFER_STATE_*
# Link loss
bool gcs_connection_lost # datalink to GCS lost
uint8 gcs_connection_lost_counter # counts unique GCS connection lost events
bool high_latency_data_link_lost # Set to true if the high latency data link (eg. RockBlock Iridium 9603 telemetry module) is lost
# VTOL flags
bool is_vtol # True if the system is VTOL capable
bool is_vtol_tailsitter # True if the system performs a 90° pitch down rotation during transition from MC to FW
bool in_transition_mode # True if VTOL is doing a transition
bool in_transition_to_fw # True if VTOL is doing a transition from MC to FW
# MAVLink identification
uint8 system_type # system type, contains mavlink MAV_TYPE
uint8 system_id # system id, contains MAVLink's system ID field
uint8 component_id # subsystem / component id, contains MAVLink's component ID field
bool safety_button_available # Set to true if a safety button is connected
bool safety_off # Set to true if safety is off
bool power_input_valid # set if input power is valid
bool usb_connected # set to true (never cleared) once telemetry received from usb link
bool open_drone_id_system_present
bool open_drone_id_system_healthy
bool parachute_system_present
bool parachute_system_healthy
bool avoidance_system_required # Set to true if avoidance system is enabled via COM_OBS_AVOID parameter
bool avoidance_system_valid # Status of the obstacle avoidance system
bool rc_calibration_in_progress
bool calibration_enabled
bool pre_flight_checks_pass # true if all checks necessary to arm pass
@@ -9,3 +9,5 @@
//#include "example_translation_direct_v1.h"
//#include "example_translation_multi_v2.h"
//#include "example_translation_service_v1.h"
#include "translation_vehicle_status_v1.h"
@@ -0,0 +1,110 @@
/****************************************************************************
* Copyright (c) 2025 PX4 Development Team.
* SPDX-License-Identifier: BSD-3-Clause
****************************************************************************/
#pragma once
// Translate VehicleStatus v0 <--> v1
#include <px4_msgs_old/msg/vehicle_status_v0.hpp>
#include <px4_msgs/msg/vehicle_status.hpp>
class VehicleStatusV1Translation {
public:
using MessageOlder = px4_msgs_old::msg::VehicleStatusV0;
static_assert(MessageOlder::MESSAGE_VERSION == 0);
using MessageNewer = px4_msgs::msg::VehicleStatus;
static_assert(MessageNewer::MESSAGE_VERSION == 1);
static constexpr const char* kTopic = "fmu/out/vehicle_status";
static void fromOlder(const MessageOlder &msg_older, MessageNewer &msg_newer) {
// Set msg_newer from msg_older
msg_newer.timestamp = msg_older.timestamp;
msg_newer.armed_time = msg_older.armed_time;
msg_newer.takeoff_time = msg_older.takeoff_time;
msg_newer.arming_state = msg_older.arming_state;
msg_newer.latest_arming_reason = msg_older.latest_arming_reason;
msg_newer.latest_disarming_reason = msg_older.latest_disarming_reason;
msg_newer.nav_state_timestamp = msg_older.nav_state_timestamp;
msg_newer.nav_state_user_intention = msg_older.nav_state_user_intention;
msg_newer.nav_state = msg_older.nav_state;
msg_newer.executor_in_charge = msg_older.executor_in_charge;
msg_newer.valid_nav_states_mask = msg_older.valid_nav_states_mask;
msg_newer.can_set_nav_states_mask = msg_older.can_set_nav_states_mask;
msg_newer.failure_detector_status = msg_older.failure_detector_status;
msg_newer.hil_state = msg_older.hil_state;
msg_newer.vehicle_type = msg_older.vehicle_type;
msg_newer.failsafe = msg_older.failsafe;
msg_newer.failsafe_and_user_took_over = msg_older.failsafe_and_user_took_over;
msg_newer.failsafe_defer_state = msg_older.failsafe_defer_state;
msg_newer.gcs_connection_lost = msg_older.gcs_connection_lost;
msg_newer.gcs_connection_lost_counter = msg_older.gcs_connection_lost_counter;
msg_newer.high_latency_data_link_lost = msg_older.high_latency_data_link_lost;
msg_newer.is_vtol = msg_older.is_vtol;
msg_newer.is_vtol_tailsitter = msg_older.is_vtol_tailsitter;
msg_newer.in_transition_mode = msg_older.in_transition_mode;
msg_newer.in_transition_to_fw = msg_older.in_transition_to_fw;
msg_newer.system_type = msg_older.system_type;
msg_newer.system_id = msg_older.system_id;
msg_newer.component_id = msg_older.component_id;
msg_newer.safety_button_available = msg_older.safety_button_available;
msg_newer.safety_off = msg_older.safety_off;
msg_newer.power_input_valid = msg_older.power_input_valid;
msg_newer.usb_connected = msg_older.usb_connected;
msg_newer.open_drone_id_system_present = msg_older.open_drone_id_system_present;
msg_newer.open_drone_id_system_healthy = msg_older.open_drone_id_system_healthy;
msg_newer.parachute_system_present = msg_older.parachute_system_present;
msg_newer.parachute_system_healthy = msg_older.parachute_system_healthy;
msg_newer.rc_calibration_in_progress = msg_older.rc_calibration_in_progress;
msg_newer.calibration_enabled = msg_older.calibration_enabled;
msg_newer.pre_flight_checks_pass = msg_older.pre_flight_checks_pass;
}
static void toOlder(const MessageNewer &msg_newer, MessageOlder &msg_older) {
// Set msg_older from msg_newer
msg_older.timestamp = msg_newer.timestamp;
msg_older.armed_time = msg_newer.armed_time;
msg_older.takeoff_time = msg_newer.takeoff_time;
msg_older.arming_state = msg_newer.arming_state;
msg_older.latest_arming_reason = msg_newer.latest_arming_reason;
msg_older.latest_disarming_reason = msg_newer.latest_disarming_reason;
msg_older.nav_state_timestamp = msg_newer.nav_state_timestamp;
msg_older.nav_state_user_intention = msg_newer.nav_state_user_intention;
msg_older.nav_state = msg_newer.nav_state;
msg_older.executor_in_charge = msg_newer.executor_in_charge;
msg_older.valid_nav_states_mask = msg_newer.valid_nav_states_mask;
msg_older.can_set_nav_states_mask = msg_newer.can_set_nav_states_mask;
msg_older.failure_detector_status = msg_newer.failure_detector_status;
msg_older.hil_state = msg_newer.hil_state;
msg_older.vehicle_type = msg_newer.vehicle_type;
msg_older.failsafe = msg_newer.failsafe;
msg_older.failsafe_and_user_took_over = msg_newer.failsafe_and_user_took_over;
msg_older.failsafe_defer_state = msg_newer.failsafe_defer_state;
msg_older.gcs_connection_lost = msg_newer.gcs_connection_lost;
msg_older.gcs_connection_lost_counter = msg_newer.gcs_connection_lost_counter;
msg_older.high_latency_data_link_lost = msg_newer.high_latency_data_link_lost;
msg_older.is_vtol = msg_newer.is_vtol;
msg_older.is_vtol_tailsitter = msg_newer.is_vtol_tailsitter;
msg_older.in_transition_mode = msg_newer.in_transition_mode;
msg_older.in_transition_to_fw = msg_newer.in_transition_to_fw;
msg_older.system_type = msg_newer.system_type;
msg_older.system_id = msg_newer.system_id;
msg_older.component_id = msg_newer.component_id;
msg_older.safety_button_available = msg_newer.safety_button_available;
msg_older.safety_off = msg_newer.safety_off;
msg_older.power_input_valid = msg_newer.power_input_valid;
msg_older.usb_connected = msg_newer.usb_connected;
msg_older.open_drone_id_system_present = msg_newer.open_drone_id_system_present;
msg_older.open_drone_id_system_healthy = msg_newer.open_drone_id_system_healthy;
msg_older.parachute_system_present = msg_newer.parachute_system_present;
msg_older.parachute_system_healthy = msg_newer.parachute_system_healthy;
msg_older.avoidance_system_required = false;
msg_older.avoidance_system_valid = false;
msg_older.rc_calibration_in_progress = msg_newer.rc_calibration_in_progress;
msg_older.calibration_enabled = msg_newer.calibration_enabled;
msg_older.pre_flight_checks_pass = msg_newer.pre_flight_checks_pass;
}
};
REGISTER_TOPIC_TRANSLATION_DIRECT(VehicleStatusV1Translation);
-1
View File
@@ -6,7 +6,6 @@ uint8 request_id
uint8 registration_id
uint8 HEALTH_COMPONENT_INDEX_NONE = 0
uint8 HEALTH_COMPONENT_INDEX_AVOIDANCE = 19
uint8 health_component_index # HEALTH_COMPONENT_INDEX_*
bool health_component_is_present
+22 -22
View File
@@ -12,9 +12,9 @@ float32 time_remaining_s # predicted time in seconds remaining until battery i
float32 temperature # Temperature of the battery in degrees Celcius, NaN if unknown
uint8 cell_count # Number of cells, 0 if unknown
uint8 BATTERY_SOURCE_POWER_MODULE = 0
uint8 BATTERY_SOURCE_EXTERNAL = 1
uint8 BATTERY_SOURCE_ESCS = 2
uint8 SOURCE_POWER_MODULE = 0
uint8 SOURCE_EXTERNAL = 1
uint8 SOURCE_ESCS = 2
uint8 source # Battery source
uint8 priority # Zero based priority is the connection on the Power Controller V1..Vn AKA BrickN-1
uint16 capacity # actual capacity of the battery
@@ -34,26 +34,26 @@ bool is_powering_off # Power off event imminent indication, false if unknown
bool is_required # Set if the battery is explicitly required before arming
uint8 BATTERY_WARNING_NONE = 0 # no battery low voltage warning active
uint8 BATTERY_WARNING_LOW = 1 # warning of low voltage
uint8 BATTERY_WARNING_CRITICAL = 2 # critical voltage, return / abort immediately
uint8 BATTERY_WARNING_EMERGENCY = 3 # immediate landing required
uint8 BATTERY_WARNING_FAILED = 4 # the battery has failed completely
uint8 BATTERY_STATE_UNHEALTHY = 6 # Battery is diagnosed to be defective or an error occurred, usage is discouraged / prohibited. Possible causes (faults) are listed in faults field.
uint8 BATTERY_STATE_CHARGING = 7 # Battery is charging
uint8 WARNING_NONE = 0 # no battery low voltage warning active
uint8 WARNING_LOW = 1 # warning of low voltage
uint8 WARNING_CRITICAL = 2 # critical voltage, return / abort immediately
uint8 WARNING_EMERGENCY = 3 # immediate landing required
uint8 WARNING_FAILED = 4 # the battery has failed completely
uint8 STATE_UNHEALTHY = 6 # Battery is diagnosed to be defective or an error occurred, usage is discouraged / prohibited. Possible causes (faults) are listed in faults field.
uint8 STATE_CHARGING = 7 # Battery is charging
uint8 BATTERY_FAULT_DEEP_DISCHARGE = 0 # Battery has deep discharged
uint8 BATTERY_FAULT_SPIKES = 1 # Voltage spikes
uint8 BATTERY_FAULT_CELL_FAIL= 2 # One or more cells have failed
uint8 BATTERY_FAULT_OVER_CURRENT = 3 # Over-current
uint8 BATTERY_FAULT_OVER_TEMPERATURE = 4 # Over-temperature
uint8 BATTERY_FAULT_UNDER_TEMPERATURE = 5 # Under-temperature fault
uint8 BATTERY_FAULT_INCOMPATIBLE_VOLTAGE = 6 # Vehicle voltage is not compatible with this battery (batteries on same power rail should have similar voltage).
uint8 BATTERY_FAULT_INCOMPATIBLE_FIRMWARE = 7 # Battery firmware is not compatible with current autopilot firmware
uint8 BATTERY_FAULT_INCOMPATIBLE_MODEL = 8 # Battery model is not supported by the system
uint8 BATTERY_FAULT_HARDWARE_FAILURE = 9 # hardware problem
uint8 BATTERY_FAULT_FAILED_TO_ARM = 10 # Battery had a problem while arming
uint8 BATTERY_FAULT_COUNT = 11 # Counter - keep it as last element!
uint8 FAULT_DEEP_DISCHARGE = 0 # Battery has deep discharged
uint8 FAULT_SPIKES = 1 # Voltage spikes
uint8 FAULT_CELL_FAIL= 2 # One or more cells have failed
uint8 FAULT_OVER_CURRENT = 3 # Over-current
uint8 FAULT_OVER_TEMPERATURE = 4 # Over-temperature
uint8 FAULT_UNDER_TEMPERATURE = 5 # Under-temperature fault
uint8 FAULT_INCOMPATIBLE_VOLTAGE = 6 # Vehicle voltage is not compatible with this battery (batteries on same power rail should have similar voltage).
uint8 FAULT_INCOMPATIBLE_FIRMWARE = 7 # Battery firmware is not compatible with current autopilot firmware
uint8 FAULT_INCOMPATIBLE_MODEL = 8 # Battery model is not supported by the system
uint8 FAULT_HARDWARE_FAILURE = 9 # hardware problem
uint8 FAULT_FAILED_TO_ARM = 10 # Battery had a problem while arming
uint8 FAULT_COUNT = 11 # Counter - keep it as last element!
uint16 faults # Smart battery supply status/fault flags (bitmask) for health indication.
uint8 warning # Current battery warning
+6 -10
View File
@@ -1,6 +1,6 @@
# Encodes the system state of the vehicle published by commander
uint32 MESSAGE_VERSION = 0
uint32 MESSAGE_VERSION = 1
uint64 timestamp # time since system start (microseconds)
@@ -87,15 +87,14 @@ uint8 hil_state
uint8 HIL_STATE_OFF = 0
uint8 HIL_STATE_ON = 1
# If it's a VTOL, then the value will be VEHICLE_TYPE_ROTARY_WING while flying as a multicopter, and VEHICLE_TYPE_FIXED_WING when flying as a fixed-wing
# Current vehicle locomotion method. A vehicle can have different methods (e.g. VTOL transitions from RW to FW method)
uint8 vehicle_type
uint8 VEHICLE_TYPE_UNKNOWN = 0
uint8 VEHICLE_TYPE_ROTARY_WING = 1
uint8 VEHICLE_TYPE_FIXED_WING = 2
uint8 VEHICLE_TYPE_ROVER = 3
uint8 VEHICLE_TYPE_AIRSHIP = 4
uint8 VEHICLE_TYPE_ROTARY_WING = 0
uint8 VEHICLE_TYPE_FIXED_WING = 1
uint8 VEHICLE_TYPE_ROVER = 2
uint8 VEHICLE_TYPE_BOAT = 5
uint8 FAILSAFE_DEFER_STATE_DISABLED = 0
uint8 FAILSAFE_DEFER_STATE_ENABLED = 1
uint8 FAILSAFE_DEFER_STATE_WOULD_FAILSAFE = 2 # Failsafes deferred, but would trigger a failsafe
@@ -132,9 +131,6 @@ bool open_drone_id_system_healthy
bool parachute_system_present
bool parachute_system_healthy
bool avoidance_system_required # Set to true if avoidance system is enabled via COM_OBS_AVOID parameter
bool avoidance_system_valid # Status of the obstacle avoidance system
bool rc_calibration_in_progress
bool calibration_enabled
@@ -97,7 +97,7 @@ __BEGIN_DECLS
extern long PX4_TICKS_PER_SEC;
__END_DECLS
#define PX4_ROOTFSDIR CONFIG_BOARD_ROOTFSDIR
#define PX4_ROOTFSDIR CONFIG_BOARD_ROOT_PATH
// Qurt doesn't have an SD card for storage
#ifndef __PX4_QURT
-1
View File
@@ -5,7 +5,6 @@
# tests command arguments
set(tests
atomic_bitset
bezier
bitset
bson
dataman
+171 -80
View File
@@ -47,7 +47,7 @@ VoxlEsc::VoxlEsc() :
_mixing_output{"VOXL_ESC", VOXL_ESC_OUTPUT_CHANNELS, *this, MixingOutput::SchedulingPolicy::Auto, false, false},
_cycle_perf(perf_alloc(PC_ELAPSED, MODULE_NAME": cycle")),
_output_update_perf(perf_alloc(PC_INTERVAL, MODULE_NAME": output update interval")),
_battery(1, nullptr, _battery_report_interval, battery_status_s::BATTERY_SOURCE_POWER_MODULE)
_battery(1, nullptr, _battery_report_interval, battery_status_s::SOURCE_POWER_MODULE)
{
_device = VOXL_ESC_DEFAULT_PORT;
@@ -90,13 +90,13 @@ VoxlEsc::~VoxlEsc()
int VoxlEsc::init()
{
PX4_INFO("VOXL_ESC: Starting VOXL ESC driver");
PX4_ERR("Starting VOXL ESC driver");
/* Getting initial parameter values */
int ret = update_params();
if (ret != OK) {
PX4_ERR("VOXL_ESC: Failed to update params during init");
PX4_ERR("Failed to update params during init");
return ret;
}
@@ -124,13 +124,13 @@ int VoxlEsc::device_init()
// Open serial port
if (!_uart_port.isOpen()) {
PX4_INFO("VOXL_ESC: Opening UART ESC device %s, baud rate %" PRIi32, _device, _parameters.baud_rate);
PX4_ERR("Opening UART ESC device %s, baud rate %" PRIi32, _device, _parameters.baud_rate);
#ifndef __PX4_QURT
//warn user that unless DMA is enabled for UART RX, data can be lost due to high frequency of per char cpu interrupts
//at least at 2mbit, there are definitely losses, did not test other baud rates to find the cut off
if (_parameters.baud_rate > 250000) {
PX4_WARN("VOXL_ESC: Baud rate is too high for non-DMA based UART, this can lead to loss of RX data");
PX4_WARN("Baud rate is too high for non-DMA based UART, this can lead to loss of RX data");
}
#endif
@@ -165,7 +165,7 @@ int VoxlEsc::device_init()
}
// Detect ESCs
PX4_INFO("VOXL_ESC: Detecting ESCs...");
PX4_ERR("Detecting ESCs...");
qc_esc_packet_init(&_fb_packet);
//request extended version info from each ESC and wait for reply
@@ -174,7 +174,7 @@ int VoxlEsc::device_init()
cmd.len = qc_esc_create_extended_version_request_packet(esc_id, cmd.buf, sizeof(cmd.buf));
if (_uart_port.write(cmd.buf, cmd.len) != cmd.len) {
PX4_ERR("VOXL_ESC: Could not write version request packet to UART port");
PX4_ERR("Could not write version request packet to UART port");
return -1;
}
@@ -201,17 +201,17 @@ int VoxlEsc::device_init()
QC_ESC_EXTENDED_VERSION_INFO ver;
memcpy(&ver, _fb_packet.buffer, packet_size);
PX4_INFO("VOXL_ESC: \tESC ID : %i", ver.id);
PX4_INFO("VOXL_ESC: \tBoard Type : %i: %s", ver.hw_version, board_id_to_name(ver.hw_version));
PX4_ERR("\tESC ID : %i", ver.id);
PX4_ERR("\tBoard Type : %i: %s", ver.hw_version, board_id_to_name(ver.hw_version));
uint8_t *u = &ver.unique_id[0];
PX4_INFO("VOXL_ESC: \tUnique ID : 0x%02X%02X%02X%02X%02X%02X%02X%02X%02X%02X%02X%02X",
u[11], u[10], u[9], u[8], u[7], u[6], u[5], u[4], u[3], u[2], u[1], u[0]);
PX4_ERR("\tUnique ID : 0x%02X%02X%02X%02X%02X%02X%02X%02X%02X%02X%02X%02X",
u[11], u[10], u[9], u[8], u[7], u[6], u[5], u[4], u[3], u[2], u[1], u[0]);
PX4_INFO("VOXL_ESC: \tFirmware : version %4d, hash %.12s", ver.sw_version, ver.firmware_git_version);
PX4_INFO("VOXL_ESC: \tBootloader : version %4d, hash %.12s", ver.bootloader_version, ver.bootloader_git_version);
PX4_INFO("VOXL_ESC: \tReply time : %" PRIu32 "us", (uint32_t)response_time);
PX4_INFO("VOXL_ESC:");
PX4_ERR("\tFirmware : version %4d, hash %.12s", ver.sw_version, ver.firmware_git_version);
PX4_ERR("\tBootloader : version %4d, hash %.12s", ver.bootloader_version, ver.bootloader_git_version);
PX4_ERR("\tReply time : %" PRIu32 "us", (uint32_t)response_time);
PX4_INFO("");
if (ver.id == esc_id) {
memcpy(&_version_info[esc_id], &ver, sizeof(ver));
@@ -223,7 +223,7 @@ int VoxlEsc::device_init()
}
if (!got_response) {
PX4_ERR("VOXL_ESC: ESC %d version info response timeout", esc_id);
PX4_ERR("ESC %d version info response timeout", esc_id);
}
}
@@ -232,7 +232,7 @@ int VoxlEsc::device_init()
for (int esc_id = 0; esc_id < VOXL_ESC_OUTPUT_CHANNELS; esc_id++) {
if (_version_info[esc_id].sw_version == 0) {
PX4_ERR("VOXL_ESC: ESC ID %d was not detected", esc_id);
PX4_ERR("ESC ID %d was not detected", esc_id);
esc_detection_fault = true;
}
}
@@ -240,7 +240,7 @@ int VoxlEsc::device_init()
//check the firmware hashes to make sure they are the same. Firmware hash has 8 chars plus optional "*"
for (int esc_id = 1; esc_id < VOXL_ESC_OUTPUT_CHANNELS; esc_id++) {
if (strncmp(_version_info[0].firmware_git_version, _version_info[esc_id].firmware_git_version, 9) != 0) {
PX4_ERR("VOXL_ESC: ESC %d Firmware hash does not match ESC 0 firmware hash: (%.12s) != (%.12s)",
PX4_ERR("ESC %d Firmware hash does not match ESC 0 firmware hash: (%.12s) != (%.12s)",
esc_id, _version_info[esc_id].firmware_git_version, _version_info[0].firmware_git_version);
esc_detection_fault = true;
}
@@ -256,13 +256,13 @@ int VoxlEsc::device_init()
}
if (esc_detection_fault) {
PX4_ERR("VOXL_ESC: Critical error during ESC initialization");
PX4_ERR("Critical error during ESC initialization");
return -1;
}
PX4_INFO("VOXL_ESC: Use extened rpm packet : %d", _extended_rpm);
PX4_ERR("Use extened rpm packet : %d", _extended_rpm);
PX4_INFO("VOXL_ESC: All ESCs successfully detected");
PX4_ERR("All ESCs successfully detected");
_device_initialized = true;
@@ -309,45 +309,53 @@ int VoxlEsc::load_params(voxl_esc_params_t *params, ch_assign_t *map)
param_get(param_find("VOXL_ESC_T_WARN"), &params->esc_warn_temp_threshold);
param_get(param_find("VOXL_ESC_T_OVER"), &params->esc_over_temp_threshold);
param_get(param_find("VOXL_ESC_GPIO_CH"), &params->gpio_ctl_channel);
if (params->rpm_min >= params->rpm_max) {
PX4_ERR("VOXL_ESC: Invalid parameter VOXL_ESC_RPM_MIN. Please verify parameters.");
PX4_ERR("Invalid parameter VOXL_ESC_RPM_MIN. Please verify parameters.");
params->rpm_min = 0;
ret = PX4_ERROR;
}
if (params->turtle_motor_percent < 0 || params->turtle_motor_percent > 100) {
PX4_ERR("VOXL_ESC: Invalid parameter VOXL_ESC_T_PERC. Please verify parameters.");
PX4_ERR("Invalid parameter VOXL_ESC_T_PERC. Please verify parameters.");
params->turtle_motor_percent = 0;
ret = PX4_ERROR;
}
if (params->turtle_motor_deadband < 0 || params->turtle_motor_deadband > 100) {
PX4_ERR("VOXL_ESC: Invalid parameter VOXL_ESC_T_DEAD. Please verify parameters.");
PX4_ERR("Invalid parameter VOXL_ESC_T_DEAD. Please verify parameters.");
params->turtle_motor_deadband = 0;
ret = PX4_ERROR;
}
if (params->turtle_motor_expo < 0 || params->turtle_motor_expo > 100) {
PX4_ERR("VOXL_ESC: Invalid parameter VOXL_ESC_T_EXPO. Please verify parameters.");
PX4_ERR("Invalid parameter VOXL_ESC_T_EXPO. Please verify parameters.");
params->turtle_motor_expo = 0;
ret = PX4_ERROR;
}
if (params->turtle_stick_minf < 0.0f || params->turtle_stick_minf > 100.0f) {
PX4_ERR("VOXL_ESC: Invalid parameter VOXL_ESC_T_MINF. Please verify parameters.");
PX4_ERR("Invalid parameter VOXL_ESC_T_MINF. Please verify parameters.");
params->turtle_stick_minf = 0.0f;
ret = PX4_ERROR;
}
if (params->turtle_cosphi < 0.0f || params->turtle_cosphi > 100.0f) {
PX4_ERR("VOXL_ESC: Invalid parameter VOXL_ESC_T_COSP. Please verify parameters.");
PX4_ERR("Invalid parameter VOXL_ESC_T_COSP. Please verify parameters.");
params->turtle_cosphi = 0.0f;
ret = PX4_ERROR;
}
if (params->gpio_ctl_channel < 0 || params->gpio_ctl_channel > 6) {
PX4_ERR("Invalid parameter VOXL_ESC_GPIO_CH. Please verify parameters.");
params->gpio_ctl_channel = 0;
ret = PX4_ERROR;
}
for (int i = 0; i < VOXL_ESC_OUTPUT_CHANNELS; i++) {
if (params->function_map[i] < (int)OutputFunction::Motor1 || params->function_map[i] > (int)OutputFunction::Motor4) {
PX4_ERR("VOXL_ESC: Invalid parameter VOXL_ESC_FUNCX. Only supports motors 1-4. Please verify parameters.");
PX4_ERR("Invalid parameter VOXL_ESC_FUNCX. Only supports motors 1-4. Please verify parameters.");
params->function_map[i] = 0;
ret = PX4_ERROR;
@@ -365,7 +373,7 @@ int VoxlEsc::load_params(voxl_esc_params_t *params, ch_assign_t *map)
if (params->motor_map[i] == VOXL_ESC_OUTPUT_DISABLED ||
params->motor_map[i] < -(VOXL_ESC_OUTPUT_CHANNELS) ||
params->motor_map[i] > VOXL_ESC_OUTPUT_CHANNELS) {
PX4_ERR("VOXL_ESC: Invalid parameter VOXL_ESC_MOTORX. Please verify parameters.");
PX4_ERR("Invalid parameter VOXL_ESC_MOTORX. Please verify parameters.");
params->motor_map[i] = 0;
ret = PX4_ERROR;
}
@@ -471,9 +479,8 @@ int VoxlEsc::parse_response(uint8_t *buf, uint8_t len, bool print_feedback)
uint32_t voltage = fb.voltage;
int32_t current = fb.current * 8;
int32_t temperature = fb.temperature / 100;
PX4_INFO("VOXL_ESC: [%" PRId64 "] ID_RAW=%d ID=%d, RPM=%5d, PWR=%3d%%, V=%5dmV, I=%+5dmA, T=%+3dC", tnow, (int)id,
motor_idx + 1,
(int)rpm, (int)power, (int)voltage, (int)current, (int)temperature);
PX4_ERR("[%" PRId64 "] ID_RAW=%d ID=%d, RPM=%5d, PWR=%3d%%, V=%5dmV, I=%+5dmA, T=%+3dC", tnow, (int)id,
motor_idx + 1, (int)rpm, (int)power, (int)voltage, (int)current, (int)temperature);
}
_esc_chans[id].rate_meas = fb.rpm;
@@ -541,24 +548,24 @@ int VoxlEsc::parse_response(uint8_t *buf, uint8_t len, bool print_feedback)
QC_ESC_VERSION_INFO ver;
memcpy(&ver, _fb_packet.buffer, packet_size);
PX4_INFO("VOXL_ESC: ESC ID: %i", ver.id);
PX4_INFO("VOXL_ESC: HW Version: %i", ver.hw_version);
PX4_INFO("VOXL_ESC: SW Version: %i", ver.sw_version);
PX4_INFO("VOXL_ESC: Unique ID: %i", (int)ver.unique_id);
PX4_ERR("ESC ID: %i", ver.id);
PX4_ERR("HW Version: %i", ver.hw_version);
PX4_ERR("SW Version: %i", ver.sw_version);
PX4_ERR("Unique ID: %i", (int)ver.unique_id);
} else if (packet_type == ESC_PACKET_TYPE_VERSION_EXT_RESPONSE && packet_size == sizeof(QC_ESC_EXTENDED_VERSION_INFO)) {
QC_ESC_EXTENDED_VERSION_INFO ver;
memcpy(&ver, _fb_packet.buffer, packet_size);
PX4_INFO("VOXL_ESC: \tESC ID : %i", ver.id);
PX4_INFO("VOXL_ESC: \tBoard : %i", ver.hw_version);
PX4_INFO("VOXL_ESC: \tSW Version : %i", ver.sw_version);
PX4_ERR("\tESC ID : %i", ver.id);
PX4_ERR("\tBoard : %i", ver.hw_version);
PX4_ERR("\tSW Version : %i", ver.sw_version);
uint8_t *u = &ver.unique_id[0];
PX4_INFO("VOXL_ESC: \tUnique ID : 0x%02X%02X%02X%02X%02X%02X%02X%02X%02X%02X%02X%02X",
u[11], u[10], u[9], u[8], u[7], u[6], u[5], u[4], u[3], u[2], u[1], u[0]);
PX4_ERR("\tUnique ID : 0x%02X%02X%02X%02X%02X%02X%02X%02X%02X%02X%02X%02X",
u[11], u[10], u[9], u[8], u[7], u[6], u[5], u[4], u[3], u[2], u[1], u[0]);
PX4_INFO("VOXL_ESC: \tFirmware : version %4d, hash %.12s", ver.sw_version, ver.firmware_git_version);
PX4_INFO("VOXL_ESC: \tBootloader : version %4d, hash %.12s", ver.bootloader_version, ver.bootloader_git_version);
PX4_ERR("\tFirmware : version %4d, hash %.12s", ver.sw_version, ver.firmware_git_version);
PX4_ERR("\tBootloader : version %4d, hash %.12s", ver.bootloader_version, ver.bootloader_git_version);
} else if (packet_type == ESC_PACKET_TYPE_FB_POWER_STATUS && packet_size == sizeof(QC_ESC_FB_POWER_STATUS)) {
QC_ESC_FB_POWER_STATUS packet;
@@ -671,7 +678,7 @@ int VoxlEsc::custom_command(int argc, char *argv[])
}
if (!is_running()) {
PX4_INFO("VOXL_ESC:Not running");
PX4_INFO("Not running");
return -1;
}
@@ -730,7 +737,7 @@ int VoxlEsc::custom_command(int argc, char *argv[])
if (!strcmp(verb, "reset")) {
if (esc_id < VOXL_ESC_OUTPUT_CHANNELS) {
PX4_INFO("VOXL_ESC: Reset ESC: %i", esc_id);
PX4_ERR("Reset ESC: %i", esc_id);
cmd.len = qc_esc_create_reset_packet(esc_id, cmd.buf, sizeof(cmd.buf));
cmd.response = false;
return get_instance()->send_cmd_thread_safe(&cmd);
@@ -742,7 +749,7 @@ int VoxlEsc::custom_command(int argc, char *argv[])
} else if (!strcmp(verb, "version")) {
if (esc_id < VOXL_ESC_OUTPUT_CHANNELS) {
PX4_INFO("VOXL_ESC: Request version for ESC: %i", esc_id);
PX4_ERR("Request version for ESC: %i", esc_id);
cmd.len = qc_esc_create_version_request_packet(esc_id, cmd.buf, sizeof(cmd.buf));
cmd.response = true;
cmd.resp_delay_us = 2000;
@@ -755,7 +762,7 @@ int VoxlEsc::custom_command(int argc, char *argv[])
} else if (!strcmp(verb, "version-ext")) {
if (esc_id < VOXL_ESC_OUTPUT_CHANNELS) {
PX4_INFO("VOXL_ESC: Request extended version for ESC: %i", esc_id);
PX4_ERR("Request extended version for ESC: %i", esc_id);
cmd.len = qc_esc_create_extended_version_request_packet(esc_id, cmd.buf, sizeof(cmd.buf));
cmd.response = true;
cmd.resp_delay_us = 5000;
@@ -768,7 +775,7 @@ int VoxlEsc::custom_command(int argc, char *argv[])
} else if (!strcmp(verb, "tone")) {
if (esc_id < VOXL_ESC_OUTPUT_CHANNELS) {
PX4_INFO("VOXL_ESC: Request tone for ESC mask: %i", esc_id);
PX4_ERR("Request tone for ESC mask: %i", esc_id);
cmd.len = qc_esc_create_sound_packet(period, duration, power, esc_id, cmd.buf, sizeof(cmd.buf));
cmd.response = false;
return get_instance()->send_cmd_thread_safe(&cmd);
@@ -782,7 +789,7 @@ int VoxlEsc::custom_command(int argc, char *argv[])
if (led_mask <= 0x0FFF) {
get_instance()->_led_rsc.test = true;
get_instance()->_led_rsc.breath_en = false;
PX4_INFO("VOXL_ESC: Request LED control for ESCs with mask: %i", led_mask);
PX4_ERR("Request LED control for ESCs with mask: %i", led_mask);
get_instance()->_esc_chans[0].led = (led_mask & 0x0007);
get_instance()->_esc_chans[1].led = (led_mask & 0x0038) >> 3;
@@ -797,7 +804,7 @@ int VoxlEsc::custom_command(int argc, char *argv[])
} else if (!strcmp(verb, "rpm")) {
if (esc_id < VOXL_ESC_OUTPUT_CHANNELS) {
PX4_INFO("VOXL_ESC: Request RPM for ESC ID: %i - RPM: %i", esc_id, rate);
PX4_ERR("Request RPM for ESC ID: %i - RPM: %i", esc_id, rate);
int16_t rate_req[VOXL_ESC_OUTPUT_CHANNELS] = {0, 0, 0, 0};
uint8_t id_fb = 0;
@@ -831,8 +838,8 @@ int VoxlEsc::custom_command(int argc, char *argv[])
cmd.repeat_delay_us = repeat_delay_us;
cmd.print_feedback = true;
PX4_INFO("VOXL_ESC: Feedback id debug: %i", id_fb);
PX4_INFO("VOXL_ESC: Sending UART ESC RPM command %i", rate);
PX4_ERR("Feedback id debug: %i", id_fb);
PX4_ERR("Sending UART ESC RPM command %i", rate);
return get_instance()->send_cmd_thread_safe(&cmd);
@@ -843,7 +850,7 @@ int VoxlEsc::custom_command(int argc, char *argv[])
} else if (!strcmp(verb, "pwm")) {
if (esc_id < VOXL_ESC_OUTPUT_CHANNELS) {
PX4_INFO("VOXL_ESC: Request PWM for ESC ID: %i - PWM: %i", esc_id, rate);
PX4_ERR("Request PWM for ESC ID: %i - PWM: %i", esc_id, rate);
int16_t rate_req[VOXL_ESC_OUTPUT_CHANNELS] = {0, 0, 0, 0};
uint8_t id_fb = 0;
@@ -876,8 +883,8 @@ int VoxlEsc::custom_command(int argc, char *argv[])
cmd.repeat_delay_us = repeat_delay_us;
cmd.print_feedback = true;
PX4_INFO("VOXL_ESC: Feedback id debug: %i", id_fb);
PX4_INFO("VOXL_ESC: Sending UART ESC power command %i", rate);
PX4_ERR("Feedback id debug: %i", id_fb);
PX4_ERR("Sending UART ESC power command %i", rate);
return get_instance()->send_cmd_thread_safe(&cmd);
@@ -1242,14 +1249,58 @@ bool VoxlEsc::updateOutputs(bool stop_motors, uint16_t outputs[MAX_ACTUATORS],
_extended_rpm);
if (_uart_port.write(cmd.buf, cmd.len) != cmd.len) {
PX4_ERR("VOXL_ESC: Failed to send packet");
PX4_ERR("Failed to send packet");
return false;
}
// Track and manage gpio command writes
bool write_gpio_command = false;
if (_gpio_ctl_en) {
if (_gpio_ctl_high != _prev_gpio_ctl_high) {
_gpio_write_counter = 0;
}
if (_gpio_write_counter < 10) {
write_gpio_command = true;
_gpio_write_counter++;
}
_prev_gpio_ctl_high = _gpio_ctl_high;
if (write_gpio_command) {
Command gpio_cmd;
const int ESC_PACKET_TYPE_GPIO_CMD = 15;
uint8_t data[5];
int esc_id = 0; // In future un-hardcode
int val = 0;
if (_gpio_ctl_high) {
val = 1;
}
data[0] = esc_id; // esc id
data[1] = 80; // 01010000 : pin F0
data[2] = 0; // 0: output, 1: input
data[3] = val; //cmd LSB
data[4] = 0; // cmd MSB
// type, data, size
gpio_cmd.len = qc_esc_create_packet(ESC_PACKET_TYPE_GPIO_CMD, (uint8_t *) & (data[0]), 5, gpio_cmd.buf,
sizeof(gpio_cmd.buf));
if (_uart_port.write(gpio_cmd.buf, gpio_cmd.len) != gpio_cmd.len) {
PX4_ERR("Failed to send gpio packet");
return false;
}
}
}
// increment ESC id from which to request feedback in round robin order
_fb_idx = (_fb_idx + 1) % VOXL_ESC_OUTPUT_CHANNELS;
/*
* Here we read and parse response from ESCs. Since the latest command has just been sent out,
* the response packet we may read here is probabaly from previous iteration, but it is totally ok.
@@ -1283,20 +1334,18 @@ bool VoxlEsc::updateOutputs(bool stop_motors, uint16_t outputs[MAX_ACTUATORS],
_esc_status_pub.publish(_esc_status);
// If any extra external modal io data has been received then
// send it over as well
while (_voxl2_io_data_sub.updated()) {
buffer128_s io_data{};
_voxl2_io_data_sub.copy(&io_data);
uint8_t num_writes = 0;
// PX4_INFO("Got Modal IO data: %u bytes", io_data.len);
// PX4_INFO(" 0x%.2x 0x%.2x 0x%.2x 0x%.2x 0x%.2x 0x%.2x 0x%.2x 0x%.2x",
// io_data.data[0], io_data.data[1], io_data.data[2], io_data.data[3],
// io_data.data[4], io_data.data[5], io_data.data[6], io_data.data[7]);
if (_uart_port.write(io_data.data, io_data.len) != io_data.len) {
PX4_ERR("VOXL_ESC: Failed to send modal io data to esc");
while (_esc_serial_passthru_sub.updated() && (num_writes < 4)) {
mavlink_tunnel_s uart_passthru{};
_esc_serial_passthru_sub.copy(&uart_passthru);
if (_uart_port.write(uart_passthru.payload, uart_passthru.payload_length) != uart_passthru.payload_length) {
PX4_ERR("Failed to send mavlink tunnel data to esc");
return false;
}
num_writes++;
}
perf_count(_output_update_perf);
@@ -1308,7 +1357,7 @@ bool VoxlEsc::updateOutputs(bool stop_motors, uint16_t outputs[MAX_ACTUATORS],
void VoxlEsc::Run()
{
if (should_exit()) {
PX4_ERR("VOXL_ESC: Stopping the module");
PX4_ERR("Stopping the module");
ScheduleClear();
_mixing_output.unregister();
@@ -1328,12 +1377,12 @@ void VoxlEsc::Run()
int dev_init_ret = device_init();
if (dev_init_ret != 0) {
PX4_WARN("VOXL_ESC: Failed to initialize device, retries left %d", retries_left);
PX4_WARN("Failed to initialize device, retries left %d", retries_left);
}
}
if (!_device_initialized) {
PX4_ERR("VOXL_ESC: Failed to initialize device, exiting the module");
PX4_ERR("Failed to initialize device, exiting the module");
ScheduleClear();
_mixing_output.unregister();
exit_and_cleanup();
@@ -1374,11 +1423,12 @@ void VoxlEsc::Run()
update_leds(_led_rsc.mode, _led_rsc.control);
}
if (_parameters.mode > 0) {
/* if turtle mode enabled, we go straight to the sticks, no mix */
if (_manual_control_setpoint_sub.updated()) {
/* check whether sticks have been updated */
if (_manual_control_setpoint_sub.updated()) {
_manual_control_setpoint_sub.copy(&_manual_control_setpoint);
_manual_control_setpoint_sub.copy(&_manual_control_setpoint);
// if turtle mode enabled, we go straight to the sticks, no mix
if (_parameters.mode > 0) {
if (!_outputs_on) {
@@ -1400,6 +1450,45 @@ void VoxlEsc::Run()
}
}
// check if gpio control is enabled
if (_parameters.gpio_ctl_channel > 0) {
_gpio_ctl_en = true;
float gpio_setpoint = VOXL_ESC_GPIO_CTL_DISABLED_SETPOINT;
switch (_parameters.gpio_ctl_channel) {
case VOXL_ESC_GPIO_CTL_AUX1:
gpio_setpoint = _manual_control_setpoint.aux1;
break;
case VOXL_ESC_GPIO_CTL_AUX2:
gpio_setpoint = _manual_control_setpoint.aux2;
break;
case VOXL_ESC_GPIO_CTL_AUX3:
gpio_setpoint = _manual_control_setpoint.aux3;
break;
case VOXL_ESC_GPIO_CTL_AUX4:
gpio_setpoint = _manual_control_setpoint.aux4;
break;
case VOXL_ESC_GPIO_CTL_AUX5:
gpio_setpoint = _manual_control_setpoint.aux5;
break;
case VOXL_ESC_GPIO_CTL_AUX6:
gpio_setpoint = _manual_control_setpoint.aux6;
break;
}
if (gpio_setpoint > VOXL_ESC_GPIO_CTL_THRESHOLD) {
_gpio_ctl_high = false;
} else {
_gpio_ctl_high = true;
}
}
}
if (!_outputs_on) {
@@ -1431,19 +1520,19 @@ void VoxlEsc::Run()
} else {
if (_current_cmd.retries == 0) {
_current_cmd.clear();
PX4_ERR("VOXL_ESC: Failed to send command, errno: %i", errno);
PX4_ERR("Failed to send command, errno: %i", errno);
} else {
_current_cmd.retries--;
PX4_ERR("VOXL_ESC: Failed to send command, errno: %i", errno);
PX4_ERR("Failed to send command, errno: %i", errno);
}
}
px4_usleep(_current_cmd.repeat_delay_us);
} while (_current_cmd.repeats-- > 0);
PX4_INFO("VOXL_ESC: RX packet count: %d", (int)_rx_packet_count);
PX4_INFO("VOXL_ESC: CRC error count: %d", (int)_rx_crc_error_count);
PX4_ERR("RX packet count: %d", (int)_rx_packet_count);
PX4_ERR("CRC error count: %d", (int)_rx_crc_error_count);
} else {
Command *new_cmd = _pending_cmd.load();
@@ -1547,9 +1636,11 @@ void VoxlEsc::print_params()
PX4_INFO("Params: VOXL_ESC_VLOG: %" PRId32, _parameters.verbose_logging);
PX4_INFO("Params: VOXL_ESC_PUB_BST: %" PRId32, _parameters.publish_battery_status);
PX4_INFO("Params: VOXL_ESC_T_WARN: %" PRId32, _parameters.esc_warn_temp_threshold);
PX4_INFO("Params: VOXL_ESC_T_OVER: %" PRId32, _parameters.esc_over_temp_threshold);
PX4_INFO("Params: VOXL_ESC_GPIO_CH: %" PRId32, _parameters.gpio_ctl_channel);
}
int VoxlEsc::print_status()
+23 -10
View File
@@ -49,7 +49,7 @@
#include <uORB/topics/led_control.h>
#include <uORB/topics/esc_status.h>
#include <uORB/topics/actuator_test.h>
#include <uORB/topics/buffer128.h>
#include <uORB/topics/mavlink_tunnel.h>
#include <px4_platform_common/Serial.hpp>
@@ -129,17 +129,24 @@ private:
static constexpr uint32_t VOXL_ESC_MODE_TURTLE_AUX1 = 1;
static constexpr uint32_t VOXL_ESC_MODE_TURTLE_AUX2 = 2;
static constexpr uint16_t VOXL_ESC_EXT_RPM =
39; // minimum firmware version for extended RPM command support
static constexpr uint16_t VOXL_ESC_RPM_MAX = INT16_MAX -
1; // 32K, Limit max standard range RPM to prevent overflow (rpm packet packing function accepts int32_t)
static constexpr uint16_t VOXL_ESC_RPM_MAX_EXT = UINT16_MAX -
5; // 65K, Limit max extended range RPM to prevent overflow (rpm packet packing function accepts int32_t)
// minimum firmware version for extended RPM command support
static constexpr uint16_t VOXL_ESC_EXT_RPM = 39;
// 32K, Limit max standard range RPM to prevent overflow (rpm packet packing function accepts int32_t)
static constexpr uint16_t VOXL_ESC_RPM_MAX = INT16_MAX - 1;
// 65K, Limit max extended range RPM to prevent overflow (rpm packet packing function accepts int32_t)
static constexpr uint16_t VOXL_ESC_RPM_MAX_EXT = UINT16_MAX - 5;
static constexpr uint16_t VOXL_ESC_NUM_INIT_RETRIES = 3;
//static constexpr uint16_t max_pwm(uint16_t pwm) { return math::min(pwm, VOXL_ESC_PWM_MAX); }
//static constexpr uint16_t max_rpm(uint16_t rpm) { return math::min(rpm, VOXL_ESC_RPM_MAX); }
static constexpr float VOXL_ESC_GPIO_CTL_DISABLED_SETPOINT = -0.1f;
static constexpr float VOXL_ESC_GPIO_CTL_THRESHOLD = 0.0f;
static constexpr uint32_t VOXL_ESC_GPIO_CTL_AUX1 = 1;
static constexpr uint32_t VOXL_ESC_GPIO_CTL_AUX2 = 2;
static constexpr uint32_t VOXL_ESC_GPIO_CTL_AUX3 = 3;
static constexpr uint32_t VOXL_ESC_GPIO_CTL_AUX4 = 4;
static constexpr uint32_t VOXL_ESC_GPIO_CTL_AUX5 = 5;
static constexpr uint32_t VOXL_ESC_GPIO_CTL_AUX6 = 6;
Serial _uart_port{};
@@ -161,6 +168,7 @@ private:
int32_t publish_battery_status{0};
int32_t esc_warn_temp_threshold{0};
int32_t esc_over_temp_threshold{0};
int32_t gpio_ctl_channel{0};
} voxl_esc_params_t;
struct EscChan {
@@ -205,7 +213,7 @@ private:
uORB::Subscription _parameter_update_sub{ORB_ID(parameter_update)};
uORB::Subscription _actuator_test_sub{ORB_ID(actuator_test)};
uORB::Subscription _led_update_sub{ORB_ID(led_control)};
uORB::Subscription _voxl2_io_data_sub{ORB_ID(voxl2_io_data)};
uORB::Subscription _esc_serial_passthru_sub{ORB_ID(esc_serial_passthru)};
uORB::Publication<actuator_outputs_s> _outputs_debug_pub{ORB_ID(actuator_outputs_debug)};
uORB::Publication<esc_status_s> _esc_status_pub{ORB_ID(esc_status)};
@@ -224,6 +232,11 @@ private:
int32_t _rpm_fullscale{0};
manual_control_setpoint_s _manual_control_setpoint{};
int32_t _gpio_write_counter{0};
bool _gpio_ctl_en{false};
bool _gpio_ctl_high{true};
bool _prev_gpio_ctl_high{true};
uint16_t _cmd_id{0};
Command _current_cmd;
px4::atomic<Command *> _pending_cmd{nullptr};
@@ -262,3 +262,17 @@ PARAM_DEFINE_INT32(VOXL_ESC_T_WARN, 0);
* @max 200
*/
PARAM_DEFINE_INT32(VOXL_ESC_T_OVER, 0);
/**
* GPIO Control Channel
*
*
* @reboot_required true
*
* @group VOXL ESC
* @value 0 - Disabled
* @min 0
* @max 6
*/
PARAM_DEFINE_INT32(VOXL_ESC_GPIO_CH, 0);
+36 -130
View File
@@ -42,18 +42,7 @@ int ADS1115::init()
return ret;
}
uint8_t config[2] = {};
config[0] = CONFIG_HIGH_OS_NOACT | CONFIG_HIGH_MUX_P0NG | CONFIG_HIGH_PGA_6144 | CONFIG_HIGH_MODE_SS;
config[1] = CONFIG_LOW_DR_250SPS | CONFIG_LOW_COMP_MODE_TRADITIONAL | CONFIG_LOW_COMP_POL_RESET |
CONFIG_LOW_COMP_LAT_NONE | CONFIG_LOW_COMP_QU_DISABLE;
ret = writeReg(ADDRESSPOINTER_REG_CONFIG, config, 2);
if (ret != PX4_OK) {
PX4_ERR("writeReg failed (%i)", ret);
return ret;
}
setChannel(ADS1115::A0); // prepare for the first measure.
readChannel(Channel::A0); // prepare for the first measure.
ScheduleOnInterval(SAMPLE_INTERVAL / 4, SAMPLE_INTERVAL / 4);
@@ -62,152 +51,69 @@ int ADS1115::init()
int ADS1115::probe()
{
uint8_t buf[2] = {};
int ret = readReg(ADDRESSPOINTER_REG_CONFIG, buf, 2);
// The ADS1115 has no ID register, so we read out the threshold registers
// and check their default values. We cannot use the config register, as
// this is changed by this driver. Note the default value is in BE.
static constexpr uint32_t DEFAULT{0xFF7F0080};
union {
struct {
uint8_t low[2];
uint8_t high[2];
} parts;
uint32_t threshold{};
};
int ret = readReg(ADDRESSPOINTER_REG_LO_THRESH, parts.low, 2);
if (ret != PX4_OK) {
DEVICE_DEBUG("readReg failed (%i)", ret);
DEVICE_DEBUG("lo_thresh read failed (%i)", ret);
return ret;
}
if (buf[0] != CONFIG_RESET_VALUE_HIGH || buf[1] != CONFIG_RESET_VALUE_LOW) {
DEVICE_DEBUG("ADS1115 not found");
return PX4_ERROR;
ret = readReg(ADDRESSPOINTER_REG_HI_THRESH, parts.high, 2);
if (ret != PX4_OK) {
DEVICE_DEBUG("hi_thresh read failed (%i)", ret);
return ret;
}
return PX4_OK;
if (threshold == DEFAULT) {
return PX4_OK;
}
DEVICE_DEBUG("ADS1115 not found");
return PX4_ERROR;
}
int ADS1115::setChannel(ADS1115::ChannelSelection ch)
int ADS1115::readChannel(ADS1115::Channel ch)
{
uint8_t buf[2] = {};
uint8_t next_mux_reg = CONFIG_HIGH_MUX_P0NG;
switch (ch) {
case A0:
next_mux_reg = CONFIG_HIGH_MUX_P0NG;
break;
case A1:
next_mux_reg = CONFIG_HIGH_MUX_P1NG;
break;
case A2:
next_mux_reg = CONFIG_HIGH_MUX_P2NG;
break;
case A3:
next_mux_reg = CONFIG_HIGH_MUX_P3NG;
break;
default:
assert(false);
break;
}
buf[0] = CONFIG_HIGH_OS_START_SINGLE | next_mux_reg | CONFIG_HIGH_PGA_6144 | CONFIG_HIGH_MODE_SS;
uint8_t buf[2];
buf[0] = CONFIG_HIGH_OS_START_SINGLE | uint8_t(ch) | CONFIG_HIGH_PGA_6144 | CONFIG_HIGH_MODE_SS;
buf[1] = CONFIG_LOW_DR_250SPS | CONFIG_LOW_COMP_MODE_TRADITIONAL | CONFIG_LOW_COMP_POL_RESET |
CONFIG_LOW_COMP_LAT_NONE | CONFIG_LOW_COMP_QU_DISABLE;
return writeReg(ADDRESSPOINTER_REG_CONFIG, buf, 2); // must write whole register to take effect
}
bool ADS1115::isSampleReady()
int ADS1115::isSampleReady()
{
uint8_t buf[1] = {0x00};
if (readReg(ADDRESSPOINTER_REG_CONFIG, buf, 1) != 0) { return false; } // Pull config register
if (readReg(ADDRESSPOINTER_REG_CONFIG, buf, 1) != PX4_OK) { return -1; } // Pull config register
return (buf[0] & (uint8_t) 0x80);
return (buf[0] & (uint8_t) 0x80) ? 1 : 0;
}
ADS1115::ChannelSelection ADS1115::getMeasurement(int16_t *value)
ADS1115::Channel ADS1115::getMeasurement(int16_t *value)
{
uint8_t buf[2] = {0x00};
readReg(ADDRESSPOINTER_REG_CONFIG, buf, 1); // Pull config register
ChannelSelection channel;
switch ((buf[0] & (uint8_t) 0x70) >> 4) {
case 0x04:
channel = A0;
break;
if (readReg(ADDRESSPOINTER_REG_CONFIG, buf, 1) != PX4_OK) { return Channel::Invalid; }
case 0x05:
channel = A1;
break;
const auto channel{Channel(buf[0] & CONFIG_HIGH_MUX_P3NG)};
case 0x06:
channel = A2;
break;
if (readReg(ADDRESSPOINTER_REG_CONVERSATION, buf, 2) != PX4_OK) { return Channel::Invalid; }
case 0x07:
channel = A3;
break;
*value = int16_t((buf[0] << 8) | buf[1]);
default:
return Invalid;
}
readReg(ADDRESSPOINTER_REG_CONVERSATION, buf, 2);
uint16_t raw_adc_val = buf[0] * 256 + buf[1];
if (raw_adc_val & (uint16_t) 0x8000) { // Negetive value
raw_adc_val = ~raw_adc_val + 1; // 2's complement
*value = -raw_adc_val;
} else {
*value = raw_adc_val;
}
return channel;
}
ADS1115::ChannelSelection ADS1115::cycleMeasure(int16_t *value)
{
uint8_t buf[2] = {0x00};
readReg(ADDRESSPOINTER_REG_CONFIG, buf, 1); // Pull config register
ChannelSelection channel;
uint8_t next_mux_reg = CONFIG_HIGH_MUX_P0NG;
switch ((buf[0] & (uint8_t) 0x70) >> 4) {
case 0x04:
channel = A0;
next_mux_reg = CONFIG_HIGH_MUX_P1NG;
break;
case 0x05:
channel = A1;
next_mux_reg = CONFIG_HIGH_MUX_P2NG;
break;
case 0x06:
channel = A2;
next_mux_reg = CONFIG_HIGH_MUX_P3NG;
break;
case 0x07:
channel = A3;
next_mux_reg = CONFIG_HIGH_MUX_P0NG;
break;
default:
return Invalid;
}
readReg(ADDRESSPOINTER_REG_CONVERSATION, buf, 2);
uint16_t raw_adc_val = buf[0] * 256 + buf[1];
if (raw_adc_val & (uint16_t) 0x8000) { // Negetive value
raw_adc_val = ~raw_adc_val + 1; // 2's complement
*value = -raw_adc_val;
} else {
*value = raw_adc_val;
}
buf[0] = CONFIG_HIGH_OS_START_SINGLE | next_mux_reg | CONFIG_HIGH_PGA_6144 | CONFIG_HIGH_MODE_SS;
buf[1] = CONFIG_LOW_DR_250SPS | CONFIG_LOW_COMP_MODE_TRADITIONAL | CONFIG_LOW_COMP_POL_RESET |
CONFIG_LOW_COMP_LAT_NONE | CONFIG_LOW_COMP_QU_DISABLE;
writeReg(ADDRESSPOINTER_REG_CONFIG, buf, 2); // must write whole register to take effect
return channel;
}
+20 -19
View File
@@ -93,9 +93,6 @@
#define CONFIG_LOW_COMP_QU_AFTER4 0x02
#define CONFIG_LOW_COMP_QU_DISABLE 0x03
#define CONFIG_RESET_VALUE_HIGH 0x85
#define CONFIG_RESET_VALUE_LOW 0x83
using namespace time_literals;
/*
@@ -127,35 +124,39 @@ protected:
private:
uORB::PublicationMulti<adc_report_s> _to_adc_report{ORB_ID(adc_report)};
uORB::PublicationMulti<adc_report_s> _to_adc_report{ORB_ID(adc_report)};
static const hrt_abstime SAMPLE_INTERVAL{50_ms};
static const hrt_abstime SAMPLE_INTERVAL{50_ms};
adc_report_s _adc_report{};
perf_counter_t _cycle_perf;
perf_counter_t _cycle_perf;
perf_counter_t _comms_errors;
int _channel_cycle_count{0};
uint8_t _channel_cycle_mask{0};
bool _reported_ready_last_cycle{false};
static constexpr uint8_t MAX_READY_COUNTER{20};
uint8_t _ready_counter{MAX_READY_COUNTER};
// ADS1115 logic part
enum ChannelSelection {
Invalid = -1, A0 = 0, A1, A2, A3
enum class Channel : uint8_t {
A0 = CONFIG_HIGH_MUX_P0NG,
A1 = CONFIG_HIGH_MUX_P1NG,
A2 = CONFIG_HIGH_MUX_P2NG,
A3 = CONFIG_HIGH_MUX_P3NG,
Invalid = 0xff,
};
/* set multiplexer to specific channel */
int setChannel(ChannelSelection ch);
/* return true if sample result is valid */
bool isSampleReady();
constexpr unsigned ch2u(Channel ch) { return (unsigned(ch) >> 4) & 0b11u; }
constexpr Channel u2ch(unsigned ch) { return Channel((ch << 4) | CONFIG_HIGH_MUX_P0NG); }
// Set the channel and start a conversion
int readChannel(Channel ch);
// return 1 if sample result is valid else 0 or -1 if I2C transaction failed
int isSampleReady();
/*
* get adc sample. return the channel being measured.
* Invalid indicates sample failure.
*/
ChannelSelection getMeasurement(int16_t *value);
/*
* get adc sample and automatically switch to next channel and start another measurement
*/
ChannelSelection cycleMeasure(int16_t *value);
Channel getMeasurement(int16_t *value);
int readReg(uint8_t addr, uint8_t *buf, size_t len);
+45 -43
View File
@@ -45,7 +45,8 @@
ADS1115::ADS1115(const I2CSPIDriverConfig &config) :
I2C(config),
I2CSPIDriver(config),
_cycle_perf(perf_alloc(PC_ELAPSED, MODULE_NAME": single-sample"))
_cycle_perf(perf_alloc(PC_ELAPSED, MODULE_NAME": single-sample")),
_comms_errors(perf_alloc(PC_COUNT, MODULE_NAME": comms errors"))
{
_adc_report.device_id = this->get_device_id();
_adc_report.resolution = 32768;
@@ -61,6 +62,7 @@ ADS1115::~ADS1115()
{
ScheduleClear();
perf_free(_cycle_perf);
perf_free(_comms_errors);
}
void ADS1115::exit_and_cleanup()
@@ -77,56 +79,55 @@ void ADS1115::RunImpl()
perf_begin(_cycle_perf);
_adc_report.timestamp = hrt_absolute_time();
const int ready = isSampleReady();
if (isSampleReady()) { // whether ADS1115 is ready to be read or not
if (!_reported_ready_last_cycle) {
PX4_INFO("ADS1115: reported ready");
_reported_ready_last_cycle = true;
if (ready == 1) {
// I2C transaction success and status register reported conversion as finished
if (_ready_counter == 0) { PX4_INFO("ADS1115: reported ready"); }
if (_ready_counter < MAX_READY_COUNTER) { _ready_counter++; }
int16_t value;
Channel ch = getMeasurement(&value);
if (ch != Channel::Invalid) {
// Store current readings and mark channel as read
const unsigned index{ch2u(ch)};
_adc_report.channel_id[index] = index;
_adc_report.raw_data[index] = value;
_channel_cycle_mask |= 1u << index;
} else {
// we will retry the same channel again
perf_count(_comms_errors);
}
int16_t buf;
ADS1115::ChannelSelection ch = cycleMeasure(&buf);
++_channel_cycle_count;
// Find the next unread channel in the bitmask
uint8_t next_index{0};
switch (ch) {
case ADS1115::A0:
_adc_report.channel_id[0] = 0;
_adc_report.raw_data[0] = buf;
break;
for (; next_index < 4 && (_channel_cycle_mask & (1u << next_index)); next_index++) {}
case ADS1115::A1:
_adc_report.channel_id[1] = 1;
_adc_report.raw_data[1] = buf;
break;
readChannel(u2ch(next_index));
case ADS1115::A2:
_adc_report.channel_id[2] = 2;
_adc_report.raw_data[2] = buf;
break;
case ADS1115::A3:
_adc_report.channel_id[3] = 3;
_adc_report.raw_data[3] = buf;
break;
default:
PX4_DEBUG("ADS1115: undefined behaviour");
setChannel(ADS1115::A0);
--_channel_cycle_count;
break;
}
if (_channel_cycle_count == 4) { // ADS1115 has 4 channels
_channel_cycle_count = 0;
if (_channel_cycle_mask == 0b1111) {
_channel_cycle_mask = 0;
_to_adc_report.publish(_adc_report);
}
} else {
if (_reported_ready_last_cycle) {
_reported_ready_last_cycle = false;
PX4_ERR("ADS1115: not ready. Device lost?");
}
} else if (ready == 0) {
// I2C transaction success but status register reported conversion still in progress
perf_count(_comms_errors);
// Reset the channel to unstick the device
readChannel(Channel::A0);
} else if (ready == -1) {
if (_ready_counter == 1) { PX4_ERR("ADS1115: device lost"); }
if (_ready_counter > 0) { _ready_counter--; }
perf_count(_comms_errors);
// Reset the channel to unstick the device
readChannel(Channel::A0);
}
perf_end(_cycle_perf);
@@ -151,7 +152,7 @@ parameter, and is disabled by default.
If enabled, internal ADCs are not used.
)DESCR_STR");
PRINT_MODULE_USAGE_NAME("ads1115", "driver");
PRINT_MODULE_USAGE_COMMAND("start");
PRINT_MODULE_USAGE_PARAMS_I2C_SPI_DRIVER(true, false);
@@ -163,6 +164,7 @@ void ADS1115::print_status()
{
I2CSPIDriverBase::print_status();
perf_print_counter(_cycle_perf);
perf_print_counter(_comms_errors);
}
extern "C" int ads1115_main(int argc, char *argv[])
+5 -5
View File
@@ -172,19 +172,19 @@ void BATT_SMBUS::RunImpl()
// Check if max lifetime voltage delta is greater than allowed.
if (_lifetime_max_delta_cell_voltage > BATT_CELL_VOLTAGE_THRESHOLD_FAILED) {
new_report.warning = battery_status_s::BATTERY_WARNING_CRITICAL;
new_report.warning = battery_status_s::WARNING_CRITICAL;
} else if (new_report.remaining > _low_thr) {
new_report.warning = battery_status_s::BATTERY_WARNING_NONE;
new_report.warning = battery_status_s::WARNING_NONE;
} else if (new_report.remaining > _crit_thr) {
new_report.warning = battery_status_s::BATTERY_WARNING_LOW;
new_report.warning = battery_status_s::WARNING_LOW;
} else if (new_report.remaining > _emergency_thr) {
new_report.warning = battery_status_s::BATTERY_WARNING_CRITICAL;
new_report.warning = battery_status_s::WARNING_CRITICAL;
} else {
new_report.warning = battery_status_s::BATTERY_WARNING_EMERGENCY;
new_report.warning = battery_status_s::WARNING_EMERGENCY;
}
new_report.interface_error = perf_event_count(_interface->_interface_errors);
@@ -143,7 +143,7 @@ private:
)
uORB::Subscription _parameter_update_sub{ORB_ID(parameter_update)};
uORB::Subscription _vehicle_status_sub{ORB_ID(vehicle_status)};
typeof(px4::msg::VehicleStatus::vehicle_type) _vehicle_type{px4::msg::VehicleStatus::VEHICLE_TYPE_UNKNOWN};
typeof(px4::msg::VehicleStatus::vehicle_type) _vehicle_type{px4::msg::VehicleStatus::VEHICLE_TYPE_ROTARY_WING};
uORB::Subscription _dist_sense_mode_change_sub{ORB_ID(distance_sensor_mode_change_request)};
typeof(px4::msg::DistanceSensorModeChangeRequest::request_on_off) _req_mode{px4::msg::DistanceSensorModeChangeRequest::REQUEST_OFF};
bool _restriction{false};
@@ -125,10 +125,15 @@ int AerotennaULanding::collect()
index--;
}
} else {
return -EAGAIN;
}
if (!checksum_passed) {
return -EAGAIN;
perf_count(_comms_errors);
perf_end(_sample_perf);
return -EBADMSG;
}
_px4_rangefinder.update(timestamp_sample, distance_m);
@@ -56,7 +56,7 @@
using namespace time_literals;
#define ULANDING_MEASURE_INTERVAL 10_ms
#define ULANDING_MEASURE_INTERVAL 12_ms
#define ULANDING_MAX_DISTANCE 50.0f
#define ULANDING_MIN_DISTANCE 0.315f
#define ULANDING_VERSION 1

Some files were not shown because too many files have changed in this diff Show More