mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-06-11 19:30:06 +08:00
Compare commits
50 Commits
| Author | SHA1 | Date | |
|---|---|---|---|
| d230215368 | |||
| 5793c002cd | |||
| af17bd75bd | |||
| ea8bcd9cef | |||
| 0ab3e45c13 | |||
| 2aecdfe116 | |||
| 0ee592f67c | |||
| d1e4198864 | |||
| a127a8293a | |||
| d857a278ff | |||
| 7cb6464cfb | |||
| 49a84f38a2 | |||
| 5c7143a33b | |||
| 71d514d359 | |||
| 38a794260c | |||
| 9198125ec5 | |||
| 6dc39d9deb | |||
| 3b2d74b017 | |||
| 2d1652f499 | |||
| d4509a6cd4 | |||
| b5f37c9fa6 | |||
| 336d055923 | |||
| 0a9a1a1552 | |||
| 1f5a9e526c | |||
| 14941bc270 | |||
| ba31054992 | |||
| 93b8bc1515 | |||
| 5fb810a5ea | |||
| d4918ea118 | |||
| 1ba9eeafd9 | |||
| f23ae924de | |||
| 75c0089c26 | |||
| 84134e5123 | |||
| f69361f742 | |||
| 5d2814f6c9 | |||
| 2169ea561b | |||
| 0cb7b8b525 | |||
| e6b80d8800 | |||
| 65a80dc8e6 | |||
| 7c63468e8b | |||
| d602b569b1 | |||
| c09c63171c | |||
| 393d4c13db | |||
| e907fb0aa2 | |||
| f419124e28 | |||
| 18d823f9e3 | |||
| d4c51ce762 | |||
| 0df117bfa5 | |||
| 59c25aa26b | |||
| f72845e0c1 |
@@ -88,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
@@ -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)
|
||||
|
||||
@@ -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"
|
||||
|
||||
@@ -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/).
|
||||
|
||||
@@ -50,69 +52,11 @@ For the latest stats on contributors please see the latest stats for the Droneco
|
||||
|
||||
## 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"> </div>
|
||||
|
||||
@@ -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,10 +14,6 @@ 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_DISARM_LAND 0.5
|
||||
|
||||
|
||||
@@ -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
|
||||
|
||||
@@ -45,12 +45,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
|
||||
|
||||
# Actuator mapping
|
||||
param set-default SIM_GZ_WH_FUNC1 101 # right wheel
|
||||
param set-default SIM_GZ_WH_MIN1 70
|
||||
|
||||
@@ -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
|
||||
|
||||
@@ -91,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
|
||||
|
||||
@@ -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
|
||||
|
||||
#
|
||||
|
||||
+1
-1
Submodule Tools/simulation/gz updated: 183cbee9e2...6c18846a4c
@@ -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;
|
||||
|
||||
@@ -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,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
|
||||
|
||||
@@ -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
-4
@@ -173,14 +173,11 @@ set(msg_files
|
||||
RcParameterMap.msg
|
||||
RoverAttitudeSetpoint.msg
|
||||
RoverAttitudeStatus.msg
|
||||
RoverVelocityStatus.msg
|
||||
RoverRateSetpoint.msg
|
||||
RoverRateStatus.msg
|
||||
RoverSteeringSetpoint.msg
|
||||
RoverThrottleSetpoint.msg
|
||||
RoverMecanumGuidanceStatus.msg
|
||||
RoverMecanumSetpoint.msg
|
||||
RoverMecanumStatus.msg
|
||||
RoverVelocityStatus.msg
|
||||
Rpm.msg
|
||||
RtlStatus.msg
|
||||
RtlTimeEstimate.msg
|
||||
|
||||
@@ -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
|
||||
|
||||
@@ -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
|
||||
@@ -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
|
||||
@@ -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
|
||||
@@ -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
|
||||
|
||||
@@ -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)
|
||||
|
||||
|
||||
@@ -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
|
||||
|
||||
@@ -87,13 +87,13 @@ 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
|
||||
|
||||
@@ -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
|
||||
|
||||
@@ -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;
|
||||
|
||||
@@ -1334,6 +1334,20 @@ bool VoxlEsc::updateOutputs(bool stop_motors, uint16_t outputs[MAX_ACTUATORS],
|
||||
|
||||
_esc_status_pub.publish(_esc_status);
|
||||
|
||||
uint8_t num_writes = 0;
|
||||
|
||||
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);
|
||||
|
||||
return true;
|
||||
@@ -1622,7 +1636,7 @@ 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);
|
||||
|
||||
|
||||
@@ -49,6 +49,7 @@
|
||||
#include <uORB/topics/led_control.h>
|
||||
#include <uORB/topics/esc_status.h>
|
||||
#include <uORB/topics/actuator_test.h>
|
||||
#include <uORB/topics/mavlink_tunnel.h>
|
||||
|
||||
#include <px4_platform_common/Serial.hpp>
|
||||
|
||||
@@ -212,6 +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 _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)};
|
||||
|
||||
@@ -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;
|
||||
}
|
||||
|
||||
|
||||
@@ -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,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[])
|
||||
|
||||
@@ -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
|
||||
|
||||
@@ -52,7 +52,7 @@ INA220::INA220(const I2CSPIDriverConfig &config, int battery_index) :
|
||||
_collection_errors(perf_alloc(PC_COUNT, "ina220_collection_err")),
|
||||
_measure_errors(perf_alloc(PC_COUNT, "ina220_measurement_err")),
|
||||
_ch_type((PM_CH_TYPE)config.custom2),
|
||||
_battery(battery_index, this, INA220_SAMPLE_INTERVAL_US, battery_status_s::BATTERY_SOURCE_POWER_MODULE)
|
||||
_battery(battery_index, this, INA220_SAMPLE_INTERVAL_US, battery_status_s::SOURCE_POWER_MODULE)
|
||||
{
|
||||
float fvalue = MAX_CURRENT;
|
||||
_max_current = fvalue;
|
||||
|
||||
@@ -49,7 +49,7 @@ INA226::INA226(const I2CSPIDriverConfig &config, int battery_index) :
|
||||
_comms_errors(perf_alloc(PC_COUNT, "ina226_com_err")),
|
||||
_collection_errors(perf_alloc(PC_COUNT, "ina226_collection_err")),
|
||||
_measure_errors(perf_alloc(PC_COUNT, "ina226_measurement_err")),
|
||||
_battery(battery_index, this, INA226_SAMPLE_INTERVAL_US, battery_status_s::BATTERY_SOURCE_POWER_MODULE)
|
||||
_battery(battery_index, this, INA226_SAMPLE_INTERVAL_US, battery_status_s::SOURCE_POWER_MODULE)
|
||||
{
|
||||
float fvalue = MAX_CURRENT;
|
||||
_max_current = fvalue;
|
||||
|
||||
@@ -49,7 +49,7 @@ INA228::INA228(const I2CSPIDriverConfig &config, int battery_index) :
|
||||
_comms_errors(perf_alloc(PC_COUNT, "ina228_com_err")),
|
||||
_collection_errors(perf_alloc(PC_COUNT, "ina228_collection_err")),
|
||||
_measure_errors(perf_alloc(PC_COUNT, "ina228_measurement_err")),
|
||||
_battery(battery_index, this, INA228_SAMPLE_INTERVAL_US, battery_status_s::BATTERY_SOURCE_POWER_MODULE)
|
||||
_battery(battery_index, this, INA228_SAMPLE_INTERVAL_US, battery_status_s::SOURCE_POWER_MODULE)
|
||||
{
|
||||
float fvalue = MAX_CURRENT;
|
||||
_max_current = fvalue;
|
||||
|
||||
@@ -45,7 +45,7 @@ INA238::INA238(const I2CSPIDriverConfig &config, int battery_index) :
|
||||
_sample_perf(perf_alloc(PC_ELAPSED, "ina238_read")),
|
||||
_comms_errors(perf_alloc(PC_COUNT, "ina238_com_err")),
|
||||
_collection_errors(perf_alloc(PC_COUNT, "ina238_collection_err")),
|
||||
_battery(battery_index, this, INA238_SAMPLE_INTERVAL_US, battery_status_s::BATTERY_SOURCE_POWER_MODULE)
|
||||
_battery(battery_index, this, INA238_SAMPLE_INTERVAL_US, battery_status_s::SOURCE_POWER_MODULE)
|
||||
{
|
||||
float fvalue = DEFAULT_MAX_CURRENT;
|
||||
_max_current = fvalue;
|
||||
|
||||
@@ -54,7 +54,7 @@ VOXLPM::VOXLPM(const I2CSPIDriverConfig &config) :
|
||||
_sample_perf(perf_alloc(PC_ELAPSED, MODULE_NAME": sample")),
|
||||
_comms_errors(perf_alloc(PC_COUNT, MODULE_NAME": comms_errors")),
|
||||
_ch_type((VOXLPM_CH_TYPE)config.custom1),
|
||||
_battery(1, this, _meas_interval_us, battery_status_s::BATTERY_SOURCE_POWER_MODULE)
|
||||
_battery(1, this, _meas_interval_us, battery_status_s::SOURCE_POWER_MODULE)
|
||||
{
|
||||
}
|
||||
|
||||
|
||||
@@ -34,6 +34,7 @@
|
||||
#include "GhstRc.hpp"
|
||||
|
||||
#include <termios.h>
|
||||
#include <math.h>
|
||||
|
||||
GhstRc::GhstRc(const char *device) :
|
||||
ModuleParams(nullptr),
|
||||
@@ -174,16 +175,18 @@ void GhstRc::Run()
|
||||
if (newBytes > 0) {
|
||||
uint16_t raw_rc_values[input_rc_s::RC_INPUT_MAX_CHANNELS] {};
|
||||
uint16_t raw_rc_count = 0;
|
||||
int8_t ghst_rssi = -1;
|
||||
ghstLinkStatistics_t link_stats = { .rssi_pct = -1, .rssi_dbm = NAN, .link_quality = 0 };
|
||||
|
||||
if (ghst_parse(cycle_timestamp, &rcs_buf[0], newBytes, &raw_rc_values[0], &ghst_rssi,
|
||||
if (ghst_parse(cycle_timestamp, &rcs_buf[0], newBytes, &raw_rc_values[0], &link_stats,
|
||||
&raw_rc_count, input_rc_s::RC_INPUT_MAX_CHANNELS)
|
||||
) {
|
||||
// we have a new GHST frame. Publish it.
|
||||
input_rc_s input_rc{};
|
||||
input_rc.timestamp_last_signal = cycle_timestamp;
|
||||
input_rc.channel_count = math::constrain(raw_rc_count, (uint16_t)0, (uint16_t)input_rc_s::RC_INPUT_MAX_CHANNELS);
|
||||
input_rc.rssi = ghst_rssi;
|
||||
input_rc.rssi = link_stats.rssi_pct;
|
||||
input_rc.link_quality = link_stats.link_quality;
|
||||
input_rc.rssi_dbm = link_stats.rssi_dbm;
|
||||
input_rc.input_source = input_rc_s::RC_INPUT_SOURCE_PX4FMU_GHST;
|
||||
|
||||
unsigned valid_chans = 0;
|
||||
@@ -200,13 +203,11 @@ void GhstRc::Run()
|
||||
|
||||
if (valid_chans == 0) {
|
||||
input_rc.rssi = 0;
|
||||
// can't force link quality to zero here, receiver takes care of this
|
||||
}
|
||||
|
||||
input_rc.rc_lost = (valid_chans == 0);
|
||||
|
||||
input_rc.link_quality = -1;
|
||||
input_rc.rssi_dbm = NAN;
|
||||
|
||||
input_rc.timestamp = hrt_absolute_time();
|
||||
_input_rc_pub.publish(input_rc);
|
||||
perf_count(_publish_interval_perf);
|
||||
|
||||
@@ -762,14 +762,15 @@ void RCInput::Run()
|
||||
|
||||
// parse new data
|
||||
if (newBytes > 0) {
|
||||
int8_t ghst_rssi = -1;
|
||||
rc_updated = ghst_parse(cycle_timestamp, &_rcs_buf[0], newBytes, &_raw_rc_values[0], &ghst_rssi,
|
||||
ghstLinkStatistics_t link_stats = { .rssi_pct = -1, .rssi_dbm = NAN, .link_quality = 0 };
|
||||
|
||||
rc_updated = ghst_parse(cycle_timestamp, &_rcs_buf[0], newBytes, &_raw_rc_values[0], &link_stats,
|
||||
&_raw_rc_count, input_rc_s::RC_INPUT_MAX_CHANNELS);
|
||||
|
||||
if (rc_updated) {
|
||||
// we have a new GHST frame. Publish it.
|
||||
_input_rc.input_source = input_rc_s::RC_INPUT_SOURCE_PX4FMU_GHST;
|
||||
int32_t valid_chans = fill_rc_in(_raw_rc_count, _raw_rc_values, cycle_timestamp, false, false, 0, ghst_rssi);
|
||||
int32_t valid_chans = 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
|
||||
|
||||
@@ -199,19 +199,19 @@ void Batmon::RunImpl()
|
||||
// TODO: This critical setting should be set with BMS info or through a paramter
|
||||
// Setting a hard coded BATT_CELL_VOLTAGE_THRESHOLD_FAILED may not be appropriate
|
||||
//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;
|
||||
|
||||
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);
|
||||
|
||||
@@ -44,7 +44,7 @@ UavcanBatteryBridge::UavcanBatteryBridge(uavcan::INode &node) :
|
||||
ModuleParams(nullptr),
|
||||
_sub_battery(node),
|
||||
_sub_battery_aux(node),
|
||||
_warning(battery_status_s::BATTERY_WARNING_NONE),
|
||||
_warning(battery_status_s::WARNING_NONE),
|
||||
_last_timestamp(0)
|
||||
{
|
||||
}
|
||||
@@ -215,14 +215,14 @@ void
|
||||
UavcanBatteryBridge::determineWarning(float remaining)
|
||||
{
|
||||
// propagate warning state only if the state is higher, otherwise remain in current warning state
|
||||
if (remaining < _param_bat_emergen_thr.get() || (_warning == battery_status_s::BATTERY_WARNING_EMERGENCY)) {
|
||||
_warning = battery_status_s::BATTERY_WARNING_EMERGENCY;
|
||||
if (remaining < _param_bat_emergen_thr.get() || (_warning == battery_status_s::WARNING_EMERGENCY)) {
|
||||
_warning = battery_status_s::WARNING_EMERGENCY;
|
||||
|
||||
} else if (remaining < _param_bat_crit_thr.get() || (_warning == battery_status_s::BATTERY_WARNING_CRITICAL)) {
|
||||
_warning = battery_status_s::BATTERY_WARNING_CRITICAL;
|
||||
} else if (remaining < _param_bat_crit_thr.get() || (_warning == battery_status_s::WARNING_CRITICAL)) {
|
||||
_warning = battery_status_s::WARNING_CRITICAL;
|
||||
|
||||
} else if (remaining < _param_bat_low_thr.get() || (_warning == battery_status_s::BATTERY_WARNING_LOW)) {
|
||||
_warning = battery_status_s::BATTERY_WARNING_LOW;
|
||||
} else if (remaining < _param_bat_low_thr.get() || (_warning == battery_status_s::WARNING_LOW)) {
|
||||
_warning = battery_status_s::WARNING_LOW;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
@@ -107,10 +107,10 @@ private:
|
||||
|
||||
static_assert(battery_status_s::MAX_INSTANCES <= BATTERY_INDEX_4, "Battery array too big");
|
||||
|
||||
Battery battery1 = {BATTERY_INDEX_1, this, SAMPLE_INTERVAL_US, battery_status_s::BATTERY_SOURCE_EXTERNAL};
|
||||
Battery battery2 = {BATTERY_INDEX_2, this, SAMPLE_INTERVAL_US, battery_status_s::BATTERY_SOURCE_EXTERNAL};
|
||||
Battery battery3 = {BATTERY_INDEX_3, this, SAMPLE_INTERVAL_US, battery_status_s::BATTERY_SOURCE_EXTERNAL};
|
||||
Battery battery4 = {BATTERY_INDEX_4, this, SAMPLE_INTERVAL_US, battery_status_s::BATTERY_SOURCE_EXTERNAL};
|
||||
Battery battery1 = {BATTERY_INDEX_1, this, SAMPLE_INTERVAL_US, battery_status_s::SOURCE_EXTERNAL};
|
||||
Battery battery2 = {BATTERY_INDEX_2, this, SAMPLE_INTERVAL_US, battery_status_s::SOURCE_EXTERNAL};
|
||||
Battery battery3 = {BATTERY_INDEX_3, this, SAMPLE_INTERVAL_US, battery_status_s::SOURCE_EXTERNAL};
|
||||
Battery battery4 = {BATTERY_INDEX_4, this, SAMPLE_INTERVAL_US, battery_status_s::SOURCE_EXTERNAL};
|
||||
|
||||
Battery *_battery[battery_status_s::MAX_INSTANCES] = { &battery1, &battery2, &battery3, &battery4 };
|
||||
};
|
||||
|
||||
@@ -100,10 +100,12 @@ public:
|
||||
}
|
||||
|
||||
// reading_type
|
||||
const float tolerance = 1e-6;
|
||||
|
||||
if (dist.current_distance > dist.max_distance) {
|
||||
range_sensor.reading_type = uavcan::equipment::range_sensor::Measurement::READING_TYPE_TOO_FAR;
|
||||
|
||||
} else if (dist.current_distance < dist.min_distance) {
|
||||
} else if (dist.current_distance < dist.min_distance - tolerance) {
|
||||
range_sensor.reading_type = uavcan::equipment::range_sensor::Measurement::READING_TYPE_TOO_CLOSE;
|
||||
|
||||
} else if (dist.signal_quality != 0) {
|
||||
|
||||
@@ -307,16 +307,16 @@ void Battery::estimateStateOfCharge()
|
||||
uint8_t Battery::determineWarning(float state_of_charge)
|
||||
{
|
||||
if (state_of_charge < _params.emergen_thr) {
|
||||
return battery_status_s::BATTERY_WARNING_EMERGENCY;
|
||||
return battery_status_s::WARNING_EMERGENCY;
|
||||
|
||||
} else if (state_of_charge < _params.crit_thr) {
|
||||
return battery_status_s::BATTERY_WARNING_CRITICAL;
|
||||
return battery_status_s::WARNING_CRITICAL;
|
||||
|
||||
} else if (state_of_charge < _params.low_thr) {
|
||||
return battery_status_s::BATTERY_WARNING_LOW;
|
||||
return battery_status_s::WARNING_LOW;
|
||||
|
||||
} else {
|
||||
return battery_status_s::BATTERY_WARNING_NONE;
|
||||
return battery_status_s::WARNING_NONE;
|
||||
}
|
||||
}
|
||||
|
||||
@@ -327,7 +327,7 @@ uint16_t Battery::determineFaults()
|
||||
if ((_params.n_cells > 0)
|
||||
&& (_voltage_v > (_params.n_cells * _params.v_charged * 1.05f))) {
|
||||
// Reported as a "spike" since "over-voltage" does not exist in MAV_BATTERY_FAULT
|
||||
faults |= (1 << battery_status_s::BATTERY_FAULT_SPIKES);
|
||||
faults |= (1 << battery_status_s::FAULT_SPIKES);
|
||||
}
|
||||
|
||||
return faults;
|
||||
|
||||
@@ -175,7 +175,7 @@ private:
|
||||
float _state_of_charge_volt_based{-1.f}; // [0,1]
|
||||
float _state_of_charge{-1.f}; // [0,1]
|
||||
float _scale{1.f};
|
||||
uint8_t _warning{battery_status_s::BATTERY_WARNING_NONE};
|
||||
uint8_t _warning{battery_status_s::WARNING_NONE};
|
||||
hrt_abstime _last_timestamp{0};
|
||||
bool _armed{false};
|
||||
bool _vehicle_status_is_fw{false};
|
||||
|
||||
@@ -1128,6 +1128,11 @@ int parameter_flashfs_init(sector_descriptor_t *fconfig, uint8_t *buffer, uint16
|
||||
if (pf == NULL) {
|
||||
// Parameters can't be found, assume sector is corrupt or empty
|
||||
rv = parameter_flashfs_erase();
|
||||
|
||||
// A positive return value means flash space has been erased successfully.
|
||||
if (rv > 0) {
|
||||
rv = 0;
|
||||
}
|
||||
}
|
||||
|
||||
return rv;
|
||||
|
||||
+14
-8
@@ -56,6 +56,7 @@
|
||||
#include <termios.h>
|
||||
#include <string.h>
|
||||
#include <unistd.h>
|
||||
#include <math.h>
|
||||
|
||||
// TODO: include RSSI dBm to percentage conversion for ghost receiver
|
||||
#include "spektrum_rssi.h"
|
||||
@@ -77,8 +78,8 @@ enum class ghst_parser_state_t : uint8_t {
|
||||
synced
|
||||
};
|
||||
|
||||
// only RSSI frame contains value of RSSI, if it is not received, send last received RSSI
|
||||
static int8_t ghst_rssi = -1;
|
||||
// only RSSI frame contains value of RSSI, if it is not received, send last received RSSI/LQ
|
||||
static ghstLinkStatistics_t last_link_stats = { .rssi_pct = -1, .rssi_dbm = NAN, .link_quality = 0 };
|
||||
|
||||
static ghst_frame_t &ghst_frame = rc_decode_buf.ghst_frame;
|
||||
static uint32_t current_frame_position = 0U;
|
||||
@@ -89,7 +90,8 @@ static uint16_t prev_rc_vals[GHST_MAX_NUM_CHANNELS];
|
||||
/**
|
||||
* parse the current ghst_frame buffer
|
||||
*/
|
||||
static bool ghst_parse_buffer(uint16_t *values, int8_t *rssi, uint16_t *num_values, uint16_t max_channels);
|
||||
static bool ghst_parse_buffer(uint16_t *values, ghstLinkStatistics_t *link_stats, uint16_t *num_values,
|
||||
uint16_t max_channels);
|
||||
|
||||
int ghst_config(int uart_fd)
|
||||
{
|
||||
@@ -114,7 +116,7 @@ static uint16_t convert_channel_value(unsigned chan_value);
|
||||
|
||||
|
||||
bool ghst_parse(const uint64_t now, const uint8_t *frame, unsigned len, uint16_t *values,
|
||||
int8_t *rssi, uint16_t *num_values, uint16_t max_channels)
|
||||
ghstLinkStatistics_t *link_stats, uint16_t *num_values, uint16_t max_channels)
|
||||
{
|
||||
bool success = false;
|
||||
uint8_t *ghst_frame_ptr = (uint8_t *)&ghst_frame;
|
||||
@@ -145,7 +147,7 @@ bool ghst_parse(const uint64_t now, const uint8_t *frame, unsigned len, uint16_t
|
||||
len -= current_len;
|
||||
frame += current_len;
|
||||
|
||||
if (ghst_parse_buffer(values, rssi, num_values, max_channels)) {
|
||||
if (ghst_parse_buffer(values, link_stats, num_values, max_channels)) {
|
||||
success = true;
|
||||
}
|
||||
}
|
||||
@@ -182,7 +184,8 @@ static uint16_t convert_channel_value(unsigned int chan_value)
|
||||
return converted_chan_value;
|
||||
}
|
||||
|
||||
static bool ghst_parse_buffer(uint16_t *values, int8_t *rssi, uint16_t *num_values, uint16_t max_channels)
|
||||
static bool ghst_parse_buffer(uint16_t *values, ghstLinkStatistics_t *link_stats, uint16_t *num_values,
|
||||
uint16_t max_channels)
|
||||
{
|
||||
uint8_t *ghst_frame_ptr = (uint8_t *)&ghst_frame;
|
||||
|
||||
@@ -299,13 +302,16 @@ static bool ghst_parse_buffer(uint16_t *values, int8_t *rssi, uint16_t *num_valu
|
||||
} else if (ghst_frame.type == static_cast<uint8_t>(ghstFrameType::frameTypeRssi)) {
|
||||
const ghstPayloadRssi_t *const rssiValues = (ghstPayloadRssi_t *)&ghst_frame.payload;
|
||||
// TODO: call function for RSSI dBm to percentage conversion for ghost receiver
|
||||
ghst_rssi = spek_dbm_to_percent(static_cast<int8_t>(rssiValues->rssidBm));
|
||||
last_link_stats.rssi_pct = spek_dbm_to_percent(static_cast<int8_t>
|
||||
(rssiValues->rssidBm)); // rssidBm sign inverted (90 = -90dBm)
|
||||
last_link_stats.rssi_dbm = -rssiValues->rssidBm;
|
||||
last_link_stats.link_quality = rssiValues->lq; // 0 - 100
|
||||
|
||||
} else {
|
||||
GHST_DEBUG("Frame type: %u", ghst_frame.type);
|
||||
}
|
||||
|
||||
*rssi = ghst_rssi;
|
||||
*link_stats = last_link_stats;
|
||||
|
||||
memcpy(prev_rc_vals, values, sizeof(uint16_t) * GHST_MAX_NUM_CHANNELS);
|
||||
|
||||
|
||||
+8
-1
@@ -106,6 +106,13 @@ typedef struct {
|
||||
int txPowerdBm: 8; // Tx power [dBm]
|
||||
} __attribute__((__packed__)) ghstPayloadRssi_t;
|
||||
|
||||
// Link statistics for internal transport
|
||||
typedef struct {
|
||||
int8_t rssi_pct;
|
||||
float rssi_dbm;
|
||||
int8_t link_quality;
|
||||
} ghstLinkStatistics_t;
|
||||
|
||||
/**
|
||||
* Configure an UART port to be used for GHST
|
||||
* @param uart_fd UART file descriptor
|
||||
@@ -127,7 +134,7 @@ __EXPORT int ghst_config(int uart_fd);
|
||||
* @return true if channels successfully decoded
|
||||
*/
|
||||
__EXPORT bool ghst_parse(const uint64_t now, const uint8_t *frame, unsigned len, uint16_t *values,
|
||||
int8_t *rssi, uint16_t *num_values, uint16_t max_channels);
|
||||
ghstLinkStatistics_t *link_stats, uint16_t *num_values, uint16_t max_channels);
|
||||
|
||||
|
||||
/**
|
||||
|
||||
@@ -159,7 +159,7 @@ bool RCTest::ghstTest()
|
||||
uint16_t rc_values[max_channels];
|
||||
uint16_t num_values = 0;
|
||||
int line_counter = 1;
|
||||
int8_t ghst_rssi = -1;
|
||||
ghstLinkStatistics_t link_stats;
|
||||
ghst_config(uart_fd);
|
||||
|
||||
while (fgets(line, line_size, fp) != nullptr) {
|
||||
@@ -186,7 +186,7 @@ bool RCTest::ghstTest()
|
||||
// Pipe the data into the parser
|
||||
hrt_abstime now = hrt_absolute_time();
|
||||
|
||||
bool result = ghst_parse(now, frame, frame_len, rc_values, &ghst_rssi, &num_values, max_channels);
|
||||
bool result = ghst_parse(now, frame, frame_len, rc_values, &link_stats, &num_values, max_channels);
|
||||
|
||||
if (result) {
|
||||
has_decoded_values = true;
|
||||
|
||||
@@ -1,207 +0,0 @@
|
||||
module_name: Rover Control
|
||||
|
||||
parameters:
|
||||
- group: Rover Control
|
||||
definitions:
|
||||
RO_MAX_THR_SPEED:
|
||||
description:
|
||||
short: Speed the rover drives at maximum throttle
|
||||
long: Used to linearly map speeds [m/s] to throttle values [-1. 1].
|
||||
type: float
|
||||
unit: m/s
|
||||
min: 0
|
||||
max: 100
|
||||
increment: 0.01
|
||||
decimal: 2
|
||||
default: 0
|
||||
|
||||
RO_ACCEL_LIM:
|
||||
description:
|
||||
short: Acceleration limit
|
||||
long: |
|
||||
Set to -1 to disable.
|
||||
For mecanum rovers this limit is used for longitudinal and lateral acceleration.
|
||||
type: float
|
||||
unit: m/s^2
|
||||
min: -1
|
||||
max: 100
|
||||
increment: 0.01
|
||||
decimal: 2
|
||||
default: -1
|
||||
|
||||
RO_DECEL_LIM:
|
||||
description:
|
||||
short: Deceleration limit
|
||||
long: |
|
||||
Set to -1 to disable.
|
||||
Note that if it is disabled the rover will not slow down when approaching waypoints in auto modes.
|
||||
For mecanum rovers this limit is used for longitudinal and lateral deceleration.
|
||||
type: float
|
||||
unit: m/s^2
|
||||
min: -1
|
||||
max: 100
|
||||
increment: 0.01
|
||||
decimal: 2
|
||||
default: -1
|
||||
|
||||
RO_JERK_LIM:
|
||||
description:
|
||||
short: Jerk limit
|
||||
long: |
|
||||
Set to -1 to disable.
|
||||
Note that if it is disabled the rover will not slow down when approaching waypoints in auto modes.
|
||||
For mecanum rovers this limit is used for longitudinal and lateral jerk.
|
||||
type: float
|
||||
unit: m/s^3
|
||||
min: -1
|
||||
max: 100
|
||||
increment: 0.01
|
||||
decimal: 2
|
||||
default: -1
|
||||
|
||||
RO_YAW_RATE_TH:
|
||||
description:
|
||||
short: Yaw rate measurement threshold
|
||||
long: The minimum threshold for the yaw rate measurement not to be interpreted as zero.
|
||||
type: float
|
||||
unit: deg/s
|
||||
min: 0
|
||||
max: 100
|
||||
increment: 0.01
|
||||
decimal: 2
|
||||
default: 3
|
||||
|
||||
RO_SPEED_TH:
|
||||
description:
|
||||
short: Speed measurement threshold
|
||||
long: The minimum threshold for the speed measurement not to be interpreted as zero.
|
||||
type: float
|
||||
unit: m/s
|
||||
min: 0
|
||||
max: 100
|
||||
increment: 0.01
|
||||
decimal: 2
|
||||
default: 0.1
|
||||
|
||||
RO_YAW_STICK_DZ:
|
||||
description:
|
||||
short: Yaw stick deadzone
|
||||
long: Percentage of stick input range that will be interpreted as zero around the stick centered value.
|
||||
type: float
|
||||
min: 0
|
||||
max: 1
|
||||
increment: 0.01
|
||||
decimal: 2
|
||||
default: 0.1
|
||||
|
||||
- group: Rover Rate Control
|
||||
definitions:
|
||||
RO_YAW_RATE_P:
|
||||
description:
|
||||
short: Proportional gain for closed loop yaw rate controller
|
||||
type: float
|
||||
min: 0
|
||||
max: 100
|
||||
increment: 0.01
|
||||
decimal: 3
|
||||
default: 0
|
||||
|
||||
RO_YAW_RATE_I:
|
||||
description:
|
||||
short: Integral gain for closed loop yaw rate controller
|
||||
type: float
|
||||
min: 0
|
||||
max: 100
|
||||
increment: 0.01
|
||||
decimal: 3
|
||||
default: 0
|
||||
|
||||
RO_YAW_RATE_LIM:
|
||||
description:
|
||||
short: Yaw rate limit
|
||||
long: |
|
||||
Used to cap yaw rate setpoints and map controller inputs to yaw rate setpoints
|
||||
in Acro, Stabilized and Position mode.
|
||||
type: float
|
||||
unit: deg/s
|
||||
min: 0
|
||||
max: 10000
|
||||
increment: 0.01
|
||||
decimal: 2
|
||||
default: 0
|
||||
|
||||
RO_YAW_ACCEL_LIM:
|
||||
description:
|
||||
short: Yaw acceleration limit
|
||||
long: |
|
||||
Used to cap how quickly the magnitude of yaw rate setpoints can increase.
|
||||
Set to -1 to disable.
|
||||
type: float
|
||||
unit: deg/s^2
|
||||
min: -1
|
||||
max: 10000
|
||||
increment: 0.01
|
||||
decimal: 2
|
||||
default: -1
|
||||
|
||||
RO_YAW_DECEL_LIM:
|
||||
description:
|
||||
short: Yaw deceleration limit
|
||||
long: |
|
||||
Used to cap how quickly the magnitude of yaw rate setpoints can decrease.
|
||||
Set to -1 to disable.
|
||||
type: float
|
||||
unit: deg/s^2
|
||||
min: -1
|
||||
max: 10000
|
||||
increment: 0.01
|
||||
decimal: 2
|
||||
default: -1
|
||||
|
||||
- group: Rover Attitude Control
|
||||
definitions:
|
||||
RO_YAW_P:
|
||||
description:
|
||||
short: Proportional gain for closed loop yaw controller
|
||||
type: float
|
||||
min: 0
|
||||
max: 100
|
||||
increment: 0.01
|
||||
decimal: 3
|
||||
default: 0
|
||||
|
||||
- group: Rover Velocity Control
|
||||
definitions:
|
||||
RO_SPEED_P:
|
||||
description:
|
||||
short: Proportional gain for ground speed controller
|
||||
type: float
|
||||
min: 0
|
||||
max: 100
|
||||
increment: 0.01
|
||||
decimal: 2
|
||||
default: 0
|
||||
|
||||
RO_SPEED_I:
|
||||
description:
|
||||
short: Integral gain for ground speed controller
|
||||
type: float
|
||||
min: 0
|
||||
max: 100
|
||||
increment: 0.001
|
||||
decimal: 3
|
||||
default: 0
|
||||
|
||||
RO_SPEED_LIM:
|
||||
description:
|
||||
short: Speed limit
|
||||
long: |
|
||||
Used to cap speed setpoints and map controller inputs to speed setpoints
|
||||
in Position mode.
|
||||
type: float
|
||||
unit: m/s
|
||||
min: -1
|
||||
max: 100
|
||||
increment: 0.01
|
||||
decimal: 2
|
||||
default: -1
|
||||
@@ -0,0 +1,255 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* 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
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file rovercontrol_params.c
|
||||
*
|
||||
* Parameters defined by the rover control lib.
|
||||
*/
|
||||
|
||||
/**
|
||||
* Yaw stick deadzone
|
||||
*
|
||||
* Percentage of stick input range that will be interpreted as zero around the stick centered value.
|
||||
*
|
||||
* @min 0
|
||||
* @max 1
|
||||
* @increment 0.01
|
||||
* @decimal 2
|
||||
* @group Rover Rate Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(RO_YAW_STICK_DZ, 0.1f);
|
||||
|
||||
/**
|
||||
* Yaw rate measurement threshold
|
||||
*
|
||||
* The minimum threshold for the yaw rate measurement not to be interpreted as zero.
|
||||
*
|
||||
* @unit deg/s
|
||||
* @min 0
|
||||
* @max 100
|
||||
* @increment 0.01
|
||||
* @decimal 2
|
||||
* @group Rover Rate Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(RO_YAW_RATE_TH, 3.f);
|
||||
|
||||
/**
|
||||
* Proportional gain for closed loop yaw rate controller
|
||||
*
|
||||
* @min 0
|
||||
* @max 100
|
||||
* @increment 0.01
|
||||
* @decimal 3
|
||||
* @group Rover Rate Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(RO_YAW_RATE_P, 0.f);
|
||||
|
||||
/**
|
||||
* Integral gain for closed loop yaw rate controller
|
||||
*
|
||||
* @min 0
|
||||
* @max 100
|
||||
* @increment 0.01
|
||||
* @decimal 3
|
||||
* @group Rover Rate Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(RO_YAW_RATE_I, 0.f);
|
||||
|
||||
/**
|
||||
* Yaw rate limit
|
||||
*
|
||||
* Used to cap yaw rate setpoints and map controller inputs to yaw rate setpoints
|
||||
* in Acro, Stabilized and Position mode.
|
||||
*
|
||||
* @unit deg/s
|
||||
* @min 0
|
||||
* @max 10000
|
||||
* @increment 0.01
|
||||
* @decimal 2
|
||||
* @group Rover Rate Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(RO_YAW_RATE_LIM, 0.f);
|
||||
|
||||
/**
|
||||
* Yaw acceleration limit
|
||||
*
|
||||
* Used to cap how quickly the magnitude of yaw rate setpoints can increase.
|
||||
* Set to -1 to disable.
|
||||
*
|
||||
* @unit deg/s^2
|
||||
* @min -1
|
||||
* @max 10000
|
||||
* @increment 0.01
|
||||
* @decimal 2
|
||||
* @group Rover Rate Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(RO_YAW_ACCEL_LIM, -1.f);
|
||||
|
||||
/**
|
||||
* Yaw deceleration limit
|
||||
*
|
||||
* Used to cap how quickly the magnitude of yaw rate setpoints can decrease.
|
||||
* Set to -1 to disable.
|
||||
*
|
||||
* @unit deg/s^2
|
||||
* @min -1
|
||||
* @max 10000
|
||||
* @increment 0.01
|
||||
* @decimal 2
|
||||
* @group Rover Rate Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(RO_YAW_DECEL_LIM, -1.f);
|
||||
|
||||
/**
|
||||
* Proportional gain for closed loop yaw controller
|
||||
*
|
||||
* @min 0
|
||||
* @max 100
|
||||
* @increment 0.01
|
||||
* @decimal 3
|
||||
* @group Rover Attitude Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(RO_YAW_P, 0.f);
|
||||
|
||||
/**
|
||||
* Speed the rover drives at maximum throttle
|
||||
*
|
||||
* Used to linearly map speeds [m/s] to throttle values [-1. 1].
|
||||
*
|
||||
* @min 0
|
||||
* @max 100
|
||||
* @unit m/s
|
||||
* @increment 0.01
|
||||
* @decimal 2
|
||||
* @group Rover Velocity Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(RO_MAX_THR_SPEED, 0.f);
|
||||
|
||||
/**
|
||||
* Proportional gain for ground speed controller
|
||||
*
|
||||
* @min 0
|
||||
* @max 100
|
||||
* @increment 0.01
|
||||
* @decimal 2
|
||||
* @group Rover Velocity Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(RO_SPEED_P, 0.f);
|
||||
|
||||
/**
|
||||
* Integral gain for ground speed controller
|
||||
*
|
||||
* @min 0
|
||||
* @max 100
|
||||
* @increment 0.001
|
||||
* @decimal 3
|
||||
* @group Rover Velocity Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(RO_SPEED_I, 0.f);
|
||||
|
||||
/**
|
||||
* Speed limit
|
||||
*
|
||||
* Used to cap speed setpoints and map controller inputs to speed setpoints in Position mode.
|
||||
*
|
||||
* @unit m/s
|
||||
* @min -1
|
||||
* @max 100
|
||||
* @increment 0.01
|
||||
* @decimal 2
|
||||
* @group Rover Velocity Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(RO_SPEED_LIM, -1.f);
|
||||
|
||||
/**
|
||||
* Acceleration limit
|
||||
*
|
||||
* Set to -1 to disable.
|
||||
* For mecanum rovers this limit is used for longitudinal and lateral acceleration.
|
||||
*
|
||||
* @unit m/s^2
|
||||
* @min -1
|
||||
* @max 100
|
||||
* @increment 0.01
|
||||
* @decimal 2
|
||||
* @group Rover Velocity Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(RO_ACCEL_LIM, -1.f);
|
||||
|
||||
/**
|
||||
* Deceleration limit
|
||||
*
|
||||
* Set to -1 to disable.
|
||||
* Note that if it is disabled the rover will not slow down when approaching waypoints in auto modes.
|
||||
* For mecanum rovers this limit is used for longitudinal and lateral deceleration.
|
||||
*
|
||||
* @unit m/s^2
|
||||
* @min -1
|
||||
* @max 100
|
||||
* @increment 0.01
|
||||
* @decimal 2
|
||||
* @group Rover Velocity Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(RO_DECEL_LIM, -1.f);
|
||||
|
||||
/**
|
||||
* Jerk limit
|
||||
*
|
||||
* Set to -1 to disable.
|
||||
* Note that if it is disabled the rover will not slow down when approaching waypoints in auto modes.
|
||||
* For mecanum rovers this limit is used for longitudinal and lateral jerk.
|
||||
*
|
||||
* @unit m/s^3
|
||||
* @min -1
|
||||
* @max 100
|
||||
* @increment 0.01
|
||||
* @decimal 2
|
||||
* @group Rover Velocity Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(RO_JERK_LIM, -1.f);
|
||||
|
||||
/**
|
||||
* Speed measurement threshold
|
||||
*
|
||||
* Set to -1 to disable.
|
||||
* The minimum threshold for the speed measurement not to be interpreted as zero.
|
||||
*
|
||||
* @unit m/s
|
||||
* @min 0
|
||||
* @max 100
|
||||
* @increment 0.01
|
||||
* @decimal 2
|
||||
* @group Rover Velocity Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(RO_SPEED_TH, 0.1f);
|
||||
@@ -116,7 +116,7 @@ private:
|
||||
float _time_estimate{0.f}; /**< Accumulated time estimate [s] */
|
||||
bool _is_valid{false}; /**< Checks if time estimate is valid */
|
||||
|
||||
uint8_t _vehicle_type{vehicle_status_s::VEHICLE_TYPE_UNKNOWN}; /**< the defined vehicle type to use for the calculation*/
|
||||
uint8_t _vehicle_type{vehicle_status_s::VEHICLE_TYPE_ROTARY_WING}; /**< the defined vehicle type to use for the calculation*/
|
||||
|
||||
DEFINE_PARAMETERS(
|
||||
(ParamFloat<px4::params::RTL_TIME_FACTOR>) _param_rtl_time_factor, /**< Safety factory for safe time estimate */
|
||||
|
||||
@@ -240,6 +240,18 @@ PARAM_DEFINE_INT32(SYS_HAS_NUM_ASPD, 0);
|
||||
*/
|
||||
PARAM_DEFINE_INT32(SYS_HAS_NUM_DIST, 0);
|
||||
|
||||
/**
|
||||
* Number of optical flow sensors required to be available
|
||||
*
|
||||
* The preflight check will fail if fewer than this number of optical flow sensors with valid data are present.
|
||||
*
|
||||
* @group System
|
||||
* @min 0
|
||||
* @max 1
|
||||
*/
|
||||
|
||||
PARAM_DEFINE_INT32(SYS_HAS_NUM_OF, 0);
|
||||
|
||||
/**
|
||||
* Enable factory calibration mode
|
||||
*
|
||||
|
||||
@@ -137,9 +137,9 @@ private:
|
||||
BatteryStatus::BatteryStatus() :
|
||||
ModuleParams(nullptr),
|
||||
ScheduledWorkItem(MODULE_NAME, px4::wq_configurations::hp_default),
|
||||
_battery1(1, this, SAMPLE_INTERVAL_US, battery_status_s::BATTERY_SOURCE_POWER_MODULE, 0),
|
||||
_battery1(1, this, SAMPLE_INTERVAL_US, battery_status_s::SOURCE_POWER_MODULE, 0),
|
||||
#if BOARD_NUMBER_BRICKS > 1
|
||||
_battery2(2, this, SAMPLE_INTERVAL_US, battery_status_s::BATTERY_SOURCE_POWER_MODULE, 1),
|
||||
_battery2(2, this, SAMPLE_INTERVAL_US, battery_status_s::SOURCE_POWER_MODULE, 1),
|
||||
#endif
|
||||
_loop_perf(perf_alloc(PC_ELAPSED, MODULE_NAME))
|
||||
{
|
||||
|
||||
@@ -574,7 +574,7 @@ transition_result_t Commander::arm(arm_disarm_reason_t calling_reason, bool run_
|
||||
|
||||
if (!_vehicle_control_mode.flag_control_climb_rate_enabled &&
|
||||
!_failsafe_flags.manual_control_signal_lost && !_is_throttle_low
|
||||
&& _vehicle_status.vehicle_type != vehicle_status_s::VEHICLE_TYPE_ROVER) {
|
||||
&& !is_ground_vehicle(_vehicle_status)) {
|
||||
|
||||
mavlink_log_critical(&_mavlink_log_pub, "Arming denied: high throttle\t");
|
||||
events::send(events::ID("commander_arm_denied_throttle_high"), {events::Log::Critical, events::LogInternal::Info},
|
||||
@@ -583,6 +583,16 @@ transition_result_t Commander::arm(arm_disarm_reason_t calling_reason, bool run_
|
||||
return TRANSITION_DENIED;
|
||||
}
|
||||
|
||||
if ((is_ground_vehicle(_vehicle_status))
|
||||
&& !_failsafe_flags.manual_control_signal_lost && !_is_throttle_near_center) {
|
||||
|
||||
mavlink_log_critical(&_mavlink_log_pub, "Arming denied: throttle not centered\t");
|
||||
events::send(events::ID("commander_arm_denied_throttle_not_centered"), {events::Log::Critical, events::LogInternal::Info},
|
||||
"Arming denied: throttle not centered");
|
||||
tune_negative(true);
|
||||
return TRANSITION_DENIED;
|
||||
}
|
||||
|
||||
} else if (calling_reason == arm_disarm_reason_t::stick_gesture
|
||||
|| calling_reason == arm_disarm_reason_t::rc_switch
|
||||
|| calling_reason == arm_disarm_reason_t::rc_button) {
|
||||
@@ -688,7 +698,7 @@ Commander::Commander() :
|
||||
_vehicle_status.system_id = 1;
|
||||
_vehicle_status.component_id = 1;
|
||||
_vehicle_status.system_type = 0;
|
||||
_vehicle_status.vehicle_type = vehicle_status_s::VEHICLE_TYPE_UNKNOWN;
|
||||
_vehicle_status.vehicle_type = vehicle_status_s::VEHICLE_TYPE_ROTARY_WING;
|
||||
_vehicle_status.nav_state = _user_mode_intention.get();
|
||||
_vehicle_status.nav_state_user_intention = _user_mode_intention.get();
|
||||
_vehicle_status.nav_state_timestamp = hrt_absolute_time();
|
||||
@@ -1696,7 +1706,7 @@ void Commander::executeActionRequest(const action_request_s &action_request)
|
||||
|
||||
case action_request_s::ACTION_SWITCH_MODE:
|
||||
|
||||
if (!_user_mode_intention.change(action_request.mode, ModeChangeSource::User, true)) {
|
||||
if (!_user_mode_intention.change(action_request.mode, ModeChangeSource::User, false)) {
|
||||
printRejectMode(action_request.mode);
|
||||
}
|
||||
|
||||
@@ -1723,7 +1733,6 @@ void Commander::updateParameters()
|
||||
&& _vtol_vehicle_status.vehicle_vtol_state != vtol_vehicle_status_s::VEHICLE_VTOL_STATE_FW);
|
||||
const bool is_fixed = is_fixed_wing(_vehicle_status) || (is_vtol(_vehicle_status)
|
||||
&& _vtol_vehicle_status.vehicle_vtol_state == vtol_vehicle_status_s::VEHICLE_VTOL_STATE_FW);
|
||||
const bool is_ground = is_ground_vehicle(_vehicle_status);
|
||||
|
||||
/* disable manual override for all systems that rely on electronic stabilization */
|
||||
if (is_rotary) {
|
||||
@@ -1732,8 +1741,11 @@ void Commander::updateParameters()
|
||||
} else if (is_fixed) {
|
||||
_vehicle_status.vehicle_type = vehicle_status_s::VEHICLE_TYPE_FIXED_WING;
|
||||
|
||||
} else if (is_ground) {
|
||||
} else if (is_rover_type(_vehicle_status)) {
|
||||
_vehicle_status.vehicle_type = vehicle_status_s::VEHICLE_TYPE_ROVER;
|
||||
|
||||
} else if (is_boat_type(_vehicle_status)) {
|
||||
_vehicle_status.vehicle_type = vehicle_status_s::VEHICLE_TYPE_BOAT;
|
||||
}
|
||||
|
||||
_vehicle_status.is_vtol = is_vtol(_vehicle_status);
|
||||
@@ -1889,8 +1901,7 @@ void Commander::run()
|
||||
_actuator_armed.armed = isArmed();
|
||||
_actuator_armed.prearmed = getPrearmState();
|
||||
_actuator_armed.ready_to_arm = _vehicle_status.pre_flight_checks_pass || isArmed();
|
||||
_actuator_armed.lockdown = ((_vehicle_status.nav_state == _vehicle_status.NAVIGATION_STATE_TERMINATION)
|
||||
|| (_vehicle_status.hil_state == vehicle_status_s::HIL_STATE_ON)
|
||||
_actuator_armed.lockdown = ((_vehicle_status.hil_state == vehicle_status_s::HIL_STATE_ON)
|
||||
|| _multicopter_throw_launch.isThrowLaunchInProgress());
|
||||
// _actuator_armed.manual_lockdown // action_request_s::ACTION_KILL
|
||||
_actuator_armed.force_failsafe = (_vehicle_status.nav_state == _vehicle_status.NAVIGATION_STATE_TERMINATION);
|
||||
@@ -2193,13 +2204,13 @@ void Commander::updateTunes()
|
||||
|
||||
} else if (!_vehicle_status.usb_connected &&
|
||||
(_vehicle_status.hil_state != vehicle_status_s::HIL_STATE_ON) &&
|
||||
(_battery_warning == battery_status_s::BATTERY_WARNING_CRITICAL)) {
|
||||
(_battery_warning == battery_status_s::WARNING_CRITICAL)) {
|
||||
|
||||
/* play tune on battery critical */
|
||||
set_tune(tune_control_s::TUNE_ID_BATTERY_WARNING_FAST);
|
||||
|
||||
} else if ((_vehicle_status.hil_state != vehicle_status_s::HIL_STATE_ON) &&
|
||||
(_battery_warning == battery_status_s::BATTERY_WARNING_LOW)) {
|
||||
(_battery_warning == battery_status_s::WARNING_LOW)) {
|
||||
/* play tune on battery warning */
|
||||
set_tune(tune_control_s::TUNE_ID_BATTERY_WARNING_SLOW);
|
||||
|
||||
@@ -2493,10 +2504,10 @@ void Commander::control_status_leds(bool changed, const uint8_t battery_warning)
|
||||
if (_vehicle_status.failsafe) {
|
||||
led_color = led_control_s::COLOR_PURPLE;
|
||||
|
||||
} else if (battery_warning == battery_status_s::BATTERY_WARNING_LOW) {
|
||||
} else if (battery_warning == battery_status_s::WARNING_LOW) {
|
||||
led_color = led_control_s::COLOR_AMBER;
|
||||
|
||||
} else if (battery_warning == battery_status_s::BATTERY_WARNING_CRITICAL) {
|
||||
} else if (battery_warning == battery_status_s::WARNING_CRITICAL) {
|
||||
led_color = led_control_s::COLOR_RED;
|
||||
|
||||
} else {
|
||||
@@ -2867,7 +2878,7 @@ void Commander::battery_status_check()
|
||||
// Handle shutdown request from emergency battery action
|
||||
if (_battery_warning != _failsafe_flags.battery_warning) {
|
||||
|
||||
if (_failsafe_flags.battery_warning == battery_status_s::BATTERY_WARNING_EMERGENCY) {
|
||||
if (_failsafe_flags.battery_warning == battery_status_s::WARNING_EMERGENCY) {
|
||||
#if defined(BOARD_HAS_POWER_CONTROL)
|
||||
|
||||
if (!isArmed() && (px4_shutdown_request(60_s) == 0)) {
|
||||
@@ -2902,13 +2913,15 @@ void Commander::manualControlCheck()
|
||||
|
||||
_is_throttle_above_center = (manual_control_setpoint.throttle > 0.2f);
|
||||
_is_throttle_low = (manual_control_setpoint.throttle < -0.8f);
|
||||
_is_throttle_near_center = (fabsf(manual_control_setpoint.throttle) < 0.05f);
|
||||
|
||||
if (isArmed()) {
|
||||
// Abort autonomous mode and switch to position mode if sticks are moved significantly
|
||||
// but only if actually in air.
|
||||
if (manual_control_setpoint.sticks_moving
|
||||
&& !_vehicle_control_mode.flag_control_manual_enabled
|
||||
&& (_vehicle_status.vehicle_type == vehicle_status_s::VEHICLE_TYPE_ROTARY_WING)
|
||||
&& (_vehicle_status.vehicle_type == vehicle_status_s::VEHICLE_TYPE_ROTARY_WING
|
||||
|| _vehicle_status.vehicle_type == vehicle_status_s::VEHICLE_TYPE_BOAT)
|
||||
) {
|
||||
bool override_enabled = false;
|
||||
|
||||
|
||||
@@ -262,7 +262,7 @@ private:
|
||||
|
||||
hrt_abstime _last_health_and_arming_check{0};
|
||||
|
||||
uint8_t _battery_warning{battery_status_s::BATTERY_WARNING_NONE};
|
||||
uint8_t _battery_warning{battery_status_s::WARNING_NONE};
|
||||
|
||||
bool _failsafe_user_override_request{false}; ///< override request due to stick movements
|
||||
|
||||
@@ -275,6 +275,7 @@ private:
|
||||
|
||||
bool _is_throttle_above_center{false};
|
||||
bool _is_throttle_low{false};
|
||||
bool _is_throttle_near_center{false};
|
||||
|
||||
bool _arm_tune_played{false};
|
||||
bool _have_taken_off_since_arming{false};
|
||||
|
||||
@@ -42,6 +42,7 @@ px4_add_library(health_and_arming_checks
|
||||
checks/batteryCheck.cpp
|
||||
checks/cpuResourceCheck.cpp
|
||||
checks/distanceSensorChecks.cpp
|
||||
checks/opticalFlowCheck.cpp
|
||||
checks/escCheck.cpp
|
||||
checks/estimatorCheck.cpp
|
||||
checks/failureDetectorCheck.cpp
|
||||
|
||||
@@ -46,6 +46,7 @@
|
||||
#include "checks/baroCheck.hpp"
|
||||
#include "checks/cpuResourceCheck.hpp"
|
||||
#include "checks/distanceSensorChecks.hpp"
|
||||
#include "checks/opticalFlowCheck.hpp"
|
||||
#include "checks/escCheck.hpp"
|
||||
#include "checks/estimatorCheck.hpp"
|
||||
#include "checks/failureDetectorCheck.hpp"
|
||||
@@ -130,6 +131,7 @@ private:
|
||||
BaroChecks _baro_checks;
|
||||
CpuResourceChecks _cpu_resource_checks;
|
||||
DistanceSensorChecks _distance_sensor_checks;
|
||||
OpticalFlowCheck _optical_flow_check;
|
||||
EscChecks _esc_checks;
|
||||
EstimatorChecks _estimator_checks;
|
||||
FailureDetectorChecks _failure_detector_checks;
|
||||
@@ -169,6 +171,7 @@ private:
|
||||
&_baro_checks,
|
||||
&_cpu_resource_checks,
|
||||
&_distance_sensor_checks,
|
||||
&_optical_flow_check,
|
||||
&_esc_checks,
|
||||
&_estimator_checks,
|
||||
&_failure_detector_checks,
|
||||
|
||||
@@ -39,7 +39,7 @@
|
||||
using namespace time_literals;
|
||||
|
||||
using battery_fault_reason_t = events::px4::enums::battery_fault_reason_t;
|
||||
static_assert(battery_status_s::BATTERY_FAULT_COUNT == (static_cast<uint8_t>(battery_fault_reason_t::_max) + 1)
|
||||
static_assert(battery_status_s::FAULT_COUNT == (static_cast<uint8_t>(battery_fault_reason_t::_max) + 1)
|
||||
, "Battery fault flags mismatch!");
|
||||
|
||||
static constexpr const char *battery_fault_reason_str(battery_fault_reason_t battery_fault_reason)
|
||||
@@ -78,7 +78,7 @@ void BatteryChecks::checkAndReport(const Context &context, Report &reporter)
|
||||
// Reset related failsafe flags otherwise failures from before disabling the check cause failsafes without reported reason
|
||||
reporter.failsafeFlags().battery_unhealthy = false;
|
||||
reporter.failsafeFlags().battery_low_remaining_time = false;
|
||||
reporter.failsafeFlags().battery_warning = battery_status_s::BATTERY_WARNING_NONE;
|
||||
reporter.failsafeFlags().battery_warning = battery_status_s::WARNING_NONE;
|
||||
return;
|
||||
}
|
||||
|
||||
@@ -86,7 +86,7 @@ void BatteryChecks::checkAndReport(const Context &context, Report &reporter)
|
||||
// There are possibly multiple batteries, and we can't know which ones serve which purpose. So the safest
|
||||
// option is to check if ANY of them have a warning, and specifically find which one has the most
|
||||
// urgent warning.
|
||||
uint8_t worst_warning = battery_status_s::BATTERY_WARNING_NONE;
|
||||
uint8_t worst_warning = battery_status_s::WARNING_NONE;
|
||||
float worst_battery_remaining = 1.f;
|
||||
// To make sure that all connected batteries are being regularly reported, we check which one has the
|
||||
// oldest timestamp.
|
||||
@@ -132,7 +132,7 @@ void BatteryChecks::checkAndReport(const Context &context, Report &reporter)
|
||||
}
|
||||
|
||||
// trigger a battery failsafe action if a battery disconnects in flight
|
||||
worst_warning = battery_status_s::BATTERY_WARNING_CRITICAL;
|
||||
worst_warning = battery_status_s::WARNING_CRITICAL;
|
||||
}
|
||||
|
||||
if (battery.connected) {
|
||||
@@ -195,13 +195,13 @@ void BatteryChecks::checkAndReport(const Context &context, Report &reporter)
|
||||
reporter.failsafeFlags().battery_warning = worst_warning;
|
||||
}
|
||||
|
||||
const bool battery_warning = reporter.failsafeFlags().battery_warning > battery_status_s::BATTERY_WARNING_NONE
|
||||
&& reporter.failsafeFlags().battery_warning < battery_status_s::BATTERY_WARNING_FAILED;
|
||||
const bool battery_warning = reporter.failsafeFlags().battery_warning > battery_status_s::WARNING_NONE
|
||||
&& reporter.failsafeFlags().battery_warning < battery_status_s::WARNING_FAILED;
|
||||
const bool configured_arm_threshold_in_use = !context.isArmed() && (_param_com_arm_bat_min.get() >= -FLT_EPSILON);
|
||||
const bool below_configured_arm_threshold = (worst_battery_remaining < _param_com_arm_bat_min.get());
|
||||
|
||||
if (battery_warning || (configured_arm_threshold_in_use && below_configured_arm_threshold)) {
|
||||
const bool critical_or_higher = reporter.failsafeFlags().battery_warning >= battery_status_s::BATTERY_WARNING_CRITICAL;
|
||||
const bool critical_or_higher = reporter.failsafeFlags().battery_warning >= battery_status_s::WARNING_CRITICAL;
|
||||
NavModes affected_modes = (!configured_arm_threshold_in_use && critical_or_higher)
|
||||
|| (configured_arm_threshold_in_use && below_configured_arm_threshold) ? NavModes::All : NavModes::None;
|
||||
events::LogLevel log_level = critical_or_higher || below_configured_arm_threshold
|
||||
@@ -209,7 +209,7 @@ void BatteryChecks::checkAndReport(const Context &context, Report &reporter)
|
||||
|
||||
switch (reporter.failsafeFlags().battery_warning) {
|
||||
default:
|
||||
case battery_status_s::BATTERY_WARNING_LOW:
|
||||
case battery_status_s::WARNING_LOW:
|
||||
/* EVENT
|
||||
* @description
|
||||
* The lowest battery state of charge is below the low threshold.
|
||||
@@ -227,7 +227,7 @@ void BatteryChecks::checkAndReport(const Context &context, Report &reporter)
|
||||
|
||||
break;
|
||||
|
||||
case battery_status_s::BATTERY_WARNING_CRITICAL:
|
||||
case battery_status_s::WARNING_CRITICAL:
|
||||
/* EVENT
|
||||
* @description
|
||||
* The lowest battery state of charge is below the critical threshold.
|
||||
@@ -245,7 +245,7 @@ void BatteryChecks::checkAndReport(const Context &context, Report &reporter)
|
||||
|
||||
break;
|
||||
|
||||
case battery_status_s::BATTERY_WARNING_EMERGENCY:
|
||||
case battery_status_s::WARNING_EMERGENCY:
|
||||
/* EVENT
|
||||
* @description
|
||||
* The lowest battery state of charge is below the emergency threshold.
|
||||
@@ -275,7 +275,7 @@ void BatteryChecks::checkAndReport(const Context &context, Report &reporter)
|
||||
|| is_required_battery_missing
|
||||
// No currently-connected batteries have any fault
|
||||
|| battery_has_fault
|
||||
|| reporter.failsafeFlags().battery_warning == battery_status_s::BATTERY_WARNING_FAILED;
|
||||
|| reporter.failsafeFlags().battery_warning == battery_status_s::WARNING_FAILED;
|
||||
|
||||
if (reporter.failsafeFlags().battery_unhealthy
|
||||
&& !is_required_battery_missing && !battery_has_fault) { // missing batteries and faults are reported above already
|
||||
|
||||
@@ -0,0 +1,68 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* 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
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#include "opticalFlowCheck.hpp"
|
||||
|
||||
void OpticalFlowCheck::checkAndReport(const Context &context, Report &reporter)
|
||||
{
|
||||
if (!_param_sys_has_num_of.get()) {
|
||||
return;
|
||||
}
|
||||
|
||||
const bool exists = _vehicle_optical_flow_sub.advertised();
|
||||
|
||||
if (exists) {
|
||||
vehicle_optical_flow_s flow_sens;
|
||||
const bool valid = _vehicle_optical_flow_sub.copy(&flow_sens) && (hrt_elapsed_time(&flow_sens.timestamp) < 1_s);
|
||||
reporter.setIsPresent(health_component_t::optical_flow);
|
||||
|
||||
if (!valid) {
|
||||
/* EVENT
|
||||
*/
|
||||
reporter.healthFailure(NavModes::All, health_component_t::optical_flow,
|
||||
events::ID("check_optical_flow_sensor_invalid"),
|
||||
events::Log::Error, "No valid data from optical flow sensor");
|
||||
}
|
||||
|
||||
} else {
|
||||
/* EVENT
|
||||
* @description
|
||||
* <profile name="dev">
|
||||
* This check can be configured via <param>SYS_HAS_NUM_OF</param> parameter.
|
||||
* </profile>
|
||||
*/
|
||||
reporter.healthFailure(NavModes::All, health_component_t::optical_flow,
|
||||
events::ID("check_optical_sensor_missing"),
|
||||
events::Log::Error, "Optical flow sensor missing");
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,55 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* 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
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "../Common.hpp"
|
||||
|
||||
#include <uORB/Subscription.hpp>
|
||||
#include <uORB/topics/vehicle_optical_flow.h>
|
||||
|
||||
class OpticalFlowCheck : public HealthAndArmingCheckBase
|
||||
{
|
||||
public:
|
||||
OpticalFlowCheck() = default;
|
||||
~OpticalFlowCheck() = default;
|
||||
|
||||
void checkAndReport(const Context &context, Report &reporter) override;
|
||||
|
||||
private:
|
||||
uORB::Subscription _vehicle_optical_flow_sub{ORB_ID::vehicle_optical_flow};
|
||||
|
||||
DEFINE_PARAMETERS_CUSTOM_PARENT(HealthAndArmingCheckBase,
|
||||
(ParamInt<px4::params::SYS_HAS_NUM_OF>) _param_sys_has_num_of
|
||||
)
|
||||
};
|
||||
@@ -36,6 +36,14 @@
|
||||
|
||||
using namespace time_literals;
|
||||
|
||||
PowerChecks::PowerChecks()
|
||||
{
|
||||
_voltage_low_hysteresis.set_hysteresis_time_from(false, 0_s);
|
||||
_voltage_low_hysteresis.set_hysteresis_time_from(true, 15_s);
|
||||
_voltage_high_hysteresis.set_hysteresis_time_from(false, 0_s);
|
||||
_voltage_high_hysteresis.set_hysteresis_time_from(true, 15_s);
|
||||
}
|
||||
|
||||
void PowerChecks::checkAndReport(const Context &context, Report &reporter)
|
||||
{
|
||||
if (circuit_breaker_enabled_by_val(_param_cbrk_supply_chk.get(), CBRK_SUPPLY_CHK_KEY)) {
|
||||
@@ -77,7 +85,11 @@ void PowerChecks::checkAndReport(const Context &context, Report &reporter)
|
||||
const float low_error_threshold = 4.7f;
|
||||
const float high_error_threshold = 5.4f;
|
||||
|
||||
if (avionics_power_rail_voltage < low_error_threshold) {
|
||||
const auto now = hrt_absolute_time();
|
||||
_voltage_low_hysteresis.set_state_and_update(avionics_power_rail_voltage < low_error_threshold, now);
|
||||
_voltage_high_hysteresis.set_state_and_update(avionics_power_rail_voltage > high_error_threshold, now);
|
||||
|
||||
if (_voltage_low_hysteresis.get_state()) {
|
||||
|
||||
/* EVENT
|
||||
* @description
|
||||
@@ -96,7 +108,7 @@ void PowerChecks::checkAndReport(const Context &context, Report &reporter)
|
||||
(double)avionics_power_rail_voltage);
|
||||
}
|
||||
|
||||
} else if (avionics_power_rail_voltage > high_error_threshold) {
|
||||
} else if (_voltage_high_hysteresis.get_state()) {
|
||||
/* EVENT
|
||||
* @description
|
||||
* Check the voltage supply to the FMU, it must be below {2:.2} Volt.
|
||||
|
||||
@@ -35,13 +35,14 @@
|
||||
|
||||
#include "../Common.hpp"
|
||||
|
||||
#include <lib/hysteresis/hysteresis.h>
|
||||
#include <uORB/Subscription.hpp>
|
||||
#include <uORB/topics/system_power.h>
|
||||
|
||||
class PowerChecks : public HealthAndArmingCheckBase
|
||||
{
|
||||
public:
|
||||
PowerChecks() = default;
|
||||
PowerChecks();
|
||||
~PowerChecks() = default;
|
||||
|
||||
void checkAndReport(const Context &context, Report &reporter) override;
|
||||
@@ -49,6 +50,8 @@ public:
|
||||
private:
|
||||
uORB::Subscription _system_power_sub{ORB_ID(system_power)};
|
||||
bool _overcurrent_warning_sent{false};
|
||||
systemlib::Hysteresis _voltage_low_hysteresis{false};
|
||||
systemlib::Hysteresis _voltage_high_hysteresis{false};
|
||||
|
||||
DEFINE_PARAMETERS_CUSTOM_PARENT(HealthAndArmingCheckBase,
|
||||
(ParamInt<px4::params::CBRK_SUPPLY_CHK>) _param_cbrk_supply_chk,
|
||||
|
||||
@@ -45,7 +45,6 @@ bool UserModeIntention::change(uint8_t user_intended_nav_state, ModeChangeSource
|
||||
bool force)
|
||||
{
|
||||
_ever_had_mode_change = true;
|
||||
_had_mode_change = true;
|
||||
|
||||
if (_handler) {
|
||||
// If a replacement mode is selected, select the internal one instead. The replacement will be selected after.
|
||||
|
||||
@@ -122,6 +122,16 @@ bool is_ground_vehicle(const vehicle_status_s ¤t_status)
|
||||
return (current_status.system_type == VEHICLE_TYPE_BOAT || current_status.system_type == VEHICLE_TYPE_GROUND_ROVER);
|
||||
}
|
||||
|
||||
bool is_rover_type(const vehicle_status_s ¤t_status)
|
||||
{
|
||||
return current_status.system_type == VEHICLE_TYPE_GROUND_ROVER;
|
||||
}
|
||||
|
||||
bool is_boat_type(const vehicle_status_s ¤t_status)
|
||||
{
|
||||
return current_status.system_type == VEHICLE_TYPE_BOAT;
|
||||
}
|
||||
|
||||
// End time for currently blinking LED message, 0 if no blink message
|
||||
static hrt_abstime blink_msg_end = 0;
|
||||
static int fd_leds{-1};
|
||||
|
||||
@@ -56,6 +56,8 @@ bool is_vtol(const vehicle_status_s ¤t_status);
|
||||
bool is_vtol_tailsitter(const vehicle_status_s ¤t_status);
|
||||
bool is_fixed_wing(const vehicle_status_s ¤t_status);
|
||||
bool is_ground_vehicle(const vehicle_status_s ¤t_status);
|
||||
bool is_rover_type(const vehicle_status_s ¤t_status);
|
||||
bool is_boat_type(const vehicle_status_s ¤t_status);
|
||||
|
||||
int buzzer_init(void);
|
||||
void buzzer_deinit(void);
|
||||
|
||||
@@ -192,16 +192,16 @@ FailsafeBase::ActionOptions Failsafe::fromBatteryWarningActParam(int param_value
|
||||
|
||||
switch (battery_warning) {
|
||||
default:
|
||||
case battery_status_s::BATTERY_WARNING_NONE:
|
||||
case battery_status_s::WARNING_NONE:
|
||||
options.action = Action::None;
|
||||
break;
|
||||
|
||||
case battery_status_s::BATTERY_WARNING_LOW:
|
||||
case battery_status_s::WARNING_LOW:
|
||||
options.action = Action::Warn;
|
||||
options.cause = Cause::BatteryLow;
|
||||
break;
|
||||
|
||||
case battery_status_s::BATTERY_WARNING_CRITICAL:
|
||||
case battery_status_s::WARNING_CRITICAL:
|
||||
options.action = Action::Warn;
|
||||
options.cause = Cause::BatteryCritical;
|
||||
|
||||
@@ -222,7 +222,7 @@ FailsafeBase::ActionOptions Failsafe::fromBatteryWarningActParam(int param_value
|
||||
|
||||
break;
|
||||
|
||||
case battery_status_s::BATTERY_WARNING_EMERGENCY:
|
||||
case battery_status_s::WARNING_EMERGENCY:
|
||||
options.action = Action::Warn;
|
||||
options.cause = Cause::BatteryEmergency;
|
||||
|
||||
@@ -550,21 +550,21 @@ void Failsafe::checkStateAndMode(const hrt_abstime &time_us, const State &state,
|
||||
_param_com_low_bat_act.get() : (int32_t)LowBatteryAction::Warning;
|
||||
|
||||
switch (status_flags.battery_warning) {
|
||||
case battery_status_s::BATTERY_WARNING_LOW:
|
||||
case battery_status_s::WARNING_LOW:
|
||||
_last_state_battery_warning_low = checkFailsafe(_caller_id_battery_warning_low, _last_state_battery_warning_low,
|
||||
true, fromBatteryWarningActParam(low_battery_action, battery_status_s::BATTERY_WARNING_LOW));
|
||||
true, fromBatteryWarningActParam(low_battery_action, battery_status_s::WARNING_LOW));
|
||||
break;
|
||||
|
||||
case battery_status_s::BATTERY_WARNING_CRITICAL:
|
||||
case battery_status_s::WARNING_CRITICAL:
|
||||
_last_state_battery_warning_critical = checkFailsafe(_caller_id_battery_warning_critical,
|
||||
_last_state_battery_warning_critical,
|
||||
true, fromBatteryWarningActParam(low_battery_action, battery_status_s::BATTERY_WARNING_CRITICAL));
|
||||
true, fromBatteryWarningActParam(low_battery_action, battery_status_s::WARNING_CRITICAL));
|
||||
break;
|
||||
|
||||
case battery_status_s::BATTERY_WARNING_EMERGENCY:
|
||||
case battery_status_s::WARNING_EMERGENCY:
|
||||
_last_state_battery_warning_emergency = checkFailsafe(_caller_id_battery_warning_emergency,
|
||||
_last_state_battery_warning_emergency,
|
||||
true, fromBatteryWarningActParam(low_battery_action, battery_status_s::BATTERY_WARNING_EMERGENCY));
|
||||
true, fromBatteryWarningActParam(low_battery_action, battery_status_s::WARNING_EMERGENCY));
|
||||
break;
|
||||
|
||||
default:
|
||||
|
||||
@@ -11,3 +11,11 @@ menuconfig USER_DATAMAN
|
||||
depends on BOARD_PROTECTED && MODULES_DATAMAN
|
||||
---help---
|
||||
Put dataman in userspace memory
|
||||
|
||||
|
||||
menuconfig DATAMAN_PERSISTENT_STORAGE
|
||||
bool "dataman supports persistent storage"
|
||||
default y
|
||||
depends on MODULES_DATAMAN
|
||||
---help---
|
||||
Dataman supports reading/writing to persistent storage
|
||||
|
||||
@@ -65,12 +65,14 @@ __END_DECLS
|
||||
|
||||
static constexpr int TASK_STACK_SIZE = 1420;
|
||||
|
||||
#ifdef CONFIG_DATAMAN_PERSISTENT_STORAGE
|
||||
/* Private File based Operations */
|
||||
static ssize_t _file_write(dm_item_t item, unsigned index, const void *buf, size_t count);
|
||||
static ssize_t _file_read(dm_item_t item, unsigned index, void *buf, size_t count);
|
||||
static int _file_clear(dm_item_t item);
|
||||
static int _file_initialize(unsigned max_offset);
|
||||
static void _file_shutdown();
|
||||
#endif
|
||||
|
||||
/* Private Ram based Operations */
|
||||
static ssize_t _ram_write(dm_item_t item, unsigned index, const void *buf, size_t count);
|
||||
@@ -88,6 +90,7 @@ typedef struct dm_operations_t {
|
||||
int (*wait)(px4_sem_t *sem);
|
||||
} dm_operations_t;
|
||||
|
||||
#ifdef CONFIG_DATAMAN_PERSISTENT_STORAGE
|
||||
static constexpr dm_operations_t dm_file_operations = {
|
||||
.write = _file_write,
|
||||
.read = _file_read,
|
||||
@@ -96,6 +99,7 @@ static constexpr dm_operations_t dm_file_operations = {
|
||||
.shutdown = _file_shutdown,
|
||||
.wait = px4_sem_wait,
|
||||
};
|
||||
#endif
|
||||
|
||||
static constexpr dm_operations_t dm_ram_operations = {
|
||||
.write = _ram_write,
|
||||
@@ -149,9 +153,11 @@ static uint8_t dataman_clients_count = 1;
|
||||
static perf_counter_t _dm_read_perf{nullptr};
|
||||
static perf_counter_t _dm_write_perf{nullptr};
|
||||
|
||||
#ifdef CONFIG_DATAMAN_PERSISTENT_STORAGE
|
||||
/* The data manager store file handle and file name */
|
||||
static const char *default_device_path = PX4_STORAGEDIR "/dataman";
|
||||
static char *k_data_manager_device_path = nullptr;
|
||||
#endif
|
||||
|
||||
static enum {
|
||||
BACKEND_NONE = 0,
|
||||
@@ -241,6 +247,7 @@ static ssize_t _ram_write(dm_item_t item, unsigned index, const void *buf, size_
|
||||
return count;
|
||||
}
|
||||
|
||||
#ifdef CONFIG_DATAMAN_PERSISTENT_STORAGE
|
||||
/* write to the data manager file */
|
||||
static ssize_t
|
||||
_file_write(dm_item_t item, unsigned index, const void *buf, size_t count)
|
||||
@@ -318,6 +325,7 @@ _file_write(dm_item_t item, unsigned index, const void *buf, size_t count)
|
||||
/* All is well... return the number of user data written */
|
||||
return count - DM_SECTOR_HDR_SIZE;
|
||||
}
|
||||
#endif
|
||||
|
||||
/* Retrieve from the data manager RAM buffer*/
|
||||
static ssize_t _ram_read(dm_item_t item, unsigned index, void *buf, size_t count)
|
||||
@@ -362,6 +370,7 @@ static ssize_t _ram_read(dm_item_t item, unsigned index, void *buf, size_t count
|
||||
return buffer[0];
|
||||
}
|
||||
|
||||
#ifdef CONFIG_DATAMAN_PERSISTENT_STORAGE
|
||||
/* Retrieve from the data manager file */
|
||||
static ssize_t
|
||||
_file_read(dm_item_t item, unsigned index, void *buf, size_t count)
|
||||
@@ -442,6 +451,7 @@ _file_read(dm_item_t item, unsigned index, void *buf, size_t count)
|
||||
/* Return the number of bytes of caller data read */
|
||||
return buffer[0];
|
||||
}
|
||||
#endif
|
||||
|
||||
static int _ram_clear(dm_item_t item)
|
||||
{
|
||||
@@ -475,6 +485,7 @@ static int _ram_clear(dm_item_t item)
|
||||
return result;
|
||||
}
|
||||
|
||||
#ifdef CONFIG_DATAMAN_PERSISTENT_STORAGE
|
||||
static int
|
||||
_file_clear(dm_item_t item)
|
||||
{
|
||||
@@ -528,7 +539,9 @@ _file_clear(dm_item_t item)
|
||||
fsync(dm_operations_data.file.fd);
|
||||
return result;
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_DATAMAN_PERSISTENT_STORAGE
|
||||
static int
|
||||
_file_initialize(unsigned max_offset)
|
||||
{
|
||||
@@ -594,6 +607,7 @@ _file_initialize(unsigned max_offset)
|
||||
|
||||
return 0;
|
||||
}
|
||||
#endif
|
||||
|
||||
static int
|
||||
_ram_initialize(unsigned max_offset)
|
||||
@@ -614,12 +628,14 @@ _ram_initialize(unsigned max_offset)
|
||||
return 0;
|
||||
}
|
||||
|
||||
#ifdef CONFIG_DATAMAN_PERSISTENT_STORAGE
|
||||
static void
|
||||
_file_shutdown()
|
||||
{
|
||||
close(dm_operations_data.file.fd);
|
||||
dm_operations_data.running = false;
|
||||
}
|
||||
#endif
|
||||
|
||||
static void
|
||||
_ram_shutdown()
|
||||
@@ -633,9 +649,12 @@ task_main(int argc, char *argv[])
|
||||
{
|
||||
/* Dataman can use disk or RAM */
|
||||
switch (backend) {
|
||||
#ifdef CONFIG_DATAMAN_PERSISTENT_STORAGE
|
||||
|
||||
case BACKEND_FILE:
|
||||
g_dm_ops = &dm_file_operations;
|
||||
break;
|
||||
#endif
|
||||
|
||||
case BACKEND_RAM:
|
||||
g_dm_ops = &dm_ram_operations;
|
||||
@@ -680,10 +699,13 @@ task_main(int argc, char *argv[])
|
||||
}
|
||||
|
||||
switch (backend) {
|
||||
#ifdef CONFIG_DATAMAN_PERSISTENT_STORAGE
|
||||
|
||||
case BACKEND_FILE:
|
||||
PX4_INFO("data manager file '%s' size is %u bytes", k_data_manager_device_path, max_offset);
|
||||
|
||||
break;
|
||||
#endif
|
||||
|
||||
case BACKEND_RAM:
|
||||
PX4_INFO("data manager RAM size is %u bytes", max_offset);
|
||||
@@ -871,7 +893,7 @@ usage()
|
||||
R"DESCR_STR(
|
||||
### Description
|
||||
Module to provide persistent storage for the rest of the system in form of a simple database through a C API.
|
||||
Multiple backends are supported:
|
||||
Multiple backends are supported depending on the board:
|
||||
- a file (eg. on the SD card)
|
||||
- RAM (this is obviously not persistent)
|
||||
|
||||
@@ -885,9 +907,13 @@ Reading and writing a single item is always atomic.
|
||||
|
||||
PRINT_MODULE_USAGE_NAME("dataman", "system");
|
||||
PRINT_MODULE_USAGE_COMMAND("start");
|
||||
#ifdef CONFIG_DATAMAN_PERSISTENT_STORAGE
|
||||
PRINT_MODULE_USAGE_PARAM_STRING('f', nullptr, "<file>", "Storage file", true);
|
||||
#endif
|
||||
PRINT_MODULE_USAGE_PARAM_FLAG('r', "Use RAM backend (NOT persistent)", true);
|
||||
#ifdef CONFIG_DATAMAN_PERSISTENT_STORAGE
|
||||
PRINT_MODULE_USAGE_PARAM_COMMENT("The options -f and -r are mutually exclusive. If nothing is specified, a file 'dataman' is used");
|
||||
#endif
|
||||
PRINT_MODULE_USAGE_DEFAULT_COMMANDS();
|
||||
}
|
||||
|
||||
@@ -930,9 +956,14 @@ dataman_main(int argc, char *argv[])
|
||||
return -1;
|
||||
}
|
||||
|
||||
#ifdef CONFIG_DATAMAN_PERSISTENT_STORAGE
|
||||
backend = BACKEND_FILE;
|
||||
k_data_manager_device_path = strdup(dmoptarg);
|
||||
PX4_INFO("dataman file set to: %s", k_data_manager_device_path);
|
||||
#else
|
||||
backend = BACKEND_RAM;
|
||||
PX4_WARN("dataman does not support persistent storage. Falling back to RAM.");
|
||||
#endif
|
||||
break;
|
||||
|
||||
case 'r':
|
||||
@@ -951,16 +982,22 @@ dataman_main(int argc, char *argv[])
|
||||
}
|
||||
|
||||
if (backend == BACKEND_NONE) {
|
||||
#ifdef CONFIG_DATAMAN_PERSISTENT_STORAGE
|
||||
backend = BACKEND_FILE;
|
||||
k_data_manager_device_path = strdup(default_device_path);
|
||||
#else
|
||||
backend = BACKEND_RAM;
|
||||
#endif
|
||||
}
|
||||
|
||||
start();
|
||||
|
||||
if (!is_running()) {
|
||||
PX4_ERR("dataman start failed");
|
||||
#ifdef CONFIG_DATAMAN_PERSISTENT_STORAGE
|
||||
free(k_data_manager_device_path);
|
||||
k_data_manager_device_path = nullptr;
|
||||
#endif
|
||||
return -1;
|
||||
}
|
||||
|
||||
@@ -976,8 +1013,10 @@ dataman_main(int argc, char *argv[])
|
||||
|
||||
if (!strcmp(argv[1], "stop")) {
|
||||
stop();
|
||||
#ifdef CONFIG_DATAMAN_PERSISTENT_STORAGE
|
||||
free(k_data_manager_device_path);
|
||||
k_data_manager_device_path = nullptr;
|
||||
#endif
|
||||
|
||||
} else if (!strcmp(argv[1], "status")) {
|
||||
status();
|
||||
|
||||
@@ -38,6 +38,7 @@ execute_process(
|
||||
COMMAND ${PYTHON_EXECUTABLE} -m symforce.symbolic
|
||||
RESULT_VARIABLE PYTHON_SYMFORCE_EXIT_CODE
|
||||
OUTPUT_QUIET
|
||||
ERROR_QUIET
|
||||
)
|
||||
|
||||
# for now only provide symforce target helper if derivation.py generation isn't default
|
||||
|
||||
@@ -40,7 +40,7 @@ using namespace time_literals;
|
||||
EscBattery::EscBattery() :
|
||||
ModuleParams(nullptr),
|
||||
WorkItem(MODULE_NAME, px4::wq_configurations::lp_default),
|
||||
_battery(1, this, ESC_BATTERY_INTERVAL_US, battery_status_s::BATTERY_SOURCE_ESCS)
|
||||
_battery(1, this, ESC_BATTERY_INTERVAL_US, battery_status_s::SOURCE_ESCS)
|
||||
{
|
||||
}
|
||||
|
||||
|
||||
@@ -101,12 +101,12 @@ void StatusDisplay::set_leds()
|
||||
}
|
||||
|
||||
// handle battery warnings, once a state is reached it can not be reset
|
||||
if (_battery_status_sub.get().warning == battery_status_s::BATTERY_WARNING_CRITICAL || _critical_battery) {
|
||||
if (_battery_status_sub.get().warning == battery_status_s::WARNING_CRITICAL || _critical_battery) {
|
||||
_led_control.color = led_control_s::COLOR_RED;
|
||||
_led_control.mode = led_control_s::MODE_BLINK_FAST;
|
||||
_critical_battery = true;
|
||||
|
||||
} else if (_battery_status_sub.get().warning == battery_status_s::BATTERY_WARNING_LOW || _low_battery) {
|
||||
} else if (_battery_status_sub.get().warning == battery_status_s::WARNING_LOW || _low_battery) {
|
||||
_led_control.color = led_control_s::COLOR_RED;
|
||||
_led_control.mode = led_control_s::MODE_FLASH;
|
||||
_low_battery = true;
|
||||
|
||||
@@ -159,6 +159,11 @@ bool FlightTaskAuto::update()
|
||||
_checkEmergencyBraking();
|
||||
Vector3f waypoints[] = {_prev_wp, _position_setpoint, _next_wp};
|
||||
|
||||
if (isTargetModified()) {
|
||||
// In case the target has been modified, we take this as the next waypoints
|
||||
waypoints[2] = _position_setpoint;
|
||||
}
|
||||
|
||||
const bool should_wait_for_yaw_align = _param_mpc_yaw_mode.get() == int32_t(yaw_mode::towards_waypoint_yaw_first)
|
||||
&& !_yaw_sp_aligned;
|
||||
const bool force_zero_velocity_setpoint = should_wait_for_yaw_align || _is_emergency_braking_active;
|
||||
@@ -248,9 +253,15 @@ void FlightTaskAuto::_prepareLandSetpoints()
|
||||
// Stick full up -1 -> stop, stick full down 1 -> double the speed
|
||||
vertical_speed *= (1 - _sticks.getThrottleZeroCenteredExpo());
|
||||
|
||||
Vector2f sticks_xy = _sticks.getPitchRollExpo();
|
||||
|
||||
if (sticks_xy.longerThan(FLT_EPSILON)) {
|
||||
// Ensure no unintended yawing when nudging horizontally during initial heading alignment
|
||||
_land_heading = _yaw_sp_prev;
|
||||
}
|
||||
|
||||
rcHelpModifyYaw(_land_heading);
|
||||
|
||||
Vector2f sticks_xy = _sticks.getPitchRollExpo();
|
||||
Vector2f sticks_ne = sticks_xy;
|
||||
Sticks::rotateIntoHeadingFrameXY(sticks_ne, _yaw, _land_heading);
|
||||
|
||||
@@ -759,6 +770,15 @@ bool FlightTaskAuto::_generateHeadingAlongTraj()
|
||||
return res;
|
||||
}
|
||||
|
||||
bool FlightTaskAuto::isTargetModified() const
|
||||
{
|
||||
const bool xy_modified = (_target - _position_setpoint).xy().longerThan(FLT_EPSILON);
|
||||
const bool z_valid = PX4_ISFINITE(_position_setpoint(2));
|
||||
const bool z_modified = z_valid && std::fabs((_target - _position_setpoint)(2)) > FLT_EPSILON;
|
||||
|
||||
return xy_modified || z_modified;
|
||||
}
|
||||
|
||||
void FlightTaskAuto::_updateTrajConstraints()
|
||||
{
|
||||
// update params of the position smoothing
|
||||
|
||||
@@ -108,6 +108,7 @@ protected:
|
||||
|
||||
void _checkEmergencyBraking();
|
||||
bool _generateHeadingAlongTraj(); /**< Generates heading along trajectory. */
|
||||
bool isTargetModified() const;
|
||||
void _updateTrajConstraints();
|
||||
|
||||
void rcHelpModifyYaw(float &yaw_sp);
|
||||
|
||||
@@ -105,14 +105,11 @@ void LoggedTopics::add_default_topics()
|
||||
add_topic("radio_status");
|
||||
add_optional_topic("rover_attitude_setpoint", 100);
|
||||
add_optional_topic("rover_attitude_status", 100);
|
||||
add_optional_topic("rover_velocity_status", 100);
|
||||
add_optional_topic("rover_rate_setpoint", 100);
|
||||
add_optional_topic("rover_rate_status", 100);
|
||||
add_optional_topic("rover_steering_setpoint", 100);
|
||||
add_optional_topic("rover_throttle_setpoint", 100);
|
||||
add_optional_topic("rover_mecanum_guidance_status", 100);
|
||||
add_optional_topic("rover_mecanum_setpoint", 100);
|
||||
add_optional_topic("rover_mecanum_status", 100);
|
||||
add_optional_topic("rover_velocity_status", 100);
|
||||
add_topic("rtl_time_estimate", 1000);
|
||||
add_topic("rtl_status", 2000);
|
||||
add_optional_topic("sensor_airflow", 100);
|
||||
|
||||
Submodule src/modules/mavlink/mavlink updated: 619947d8bc...8690e10164
@@ -1814,13 +1814,13 @@ MavlinkReceiver::handle_message_battery_status(mavlink_message_t *msg)
|
||||
// Set the battery warning based on remaining charge.
|
||||
// Note: Smallest values must come first in evaluation.
|
||||
if (battery_status.remaining < _param_bat_emergen_thr.get()) {
|
||||
battery_status.warning = battery_status_s::BATTERY_WARNING_EMERGENCY;
|
||||
battery_status.warning = battery_status_s::WARNING_EMERGENCY;
|
||||
|
||||
} else if (battery_status.remaining < _param_bat_crit_thr.get()) {
|
||||
battery_status.warning = battery_status_s::BATTERY_WARNING_CRITICAL;
|
||||
battery_status.warning = battery_status_s::WARNING_CRITICAL;
|
||||
|
||||
} else if (battery_status.remaining < _param_bat_low_thr.get()) {
|
||||
battery_status.warning = battery_status_s::BATTERY_WARNING_LOW;
|
||||
battery_status.warning = battery_status_s::WARNING_LOW;
|
||||
}
|
||||
|
||||
_battery_pub.publish(battery_status);
|
||||
@@ -1976,7 +1976,16 @@ MavlinkReceiver::handle_message_tunnel(mavlink_message_t *msg)
|
||||
memcpy(tunnel.payload, mavlink_tunnel.payload, sizeof(tunnel.payload));
|
||||
static_assert(sizeof(tunnel.payload) == sizeof(mavlink_tunnel.payload), "mavlink_tunnel.payload size mismatch");
|
||||
|
||||
_mavlink_tunnel_pub.publish(tunnel);
|
||||
switch (mavlink_tunnel.payload_type) {
|
||||
case MAV_TUNNEL_PAYLOAD_TYPE_MODALAI_ESC_UART_PASSTHRU:
|
||||
_esc_serial_passthru_pub.publish(tunnel);
|
||||
break;
|
||||
|
||||
default:
|
||||
_mavlink_tunnel_pub.publish(tunnel);
|
||||
break;
|
||||
}
|
||||
|
||||
|
||||
}
|
||||
|
||||
|
||||
@@ -307,6 +307,7 @@ private:
|
||||
uORB::Publication<landing_target_pose_s> _landing_target_pose_pub{ORB_ID(landing_target_pose)};
|
||||
uORB::Publication<log_message_s> _log_message_pub{ORB_ID(log_message)};
|
||||
uORB::Publication<mavlink_tunnel_s> _mavlink_tunnel_pub{ORB_ID(mavlink_tunnel)};
|
||||
uORB::Publication<mavlink_tunnel_s> _esc_serial_passthru_pub{ORB_ID(esc_serial_passthru)};
|
||||
uORB::Publication<obstacle_distance_s> _obstacle_distance_pub{ORB_ID(obstacle_distance)};
|
||||
uORB::Publication<offboard_control_mode_s> _offboard_control_mode_pub{ORB_ID(offboard_control_mode)};
|
||||
uORB::Publication<onboard_computer_status_s> _onboard_computer_status_pub{ORB_ID(onboard_computer_status)};
|
||||
|
||||
@@ -81,31 +81,31 @@ private:
|
||||
math::max((int)battery_status.time_remaining_s, 1) : 0;
|
||||
|
||||
switch (battery_status.warning) {
|
||||
case (battery_status_s::BATTERY_WARNING_NONE):
|
||||
case (battery_status_s::WARNING_NONE):
|
||||
bat_msg.charge_state = MAV_BATTERY_CHARGE_STATE_OK;
|
||||
break;
|
||||
|
||||
case (battery_status_s::BATTERY_WARNING_LOW):
|
||||
case (battery_status_s::WARNING_LOW):
|
||||
bat_msg.charge_state = MAV_BATTERY_CHARGE_STATE_LOW;
|
||||
break;
|
||||
|
||||
case (battery_status_s::BATTERY_WARNING_CRITICAL):
|
||||
case (battery_status_s::WARNING_CRITICAL):
|
||||
bat_msg.charge_state = MAV_BATTERY_CHARGE_STATE_CRITICAL;
|
||||
break;
|
||||
|
||||
case (battery_status_s::BATTERY_WARNING_EMERGENCY):
|
||||
case (battery_status_s::WARNING_EMERGENCY):
|
||||
bat_msg.charge_state = MAV_BATTERY_CHARGE_STATE_EMERGENCY;
|
||||
break;
|
||||
|
||||
case (battery_status_s::BATTERY_WARNING_FAILED):
|
||||
case (battery_status_s::WARNING_FAILED):
|
||||
bat_msg.charge_state = MAV_BATTERY_CHARGE_STATE_FAILED;
|
||||
break;
|
||||
|
||||
case (battery_status_s::BATTERY_STATE_UNHEALTHY):
|
||||
case (battery_status_s::STATE_UNHEALTHY):
|
||||
bat_msg.charge_state = MAV_BATTERY_CHARGE_STATE_UNHEALTHY;
|
||||
break;
|
||||
|
||||
case (battery_status_s::BATTERY_STATE_CHARGING):
|
||||
case (battery_status_s::STATE_CHARGING):
|
||||
bat_msg.charge_state = MAV_BATTERY_CHARGE_STATE_CHARGING;
|
||||
break;
|
||||
|
||||
|
||||
@@ -285,7 +285,7 @@ private:
|
||||
updated = true;
|
||||
_batteries[i].connected = battery.connected;
|
||||
|
||||
if (battery.warning > battery_status_s::BATTERY_WARNING_LOW) {
|
||||
if (battery.warning > battery_status_s::WARNING_LOW) {
|
||||
msg->failure_flags |= HL_FAILURE_FLAG_BATTERY;
|
||||
}
|
||||
}
|
||||
|
||||
@@ -206,8 +206,9 @@ MissionBlock::is_mission_item_reached_or_completed()
|
||||
_waypoint_position_reached = true;
|
||||
}
|
||||
|
||||
} else if (_mission_item.nav_cmd == NAV_CMD_TAKEOFF
|
||||
&& _navigator->get_vstatus()->vehicle_type == vehicle_status_s::VEHICLE_TYPE_ROVER) {
|
||||
} else if (_mission_item.nav_cmd == NAV_CMD_TAKEOFF &&
|
||||
(_navigator->get_vstatus()->vehicle_type == vehicle_status_s::VEHICLE_TYPE_ROVER
|
||||
|| _navigator->get_vstatus()->vehicle_type == vehicle_status_s::VEHICLE_TYPE_BOAT)) {
|
||||
// Accept takeoff waypoint to be reached if the distance in 2D plane is within acceptance radius
|
||||
if (dist_xy >= 0.0f && dist_xy <= _navigator->get_acceptance_radius()) {
|
||||
_waypoint_position_reached = true;
|
||||
|
||||
@@ -1137,7 +1137,8 @@ float Navigator::get_altitude_acceptance_radius()
|
||||
return _param_nav_fw_alt_rad.get();
|
||||
}
|
||||
|
||||
} else if (get_vstatus()->vehicle_type == vehicle_status_s::VEHICLE_TYPE_ROVER) {
|
||||
} else if (get_vstatus()->vehicle_type == vehicle_status_s::VEHICLE_TYPE_ROVER
|
||||
|| get_vstatus()->vehicle_type == vehicle_status_s::VEHICLE_TYPE_BOAT) {
|
||||
return INFINITY;
|
||||
|
||||
} else {
|
||||
|
||||
@@ -721,10 +721,6 @@ Replay::nextDataMessage(std::ifstream &file, Subscription &subscription, int msg
|
||||
}
|
||||
|
||||
switch (message_header.msg_type) {
|
||||
case (int)ULogMessageType::ADD_LOGGED_MSG:
|
||||
readAndAddSubscription(file, message_header.msg_size);
|
||||
break;
|
||||
|
||||
case (int)ULogMessageType::DATA:
|
||||
file.read((char *)&file_msg_id, sizeof(file_msg_id));
|
||||
|
||||
@@ -751,6 +747,7 @@ Replay::nextDataMessage(std::ifstream &file, Subscription &subscription, int msg
|
||||
break;
|
||||
|
||||
case (int)ULogMessageType::REMOVE_LOGGED_MSG: //skip these
|
||||
case (int)ULogMessageType::ADD_LOGGED_MSG:
|
||||
case (int)ULogMessageType::PARAMETER:
|
||||
case (int)ULogMessageType::DROPOUT:
|
||||
case (int)ULogMessageType::INFO:
|
||||
@@ -907,19 +904,26 @@ Replay::run()
|
||||
ulog_message_header_s message_header;
|
||||
replay_file.seekg(_data_section_start);
|
||||
|
||||
//we know the next message must be an ADD_LOGGED_MSG
|
||||
ReadAndAndAddSubResult res;
|
||||
|
||||
do {
|
||||
while (true) {
|
||||
//we are in the Definition & Data Section Message Header section
|
||||
replay_file.read((char *)&message_header, ULOG_MSG_HEADER_LEN);
|
||||
res = readAndAddSubscription(replay_file, message_header.msg_size);
|
||||
|
||||
if (res == ReadAndAndAddSubResult::kFailure) {
|
||||
PX4_ERR("Failed to read subscription");
|
||||
return;
|
||||
if (!replay_file) {
|
||||
break;
|
||||
}
|
||||
|
||||
} while (res != ReadAndAndAddSubResult::kSuccess);
|
||||
if (message_header.msg_type == (int)ULogMessageType::ADD_LOGGED_MSG) {
|
||||
readAndAddSubscription(replay_file, message_header.msg_size);
|
||||
|
||||
} else if (message_header.msg_type == (int)ULogMessageType::DATA) {
|
||||
// End of Definition & Data Section Message Header section
|
||||
break;
|
||||
|
||||
} else {
|
||||
// Not important for now, skip
|
||||
replay_file.seekg(message_header.msg_size, ios::cur);
|
||||
}
|
||||
}
|
||||
|
||||
const uint64_t timestamp_offset = getTimestampOffset();
|
||||
uint32_t nr_published_messages = 0;
|
||||
|
||||
@@ -50,5 +50,3 @@ px4_add_module(
|
||||
MODULE_CONFIG
|
||||
module.yaml
|
||||
)
|
||||
|
||||
set_property(GLOBAL APPEND PROPERTY PX4_MODULE_CONFIG_FILES ${CMAKE_CURRENT_SOURCE_DIR}/../../lib/rover_control/module.yaml)
|
||||
|
||||
@@ -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,9 @@
|
||||
#
|
||||
############################################################################
|
||||
|
||||
add_subdirectory(RoverMecanumGuidance)
|
||||
add_subdirectory(RoverMecanumControl)
|
||||
add_subdirectory(MecanumRateControl)
|
||||
add_subdirectory(MecanumAttControl)
|
||||
add_subdirectory(MecanumPosVelControl)
|
||||
|
||||
px4_add_module(
|
||||
MODULE modules__rover_mecanum
|
||||
@@ -41,10 +42,11 @@ px4_add_module(
|
||||
RoverMecanum.cpp
|
||||
RoverMecanum.hpp
|
||||
DEPENDS
|
||||
RoverMecanumGuidance
|
||||
RoverMecanumControl
|
||||
MecanumRateControl
|
||||
MecanumAttControl
|
||||
MecanumPosVelControl
|
||||
px4_work_queue
|
||||
pure_pursuit
|
||||
rover_control
|
||||
MODULE_CONFIG
|
||||
module.yaml
|
||||
)
|
||||
|
||||
@@ -1,6 +1,5 @@
|
||||
menuconfig MODULES_ROVER_MECANUM
|
||||
bool "rover_mecanum"
|
||||
default n
|
||||
depends on MODULES_CONTROL_ALLOCATOR
|
||||
---help---
|
||||
Enable support for control of mecanum rovers
|
||||
Enable support for mecanum rovers
|
||||
|
||||
+5
-4
@@ -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,9 @@
|
||||
#
|
||||
############################################################################
|
||||
|
||||
px4_add_library(RoverMecanumGuidance
|
||||
RoverMecanumGuidance.cpp
|
||||
px4_add_library(MecanumAttControl
|
||||
MecanumAttControl.cpp
|
||||
)
|
||||
|
||||
target_include_directories(RoverMecanumGuidance PUBLIC ${CMAKE_CURRENT_SOURCE_DIR})
|
||||
target_link_libraries(MecanumAttControl PUBLIC PID)
|
||||
target_include_directories(MecanumAttControl PUBLIC ${CMAKE_CURRENT_SOURCE_DIR})
|
||||
Some files were not shown because too many files have changed in this diff Show More
Reference in New Issue
Block a user