Compare commits

..

8 Commits

Author SHA1 Message Date
Ramon Roche c5f2a32c96 ci: build each platform on its own arch 2025-02-27 08:48:02 -08:00
Ramon Roche fd06661da9 ci: test container build push 2025-02-27 07:41:13 -08:00
Ramon Roche b786006443 ci: only build amd64 for tests
avoids docker engine error when trying to export manifest lists
2025-02-26 20:48:39 -08:00
Ramon Roche 379bb181f2 ci: multi platform container build
saves cache to s3 and defaults to gh public cache
2025-02-26 20:39:56 -08:00
Ramon Roche c942530825 ci: only push containers on tag events 2025-02-26 19:29:52 -08:00
Ramon Roche b5993c4ec0 setup: install all compilers for arch
plus better output formatting
2025-02-26 19:27:39 -08:00
Ramon Roche cdaaf81354 ci: build containers on releases only 2025-02-25 21:21:59 -08:00
Ramon Roche d60d760eb4 ci: build targets using px4-dev container 2025-02-25 21:21:59 -08:00
124 changed files with 1503 additions and 2497 deletions
+4 -2
View File
@@ -94,7 +94,7 @@ jobs:
- name: Building [${{ matrix.group }}]
run: |
./Tools/ci/build_all_runner.sh ${{matrix.targets}}
./Tools/ci/build_all_runner.sh ${{matrix.targets}} ${{matrix.arch}}
- name: Arrange Build Artifacts
run: |
@@ -140,10 +140,12 @@ jobs:
release:
name: Create Release and Upload Artifacts
permissions:
contents: write
# runs-on: ubuntu-latest
runs-on: [runs-on,runner=1cpu-linux-x64,image=ubuntu22-full-x64,"run-id=${{ github.run_id }}",spot=false]
needs: [setup, group_targets]
if: startsWith(github.ref, 'refs/tags/v')
if: startsWith(github.ref, 'refs/tags/')
steps:
- name: Download Artifacts
uses: actions/download-artifact@v4
+16 -12
View File
@@ -16,9 +16,13 @@ on:
jobs:
build:
name: Build and Push Container
runs-on: [runs-on,runner=8cpu-linux-x64,image=ubuntu24-full-x64,"run-id=${{ github.run_id }}",spot=false]
name: Build and Push Container (${{ matrix.arch }})
strategy:
matrix:
arch: [x64, arm64]
runs-on: [runs-on,"runner=8cpu-linux-${{ matrix.arch }}","image=ubuntu24-full-${{ matrix.arch }}","run-id=${{ github.run_id }}",spot=false,extras=s3-cache]
steps:
- uses: runs-on/action@v1
- uses: actions/checkout@v4
with:
fetch-tags: true
@@ -32,13 +36,14 @@ jobs:
- name: Login to Docker Hub
uses: docker/login-action@v3
if: github.event_name != 'pull_request'
# if: ${{ startsWith(github.ref, 'refs/tags/') }}
with:
username: ${{ secrets.DOCKERHUB_USERNAME }}
password: ${{ secrets.DOCKERHUB_TOKEN }}
- name: Login to GitHub Container Registry
uses: docker/login-action@v3
# if: ${{ startsWith(github.ref, 'refs/tags/') }}
with:
registry: ghcr.io
username: ${{ github.actor }}
@@ -64,12 +69,11 @@ jobs:
context: Tools/setup
tags: ${{ steps.meta.outputs.tags }}
labels: ${{ steps.meta.outputs.labels }}
platforms: |
linux/amd64
platforms: linux/${{ matrix.arch == 'x64' && 'amd64' || 'arm64' }}
load: true
push: false
cache-from: type=s3,blobs_prefix=cache/${{ github.repository }}/,manifests_prefix=cache/${{ github.repository }}/,region=${{ env.RUNS_ON_AWS_REGION }},bucket=${{ env.RUNS_ON_S3_BUCKET_CACHE }}
cache-to: type=s3,blobs_prefix=cache/${{ github.repository }}/,manifests_prefix=cache/${{ github.repository }}/,region=${{ env.RUNS_ON_AWS_REGION }},bucket=${{ env.RUNS_ON_S3_BUCKET_CACHE }},mode=max
cache-from: type=gha
cache-to: type=gha,mode=max
- name: Get Tag Name
id: tag_name
@@ -89,13 +93,13 @@ jobs:
- name: Push container image
uses: docker/build-push-action@v6
# if: ${{ startsWith(github.ref, 'refs/tags/') }}
with:
context: Tools/setup
tags: ${{ steps.meta.outputs.tags }}
labels: ${{ steps.meta.outputs.labels }}
platforms: |
linux/amd64
platforms: linux/${{ matrix.arch == 'x64' && 'amd64' || 'arm64' }}
provenance: mode=max
push: ${{ github.event_name != 'pull_request' }}
cache-from: type=s3,blobs_prefix=cache/${{ github.repository }}/,manifests_prefix=cache/${{ github.repository }}/,region=${{ env.RUNS_ON_AWS_REGION }},bucket=${{ env.RUNS_ON_S3_BUCKET_CACHE }}
cache-to: type=s3,blobs_prefix=cache/${{ github.repository }}/,manifests_prefix=cache/${{ github.repository }}/,region=${{ env.RUNS_ON_AWS_REGION }},bucket=${{ env.RUNS_ON_S3_BUCKET_CACHE }},mode=max
push: true
cache-from: type=gha
cache-to: type=gha,mode=max
+1 -1
View File
@@ -99,7 +99,7 @@
#
#=============================================================================
cmake_minimum_required(VERSION 3.10 FATAL_ERROR)
cmake_minimum_required(VERSION 3.9 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)
@@ -13,6 +13,10 @@ 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,8 +12,13 @@ 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,6 +13,9 @@ 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,6 +14,10 @@ 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,6 +11,8 @@ 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,6 +45,12 @@ 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,6 +11,11 @@ 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,6 +44,12 @@ 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
@@ -45,7 +45,10 @@ 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 102 # right wheel front
@@ -13,6 +13,12 @@ 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,6 +13,11 @@ 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
@@ -1,15 +0,0 @@
#!/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,6 +15,8 @@ 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,6 +83,9 @@ 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,7 +91,6 @@ 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 an already running world
# look for running ${gz_command} gazebo 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
# Setup gz environment variables
# source generated gz_env.sh for GZ_SIM_RESOURCE_PATH
if [ -f ./gz_env.sh ]; then
. ./gz_env.sh
@@ -87,125 +87,62 @@ 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=${GZ_VERBOSE:=1} -r -s "${PX4_GZ_WORLDS}/${PX4_GZ_WORLD}.sdf" &
${gz_command} ${gz_sub_command} --verbose=1 -r -s "${PX4_GZ_WORLDS}/${PX4_GZ_WORLD}.sdf" &
if [ -z "${HEADLESS}" ]; then
echo "INFO [init] Starting gz gui"
${gz_command} ${gz_sub_command} -g > /dev/null 2>&1 &
# HEADLESS not set, starting gui
${gz_command} ${gz_sub_command} -g &
fi
else
# Gazebo is already running
# Gazebo is already running, do not start the simulator, nor the GUI
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 - either spawn a model or connect to existing one
# start gz_bridge
if [ -n "${PX4_SIM_MODEL#*gz_}" ] && [ -z "${PX4_GZ_MODEL_NAME}" ]; then
# Spawn a model
MODEL_NAME="${PX4_SIM_MODEL#*gz_}"
MODEL_NAME_INSTANCE="${MODEL_NAME}_${px4_instance}"
# model specified, gz_bridge will spawn model
POSE_ARG=""
if [ -n "${PX4_GZ_MODEL_POSE}" ]; then
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}
# model pose provided: [x, y, z, roll, pitch, yaw]
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}"
# 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"
fi
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
# 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 "ERROR [init] gz_bridge failed to start and spawn model"
exit 1
fi
# 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
# model name specificed, gz_bridge will attach to existing model
echo "INFO [init] PX4_GZ_MODEL_NAME set, PX4 will attach to existing model"
if ! gz_bridge start -w "${PX4_GZ_WORLD}" -n "${PX4_GZ_MODEL_NAME}"; then
if ! gz_bridge start -n "${PX4_GZ_MODEL_NAME}" -w "${PX4_GZ_WORLD}"; then
echo "ERROR [init] gz_bridge failed to start and attach to existing model"
exit 1
fi
else
echo "ERROR [init] failed to pass either PX4_GZ_MODEL_NAME or PX4_SIM_MODEL"
echo "ERROR [init] failed to pass only 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
+4 -7
View File
@@ -488,14 +488,11 @@ else
rc_input start $RC_INPUT_ARGS
# Manages USB interface
if param greater -s SYS_USB_AUTO -1
if ! cdcacm_autostart start
then
if ! cdcacm_autostart start
then
sercon
echo "Starting MAVLink on /dev/ttyACM0"
mavlink start -d /dev/ttyACM0
fi
sercon
echo "Starting MAVLink on /dev/ttyACM0"
mavlink start -d /dev/ttyACM0
fi
#
+2 -5
View File
@@ -87,20 +87,17 @@ def process_target(px4board_file, target_name):
if platform not in excluded_platforms:
# get the container based on the platform and toolchain
container = 'ghcr.io/px4/px4-dev:main'
if platform == 'posix':
container = 'px4io/px4-dev-base-focal:2021-09-08'
group = 'base'
if toolchain:
if toolchain.startswith('aarch64'):
container = 'px4io/px4-dev-aarch64:2022-08-12'
group = 'aarch64'
elif toolchain == 'arm-linux-gnueabihf':
container = 'px4io/px4-dev-armhf:2023-06-26'
group = 'armhf'
else:
if verbose: print(f'unmatched toolchain: {toolchain}')
elif platform == 'nuttx':
container = 'px4io/px4-dev-nuttx-focal:2022-08-12'
group = 'nuttx'
else:
if verbose: print(f'unmatched platform: {platform}')
@@ -124,7 +121,7 @@ if(verbose):
# - Events
metadata_targets = ['airframe_metadata', 'parameters_metadata', 'extract_events']
grouped_targets['base'] = {}
grouped_targets['base']['container'] = 'px4io/px4-dev-base-focal:2021-09-08'
grouped_targets['base']['container'] = 'ghcr.io/px4/px4-dev:main'
grouped_targets['base']['manufacturers'] = {}
grouped_targets['base']['manufacturers']['px4'] = []
grouped_targets['base']['manufacturers']['px4'] += metadata_targets
+22 -19
View File
@@ -4,8 +4,9 @@ mkdir artifacts
cp **/**/*.px4 artifacts/
cp **/**/*.elf artifacts/
for build_dir_path in build/*/ ; do
build_dir_path=${build_dir_path::${#build_dir_path}-1}
build_dir=${build_dir_path#*/}
build_dir=${build_dir::${#build_dir}-1}
target_name=$build_dir
mkdir artifacts/$build_dir
find artifacts/ -maxdepth 1 -type f -name "*$build_dir*"
# Airframe
@@ -26,21 +27,23 @@ for build_dir_path in build/*/ ; do
echo "----------"
done
# general metadata
mkdir artifacts/_general/
cp artifacts/px4_sitl_default/airframes.xml artifacts/_general/
# Airframe
cp artifacts/px4_sitl_default/airframes.xml artifacts/_general/
# Parameters
cp artifacts/px4_sitl_default/parameters.xml artifacts/_general/
cp artifacts/px4_sitl_default/parameters.json artifacts/_general/
cp artifacts/px4_sitl_default/parameters.json.xz artifacts/_general/
# Actuators
cp artifacts/px4_sitl_default/actuators.json artifacts/_general/
cp artifacts/px4_sitl_default/actuators.json.xz artifacts/_general/
# Events
cp artifacts/px4_sitl_default/events/all_events.json.xz artifacts/_general/
# ROS 2 msgs
cp artifacts/px4_sitl_default/events/all_events.json.xz artifacts/_general/
# Module Docs
ls -la artifacts/_general/
if [ -d artifacts/px4_sitl_default ]; then
# general metadata
mkdir artifacts/_general/
cp artifacts/px4_sitl_default/airframes.xml artifacts/_general/
# Airframe
cp artifacts/px4_sitl_default/airframes.xml artifacts/_general/
# Parameters
cp artifacts/px4_sitl_default/parameters.xml artifacts/_general/
cp artifacts/px4_sitl_default/parameters.json artifacts/_general/
cp artifacts/px4_sitl_default/parameters.json.xz artifacts/_general/
# Actuators
cp artifacts/px4_sitl_default/actuators.json artifacts/_general/
cp artifacts/px4_sitl_default/actuators.json.xz artifacts/_general/
# Events
cp artifacts/px4_sitl_default/events/all_events.json.xz artifacts/_general/
# ROS 2 msgs
cp artifacts/px4_sitl_default/events/all_events.json.xz artifacts/_general/
# Module Docs
ls -la artifacts/_general/
fi
+10 -2
View File
@@ -1,19 +1,27 @@
#!/bin/bash
GREEN='\033[0;32m'
NC='\033[0m' # No Color
FILE_DESCRIPTOR="${GREEN}[docker-entrypoint.sh]${NC}"
echo -e "$FILE_DESCRIPTOR Starting"
# Start virtual X server in the background
# - DISPLAY default is :99, set in dockerfile
# - Users can override with `-e DISPLAY=` in `docker run` command to avoid
# running Xvfb and attach their screen
if [[ -x "$(command -v Xvfb)" && "$DISPLAY" == ":99" ]]; then
echo "[docker-entrypoint.sh] Starting Xvfb"
echo -e "$FILE_DESCRIPTOR Starting Xvfb"
Xvfb :99 -screen 0 1600x1200x24+32 &
fi
# Check if the ROS_DISTRO is passed and use it
# to source the ROS environment
if [ -n "${ROS_DISTRO}" ]; then
echo "[docker-entrypoint.sh] ROS: ${ROS_DISTRO}"
echo -e "$FILE_DESCRIPTOR ROS: ${ROS_DISTRO}"
source "/opt/ros/$ROS_DISTRO/setup.bash"
fi
echo -e "$FILE_DESCRIPTOR ($( uname -m ))"
exec "$@"
+32 -15
View File
@@ -27,9 +27,12 @@ do
fi
done
echo "[ubuntu.sh] Starting..."
echo "[ubuntu.sh] arch: ${GREEN}$INSTALL_ARCH${NC}"
# detect if running in docker
if [ -f /.dockerenv ]; then
echo "Running within docker, installing initial dependencies";
echo "[ubuntu.sh] Running within docker, installing initial dependencies";
apt-get --quiet -y update && DEBIAN_FRONTEND=noninteractive apt-get --quiet -y install \
ca-certificates \
gnupg \
@@ -47,7 +50,7 @@ DIR=$( cd "$( dirname "${BASH_SOURCE[0]}" )" && pwd )
# check requirements.txt exists (script not run in source tree)
REQUIREMENTS_FILE="requirements.txt"
if [[ ! -f "${DIR}/${REQUIREMENTS_FILE}" ]]; then
echo "FAILED: ${REQUIREMENTS_FILE} needed in same directory as ubuntu.sh (${DIR})."
echo "[ubuntu.sh] FAILED: ${REQUIREMENTS_FILE} needed in same directory as ubuntu.sh (${DIR})."
return 1
fi
@@ -55,10 +58,8 @@ fi
# check ubuntu version
# otherwise warn and point to docker?
UBUNTU_RELEASE="`lsb_release -rs`"
echo "Ubuntu ${UBUNTU_RELEASE}"
echo
echo "Installing PX4 general dependencies"
echo "[ubuntu.sh] Ubuntu ${GREEN}${UBUNTU_RELEASE}${NC}"
echo "[ubuntu.sh] Installing PX4 general dependencies"
sudo apt-get update -y --quiet
sudo DEBIAN_FRONTEND=noninteractive apt-get -y --quiet --no-install-recommends install \
@@ -91,7 +92,7 @@ sudo DEBIAN_FRONTEND=noninteractive apt-get -y --quiet --no-install-recommends i
# Python3 dependencies
echo
echo "Installing PX4 Python3 dependencies"
echo "[ubuntu.sh] Installing PX4 Python3 dependencies"
PYTHON_VERSION=$(python3 --version 2>&1 | awk '{print $2}')
REQUIRED_VERSION="3.11"
if [[ "$(printf '%s\n' "$REQUIRED_VERSION" "$PYTHON_VERSION" | sort -V | head -n1)" == "$REQUIRED_VERSION" ]]; then
@@ -109,8 +110,8 @@ fi
if [[ $INSTALL_NUTTX == "true" ]]; then
echo
echo "Installing NuttX dependencies"
echo "[ubuntu.sh] NuttX Installing Dependencies"
sudo apt-get update -y --quiet
sudo DEBIAN_FRONTEND=noninteractive apt-get -y --quiet --no-install-recommends install \
automake \
binutils-dev \
@@ -118,9 +119,6 @@ if [[ $INSTALL_NUTTX == "true" ]]; then
build-essential \
curl \
flex \
g++-multilib \
gcc-arm-none-eabi \
gcc-multilib \
gdb-multiarch \
genromfs \
gettext \
@@ -147,6 +145,25 @@ if [[ $INSTALL_NUTTX == "true" ]]; then
vim-common \
;
echo
echo "[ubuntu.sh] NuttX Installing Dependencies ($INSTALL_ARCH)"
if [[ "${INSTALL_ARCH}" == "x86_64" ]]; then
sudo DEBIAN_FRONTEND=noninteractive apt-get -y --quiet --no-install-recommends install \
g++-multilib \
gcc-arm-none-eabi \
gcc-multilib \
;
fi
if [[ "${INSTALL_ARCH}" == "aarch64" ]]; then
sudo DEBIAN_FRONTEND=noninteractive apt-get -y --quiet --no-install-recommends install \
g++-aarch64-linux-gnu \
g++-arm-linux-gnueabihf \
;
fi
if [ -n "$USER" ]; then
# add user to dialout group (serial port access)
sudo usermod -aG dialout $USER
@@ -157,7 +174,7 @@ fi
if [[ $INSTALL_SIM == "true" ]]; then
echo
echo "Installing PX4 simulation dependencies"
echo "[ubuntu.sh] Installing PX4 simulation dependencies"
# General simulation dependencies
sudo DEBIAN_FRONTEND=noninteractive apt-get -y --quiet --no-install-recommends install \
@@ -182,8 +199,8 @@ if [[ $INSTALL_SIM == "true" ]]; then
fi
else
# Expects Ubuntu 22.04 > by default
echo "Gazebo (Harmonic) will be installed"
echo "Earlier versions will be removed"
echo "[ubuntu.sh] Gazebo (Harmonic) will be installed"
echo "[ubuntu.sh] Earlier versions will be removed"
# Add Gazebo binary repository
sudo wget https://packages.osrfoundation.org/gazebo.gpg -O /usr/share/keyrings/pkgs-osrf-archive-keyring.gpg
echo "deb [arch=$(dpkg --print-architecture) signed-by=/usr/share/keyrings/pkgs-osrf-archive-keyring.gpg] http://packages.osrfoundation.org/gazebo/ubuntu-stable $(lsb_release -cs) main" | sudo tee /etc/apt/sources.list.d/gazebo-stable.list > /dev/null
@@ -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::SOURCE_POWER_MODULE};
Battery _battery{1, nullptr, SYSLINK_BATTERY_STATUS_INTERVAL_US, battery_status_s::BATTERY_SOURCE_POWER_MODULE};
int32_t _rssi;
battery_state _bstate;
@@ -207,15 +207,15 @@ void GhstRc::Run()
if (new_bytes > 0) {
_bytes_rx += new_bytes;
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,
int8_t ghst_rssi = -1;
bool rc_updated = ghst_parse(cycle_timestamp, &_rcs_buf[0], new_bytes, &_raw_rc_values[0], &ghst_rssi,
&_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, link_stats.rssi_pct);
fill_rc_in(_raw_rc_count, _raw_rc_values, cycle_timestamp, false, false, 0, ghst_rssi);
// ghst telemetry works on fmu-v5
// on other Pixhawk (-related) boards we cannot write to the RC UART
-2
View File
@@ -50,9 +50,7 @@ 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
-3
View File
@@ -18,6 +18,3 @@ 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
+22 -22
View File
@@ -12,9 +12,9 @@ float32 time_remaining_s # predicted time in seconds remaining until battery i
float32 temperature # Temperature of the battery in degrees Celcius, NaN if unknown
uint8 cell_count # Number of cells, 0 if unknown
uint8 SOURCE_POWER_MODULE = 0
uint8 SOURCE_EXTERNAL = 1
uint8 SOURCE_ESCS = 2
uint8 BATTERY_SOURCE_POWER_MODULE = 0
uint8 BATTERY_SOURCE_EXTERNAL = 1
uint8 BATTERY_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 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_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 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!
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!
uint16 faults # Smart battery supply status/fault flags (bitmask) for health indication.
uint8 warning # Current battery warning
+6 -6
View File
@@ -87,13 +87,13 @@ uint8 hil_state
uint8 HIL_STATE_OFF = 0
uint8 HIL_STATE_ON = 1
# Current vehicle locomotion method. A vehicle can have different methods (e.g. VTOL transitions from RW to FW method)
# If it's a VTOL, then the value will be VEHICLE_TYPE_ROTARY_WING while flying as a multicopter, and VEHICLE_TYPE_FIXED_WING when flying as a fixed-wing
uint8 vehicle_type
uint8 VEHICLE_TYPE_ROTARY_WING = 0
uint8 VEHICLE_TYPE_FIXED_WING = 1
uint8 VEHICLE_TYPE_ROVER = 2
uint8 VEHICLE_TYPE_BOAT = 5
uint8 VEHICLE_TYPE_UNKNOWN = 0
uint8 VEHICLE_TYPE_ROTARY_WING = 1
uint8 VEHICLE_TYPE_FIXED_WING = 2
uint8 VEHICLE_TYPE_ROVER = 3
uint8 VEHICLE_TYPE_AIRSHIP = 4
uint8 FAILSAFE_DEFER_STATE_DISABLED = 0
uint8 FAILSAFE_DEFER_STATE_ENABLED = 1
+2 -16
View File
@@ -47,7 +47,7 @@ VoxlEsc::VoxlEsc() :
_mixing_output{"VOXL_ESC", VOXL_ESC_OUTPUT_CHANNELS, *this, MixingOutput::SchedulingPolicy::Auto, false, false},
_cycle_perf(perf_alloc(PC_ELAPSED, MODULE_NAME": cycle")),
_output_update_perf(perf_alloc(PC_INTERVAL, MODULE_NAME": output update interval")),
_battery(1, nullptr, _battery_report_interval, battery_status_s::SOURCE_POWER_MODULE)
_battery(1, nullptr, _battery_report_interval, battery_status_s::BATTERY_SOURCE_POWER_MODULE)
{
_device = VOXL_ESC_DEFAULT_PORT;
@@ -1334,20 +1334,6 @@ 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;
@@ -1636,7 +1622,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,7 +49,6 @@
#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>
@@ -213,7 +212,6 @@ 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)};
+130 -36
View File
@@ -42,7 +42,18 @@ int ADS1115::init()
return ret;
}
readChannel(Channel::A0); // prepare for the first measure.
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.
ScheduleOnInterval(SAMPLE_INTERVAL / 4, SAMPLE_INTERVAL / 4);
@@ -51,69 +62,152 @@ int ADS1115::init()
int ADS1115::probe()
{
// 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);
uint8_t buf[2] = {};
int ret = readReg(ADDRESSPOINTER_REG_CONFIG, buf, 2);
if (ret != PX4_OK) {
DEVICE_DEBUG("lo_thresh read failed (%i)", ret);
DEVICE_DEBUG("readReg failed (%i)", ret);
return ret;
}
ret = readReg(ADDRESSPOINTER_REG_HI_THRESH, parts.high, 2);
if (ret != PX4_OK) {
DEVICE_DEBUG("hi_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;
}
if (threshold == DEFAULT) {
return PX4_OK;
}
DEVICE_DEBUG("ADS1115 not found");
return PX4_ERROR;
return PX4_OK;
}
int ADS1115::readChannel(ADS1115::Channel ch)
int ADS1115::setChannel(ADS1115::ChannelSelection ch)
{
uint8_t buf[2];
buf[0] = CONFIG_HIGH_OS_START_SINGLE | uint8_t(ch) | CONFIG_HIGH_PGA_6144 | CONFIG_HIGH_MODE_SS;
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;
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
}
int ADS1115::isSampleReady()
bool ADS1115::isSampleReady()
{
uint8_t buf[1] = {0x00};
if (readReg(ADDRESSPOINTER_REG_CONFIG, buf, 1) != PX4_OK) { return -1; } // Pull config register
if (readReg(ADDRESSPOINTER_REG_CONFIG, buf, 1) != 0) { return false; } // Pull config register
return (buf[0] & (uint8_t) 0x80) ? 1 : 0;
return (buf[0] & (uint8_t) 0x80);
}
ADS1115::Channel ADS1115::getMeasurement(int16_t *value)
ADS1115::ChannelSelection ADS1115::getMeasurement(int16_t *value)
{
uint8_t buf[2] = {0x00};
readReg(ADDRESSPOINTER_REG_CONFIG, buf, 1); // Pull config register
ChannelSelection channel;
if (readReg(ADDRESSPOINTER_REG_CONFIG, buf, 1) != PX4_OK) { return Channel::Invalid; }
switch ((buf[0] & (uint8_t) 0x70) >> 4) {
case 0x04:
channel = A0;
break;
const auto channel{Channel(buf[0] & CONFIG_HIGH_MUX_P3NG)};
case 0x05:
channel = A1;
break;
if (readReg(ADDRESSPOINTER_REG_CONVERSATION, buf, 2) != PX4_OK) { return Channel::Invalid; }
case 0x06:
channel = A2;
break;
*value = int16_t((buf[0] << 8) | buf[1]);
case 0x07:
channel = A3;
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;
}
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;
}
+19 -20
View File
@@ -93,6 +93,9 @@
#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;
/*
@@ -124,39 +127,35 @@ 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 _comms_errors;
perf_counter_t _cycle_perf;
uint8_t _channel_cycle_mask{0};
int _channel_cycle_count{0};
static constexpr uint8_t MAX_READY_COUNTER{20};
uint8_t _ready_counter{MAX_READY_COUNTER};
bool _reported_ready_last_cycle{false};
// ADS1115 logic part
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,
enum ChannelSelection {
Invalid = -1, A0 = 0, A1, A2, A3
};
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();
/* set multiplexer to specific channel */
int setChannel(ChannelSelection ch);
/* return true if sample result is valid */
bool isSampleReady();
/*
* get adc sample. return the channel being measured.
* Invalid indicates sample failure.
*/
Channel getMeasurement(int16_t *value);
ChannelSelection getMeasurement(int16_t *value);
/*
* get adc sample and automatically switch to next channel and start another measurement
*/
ChannelSelection cycleMeasure(int16_t *value);
int readReg(uint8_t addr, uint8_t *buf, size_t len);
+43 -45
View File
@@ -45,8 +45,7 @@
ADS1115::ADS1115(const I2CSPIDriverConfig &config) :
I2C(config),
I2CSPIDriver(config),
_cycle_perf(perf_alloc(PC_ELAPSED, MODULE_NAME": single-sample")),
_comms_errors(perf_alloc(PC_COUNT, MODULE_NAME": comms errors"))
_cycle_perf(perf_alloc(PC_ELAPSED, MODULE_NAME": single-sample"))
{
_adc_report.device_id = this->get_device_id();
_adc_report.resolution = 32768;
@@ -62,7 +61,6 @@ ADS1115::~ADS1115()
{
ScheduleClear();
perf_free(_cycle_perf);
perf_free(_comms_errors);
}
void ADS1115::exit_and_cleanup()
@@ -79,55 +77,56 @@ void ADS1115::RunImpl()
perf_begin(_cycle_perf);
const int ready = isSampleReady();
_adc_report.timestamp = hrt_absolute_time();
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);
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;
}
// Find the next unread channel in the bitmask
uint8_t next_index{0};
int16_t buf;
ADS1115::ChannelSelection ch = cycleMeasure(&buf);
++_channel_cycle_count;
for (; next_index < 4 && (_channel_cycle_mask & (1u << next_index)); next_index++) {}
switch (ch) {
case ADS1115::A0:
_adc_report.channel_id[0] = 0;
_adc_report.raw_data[0] = buf;
break;
readChannel(u2ch(next_index));
case ADS1115::A1:
_adc_report.channel_id[1] = 1;
_adc_report.raw_data[1] = buf;
break;
if (_channel_cycle_mask == 0b1111) {
_channel_cycle_mask = 0;
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;
_to_adc_report.publish(_adc_report);
}
} 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);
} else {
if (_reported_ready_last_cycle) {
_reported_ready_last_cycle = false;
PX4_ERR("ADS1115: not ready. Device lost?");
}
}
perf_end(_cycle_perf);
@@ -152,7 +151,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);
@@ -164,7 +163,6 @@ void ADS1115::print_status()
{
I2CSPIDriverBase::print_status();
perf_print_counter(_cycle_perf);
perf_print_counter(_comms_errors);
}
extern "C" int ads1115_main(int argc, char *argv[])
+5 -5
View File
@@ -172,19 +172,19 @@ void BATT_SMBUS::RunImpl()
// Check if max lifetime voltage delta is greater than allowed.
if (_lifetime_max_delta_cell_voltage > BATT_CELL_VOLTAGE_THRESHOLD_FAILED) {
new_report.warning = battery_status_s::WARNING_CRITICAL;
new_report.warning = battery_status_s::BATTERY_WARNING_CRITICAL;
} else if (new_report.remaining > _low_thr) {
new_report.warning = battery_status_s::WARNING_NONE;
new_report.warning = battery_status_s::BATTERY_WARNING_NONE;
} else if (new_report.remaining > _crit_thr) {
new_report.warning = battery_status_s::WARNING_LOW;
new_report.warning = battery_status_s::BATTERY_WARNING_LOW;
} else if (new_report.remaining > _emergency_thr) {
new_report.warning = battery_status_s::WARNING_CRITICAL;
new_report.warning = battery_status_s::BATTERY_WARNING_CRITICAL;
} else {
new_report.warning = battery_status_s::WARNING_EMERGENCY;
new_report.warning = battery_status_s::BATTERY_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_ROTARY_WING};
typeof(px4::msg::VehicleStatus::vehicle_type) _vehicle_type{px4::msg::VehicleStatus::VEHICLE_TYPE_UNKNOWN};
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,15 +125,10 @@ int AerotennaULanding::collect()
index--;
}
} else {
return -EAGAIN;
}
if (!checksum_passed) {
perf_count(_comms_errors);
perf_end(_sample_perf);
return -EBADMSG;
return -EAGAIN;
}
_px4_rangefinder.update(timestamp_sample, distance_m);
@@ -56,7 +56,7 @@
using namespace time_literals;
#define ULANDING_MEASURE_INTERVAL 12_ms
#define ULANDING_MEASURE_INTERVAL 10_ms
#define ULANDING_MAX_DISTANCE 50.0f
#define ULANDING_MIN_DISTANCE 0.315f
#define ULANDING_VERSION 1
+1 -1
View File
@@ -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::SOURCE_POWER_MODULE)
_battery(battery_index, this, INA220_SAMPLE_INTERVAL_US, battery_status_s::BATTERY_SOURCE_POWER_MODULE)
{
float fvalue = MAX_CURRENT;
_max_current = fvalue;
+1 -1
View File
@@ -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::SOURCE_POWER_MODULE)
_battery(battery_index, this, INA226_SAMPLE_INTERVAL_US, battery_status_s::BATTERY_SOURCE_POWER_MODULE)
{
float fvalue = MAX_CURRENT;
_max_current = fvalue;
+1 -1
View File
@@ -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::SOURCE_POWER_MODULE)
_battery(battery_index, this, INA228_SAMPLE_INTERVAL_US, battery_status_s::BATTERY_SOURCE_POWER_MODULE)
{
float fvalue = MAX_CURRENT;
_max_current = fvalue;
+1 -1
View File
@@ -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::SOURCE_POWER_MODULE)
_battery(battery_index, this, INA238_SAMPLE_INTERVAL_US, battery_status_s::BATTERY_SOURCE_POWER_MODULE)
{
float fvalue = DEFAULT_MAX_CURRENT;
_max_current = fvalue;
+1 -1
View File
@@ -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::SOURCE_POWER_MODULE)
_battery(1, this, _meas_interval_us, battery_status_s::BATTERY_SOURCE_POWER_MODULE)
{
}
+6 -7
View File
@@ -34,7 +34,6 @@
#include "GhstRc.hpp"
#include <termios.h>
#include <math.h>
GhstRc::GhstRc(const char *device) :
ModuleParams(nullptr),
@@ -175,18 +174,16 @@ void GhstRc::Run()
if (newBytes > 0) {
uint16_t raw_rc_values[input_rc_s::RC_INPUT_MAX_CHANNELS] {};
uint16_t raw_rc_count = 0;
ghstLinkStatistics_t link_stats = { .rssi_pct = -1, .rssi_dbm = NAN, .link_quality = 0 };
int8_t ghst_rssi = -1;
if (ghst_parse(cycle_timestamp, &rcs_buf[0], newBytes, &raw_rc_values[0], &link_stats,
if (ghst_parse(cycle_timestamp, &rcs_buf[0], newBytes, &raw_rc_values[0], &ghst_rssi,
&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 = link_stats.rssi_pct;
input_rc.link_quality = link_stats.link_quality;
input_rc.rssi_dbm = link_stats.rssi_dbm;
input_rc.rssi = ghst_rssi;
input_rc.input_source = input_rc_s::RC_INPUT_SOURCE_PX4FMU_GHST;
unsigned valid_chans = 0;
@@ -203,11 +200,13 @@ 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);
+3 -4
View File
@@ -762,15 +762,14 @@ void RCInput::Run()
// parse new data
if (newBytes > 0) {
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,
int8_t ghst_rssi = -1;
rc_updated = ghst_parse(cycle_timestamp, &_rcs_buf[0], newBytes, &_raw_rc_values[0], &ghst_rssi,
&_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, link_stats.rssi_pct);
int32_t valid_chans = fill_rc_in(_raw_rc_count, _raw_rc_values, cycle_timestamp, false, false, 0, ghst_rssi);
// ghst telemetry works on fmu-v5
// on other Pixhawk (-related) boards we cannot write to the RC UART
+5 -5
View File
@@ -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::WARNING_CRITICAL;
// new_report.warning = battery_status_s::BATTERY_WARNING_CRITICAL;
if (new_report.remaining > _low_thr) {
new_report.warning = battery_status_s::WARNING_NONE;
new_report.warning = battery_status_s::BATTERY_WARNING_NONE;
} else if (new_report.remaining > _crit_thr) {
new_report.warning = battery_status_s::WARNING_LOW;
new_report.warning = battery_status_s::BATTERY_WARNING_LOW;
} else if (new_report.remaining > _emergency_thr) {
new_report.warning = battery_status_s::WARNING_CRITICAL;
new_report.warning = battery_status_s::BATTERY_WARNING_CRITICAL;
} else {
new_report.warning = battery_status_s::WARNING_EMERGENCY;
new_report.warning = battery_status_s::BATTERY_WARNING_EMERGENCY;
}
new_report.interface_error = perf_event_count(_interface->_interface_errors);
+7 -7
View File
@@ -44,7 +44,7 @@ UavcanBatteryBridge::UavcanBatteryBridge(uavcan::INode &node) :
ModuleParams(nullptr),
_sub_battery(node),
_sub_battery_aux(node),
_warning(battery_status_s::WARNING_NONE),
_warning(battery_status_s::BATTERY_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::WARNING_EMERGENCY)) {
_warning = battery_status_s::WARNING_EMERGENCY;
if (remaining < _param_bat_emergen_thr.get() || (_warning == battery_status_s::BATTERY_WARNING_EMERGENCY)) {
_warning = battery_status_s::BATTERY_WARNING_EMERGENCY;
} 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_crit_thr.get() || (_warning == battery_status_s::BATTERY_WARNING_CRITICAL)) {
_warning = battery_status_s::BATTERY_WARNING_CRITICAL;
} else if (remaining < _param_bat_low_thr.get() || (_warning == battery_status_s::WARNING_LOW)) {
_warning = battery_status_s::WARNING_LOW;
} else if (remaining < _param_bat_low_thr.get() || (_warning == battery_status_s::BATTERY_WARNING_LOW)) {
_warning = battery_status_s::BATTERY_WARNING_LOW;
}
}
+4 -4
View File
@@ -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::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 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 *_battery[battery_status_s::MAX_INSTANCES] = { &battery1, &battery2, &battery3, &battery4 };
};
@@ -100,12 +100,10 @@ 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 - tolerance) {
} else if (dist.current_distance < dist.min_distance) {
range_sensor.reading_type = uavcan::equipment::range_sensor::Measurement::READING_TYPE_TOO_CLOSE;
} else if (dist.signal_quality != 0) {
+5 -5
View File
@@ -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::WARNING_EMERGENCY;
return battery_status_s::BATTERY_WARNING_EMERGENCY;
} else if (state_of_charge < _params.crit_thr) {
return battery_status_s::WARNING_CRITICAL;
return battery_status_s::BATTERY_WARNING_CRITICAL;
} else if (state_of_charge < _params.low_thr) {
return battery_status_s::WARNING_LOW;
return battery_status_s::BATTERY_WARNING_LOW;
} else {
return battery_status_s::WARNING_NONE;
return battery_status_s::BATTERY_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::FAULT_SPIKES);
faults |= (1 << battery_status_s::BATTERY_FAULT_SPIKES);
}
return faults;
+1 -1
View File
@@ -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::WARNING_NONE};
uint8_t _warning{battery_status_s::BATTERY_WARNING_NONE};
hrt_abstime _last_timestamp{0};
bool _armed{false};
bool _vehicle_status_is_fw{false};
@@ -1128,11 +1128,6 @@ 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;
+8 -14
View File
@@ -56,7 +56,6 @@
#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"
@@ -78,8 +77,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/LQ
static ghstLinkStatistics_t last_link_stats = { .rssi_pct = -1, .rssi_dbm = NAN, .link_quality = 0 };
// only RSSI frame contains value of RSSI, if it is not received, send last received RSSI
static int8_t ghst_rssi = -1;
static ghst_frame_t &ghst_frame = rc_decode_buf.ghst_frame;
static uint32_t current_frame_position = 0U;
@@ -90,8 +89,7 @@ static uint16_t prev_rc_vals[GHST_MAX_NUM_CHANNELS];
/**
* parse the current ghst_frame buffer
*/
static bool ghst_parse_buffer(uint16_t *values, ghstLinkStatistics_t *link_stats, uint16_t *num_values,
uint16_t max_channels);
static bool ghst_parse_buffer(uint16_t *values, int8_t *rssi, uint16_t *num_values, uint16_t max_channels);
int ghst_config(int uart_fd)
{
@@ -116,7 +114,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,
ghstLinkStatistics_t *link_stats, uint16_t *num_values, uint16_t max_channels)
int8_t *rssi, uint16_t *num_values, uint16_t max_channels)
{
bool success = false;
uint8_t *ghst_frame_ptr = (uint8_t *)&ghst_frame;
@@ -147,7 +145,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, link_stats, num_values, max_channels)) {
if (ghst_parse_buffer(values, rssi, num_values, max_channels)) {
success = true;
}
}
@@ -184,8 +182,7 @@ static uint16_t convert_channel_value(unsigned int chan_value)
return converted_chan_value;
}
static bool ghst_parse_buffer(uint16_t *values, ghstLinkStatistics_t *link_stats, uint16_t *num_values,
uint16_t max_channels)
static bool ghst_parse_buffer(uint16_t *values, int8_t *rssi, uint16_t *num_values, uint16_t max_channels)
{
uint8_t *ghst_frame_ptr = (uint8_t *)&ghst_frame;
@@ -302,16 +299,13 @@ static bool ghst_parse_buffer(uint16_t *values, ghstLinkStatistics_t *link_stats
} 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
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
ghst_rssi = spek_dbm_to_percent(static_cast<int8_t>(rssiValues->rssidBm));
} else {
GHST_DEBUG("Frame type: %u", ghst_frame.type);
}
*link_stats = last_link_stats;
*rssi = ghst_rssi;
memcpy(prev_rc_vals, values, sizeof(uint16_t) * GHST_MAX_NUM_CHANNELS);
+1 -8
View File
@@ -106,13 +106,6 @@ 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
@@ -134,7 +127,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,
ghstLinkStatistics_t *link_stats, uint16_t *num_values, uint16_t max_channels);
int8_t *rssi, uint16_t *num_values, uint16_t max_channels);
/**
+2 -2
View File
@@ -159,7 +159,7 @@ bool RCTest::ghstTest()
uint16_t rc_values[max_channels];
uint16_t num_values = 0;
int line_counter = 1;
ghstLinkStatistics_t link_stats;
int8_t ghst_rssi = -1;
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, &link_stats, &num_values, max_channels);
bool result = ghst_parse(now, frame, frame_len, rc_values, &ghst_rssi, &num_values, max_channels);
if (result) {
has_decoded_values = true;
+207
View File
@@ -0,0 +1,207 @@
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
-255
View File
@@ -1,255 +0,0 @@
/****************************************************************************
*
* 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);
+1 -1
View File
@@ -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_ROTARY_WING}; /**< the defined vehicle type to use for the calculation*/
uint8_t _vehicle_type{vehicle_status_s::VEHICLE_TYPE_UNKNOWN}; /**< 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 */
-12
View File
@@ -240,18 +240,6 @@ 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::SOURCE_POWER_MODULE, 0),
_battery1(1, this, SAMPLE_INTERVAL_US, battery_status_s::BATTERY_SOURCE_POWER_MODULE, 0),
#if BOARD_NUMBER_BRICKS > 1
_battery2(2, this, SAMPLE_INTERVAL_US, battery_status_s::SOURCE_POWER_MODULE, 1),
_battery2(2, this, SAMPLE_INTERVAL_US, battery_status_s::BATTERY_SOURCE_POWER_MODULE, 1),
#endif
_loop_perf(perf_alloc(PC_ELAPSED, MODULE_NAME))
{
+13 -26
View File
@@ -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
&& !is_ground_vehicle(_vehicle_status)) {
&& _vehicle_status.vehicle_type != vehicle_status_s::VEHICLE_TYPE_ROVER) {
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,16 +583,6 @@ 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) {
@@ -698,7 +688,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_ROTARY_WING;
_vehicle_status.vehicle_type = vehicle_status_s::VEHICLE_TYPE_UNKNOWN;
_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();
@@ -1706,7 +1696,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, false)) {
if (!_user_mode_intention.change(action_request.mode, ModeChangeSource::User, true)) {
printRejectMode(action_request.mode);
}
@@ -1733,6 +1723,7 @@ 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) {
@@ -1741,11 +1732,8 @@ void Commander::updateParameters()
} else if (is_fixed) {
_vehicle_status.vehicle_type = vehicle_status_s::VEHICLE_TYPE_FIXED_WING;
} else if (is_rover_type(_vehicle_status)) {
} else if (is_ground) {
_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);
@@ -1901,7 +1889,8 @@ 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.hil_state == vehicle_status_s::HIL_STATE_ON)
_actuator_armed.lockdown = ((_vehicle_status.nav_state == _vehicle_status.NAVIGATION_STATE_TERMINATION)
|| (_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);
@@ -2204,13 +2193,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::WARNING_CRITICAL)) {
(_battery_warning == battery_status_s::BATTERY_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::WARNING_LOW)) {
(_battery_warning == battery_status_s::BATTERY_WARNING_LOW)) {
/* play tune on battery warning */
set_tune(tune_control_s::TUNE_ID_BATTERY_WARNING_SLOW);
@@ -2504,10 +2493,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::WARNING_LOW) {
} else if (battery_warning == battery_status_s::BATTERY_WARNING_LOW) {
led_color = led_control_s::COLOR_AMBER;
} else if (battery_warning == battery_status_s::WARNING_CRITICAL) {
} else if (battery_warning == battery_status_s::BATTERY_WARNING_CRITICAL) {
led_color = led_control_s::COLOR_RED;
} else {
@@ -2878,7 +2867,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::WARNING_EMERGENCY) {
if (_failsafe_flags.battery_warning == battery_status_s::BATTERY_WARNING_EMERGENCY) {
#if defined(BOARD_HAS_POWER_CONTROL)
if (!isArmed() && (px4_shutdown_request(60_s) == 0)) {
@@ -2913,15 +2902,13 @@ 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_BOAT)
&& (_vehicle_status.vehicle_type == vehicle_status_s::VEHICLE_TYPE_ROTARY_WING)
) {
bool override_enabled = false;
+1 -2
View File
@@ -262,7 +262,7 @@ private:
hrt_abstime _last_health_and_arming_check{0};
uint8_t _battery_warning{battery_status_s::WARNING_NONE};
uint8_t _battery_warning{battery_status_s::BATTERY_WARNING_NONE};
bool _failsafe_user_override_request{false}; ///< override request due to stick movements
@@ -275,7 +275,6 @@ 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,7 +42,6 @@ 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,7 +46,6 @@
#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"
@@ -131,7 +130,6 @@ 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;
@@ -171,7 +169,6 @@ 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::FAULT_COUNT == (static_cast<uint8_t>(battery_fault_reason_t::_max) + 1)
static_assert(battery_status_s::BATTERY_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::WARNING_NONE;
reporter.failsafeFlags().battery_warning = battery_status_s::BATTERY_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::WARNING_NONE;
uint8_t worst_warning = battery_status_s::BATTERY_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::WARNING_CRITICAL;
worst_warning = battery_status_s::BATTERY_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::WARNING_NONE
&& reporter.failsafeFlags().battery_warning < battery_status_s::WARNING_FAILED;
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 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::WARNING_CRITICAL;
const bool critical_or_higher = reporter.failsafeFlags().battery_warning >= battery_status_s::BATTERY_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::WARNING_LOW:
case battery_status_s::BATTERY_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::WARNING_CRITICAL:
case battery_status_s::BATTERY_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::WARNING_EMERGENCY:
case battery_status_s::BATTERY_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::WARNING_FAILED;
|| reporter.failsafeFlags().battery_warning == battery_status_s::BATTERY_WARNING_FAILED;
if (reporter.failsafeFlags().battery_unhealthy
&& !is_required_battery_missing && !battery_has_fault) { // missing batteries and faults are reported above already
@@ -1,68 +0,0 @@
/****************************************************************************
*
* 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");
}
}
@@ -1,55 +0,0 @@
/****************************************************************************
*
* 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,14 +36,6 @@
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)) {
@@ -85,11 +77,7 @@ void PowerChecks::checkAndReport(const Context &context, Report &reporter)
const float low_error_threshold = 4.7f;
const float high_error_threshold = 5.4f;
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()) {
if (avionics_power_rail_voltage < low_error_threshold) {
/* EVENT
* @description
@@ -108,7 +96,7 @@ void PowerChecks::checkAndReport(const Context &context, Report &reporter)
(double)avionics_power_rail_voltage);
}
} else if (_voltage_high_hysteresis.get_state()) {
} else if (avionics_power_rail_voltage > high_error_threshold) {
/* EVENT
* @description
* Check the voltage supply to the FMU, it must be below {2:.2} Volt.
@@ -35,14 +35,13 @@
#include "../Common.hpp"
#include <lib/hysteresis/hysteresis.h>
#include <uORB/Subscription.hpp>
#include <uORB/topics/system_power.h>
class PowerChecks : public HealthAndArmingCheckBase
{
public:
PowerChecks();
PowerChecks() = default;
~PowerChecks() = default;
void checkAndReport(const Context &context, Report &reporter) override;
@@ -50,8 +49,6 @@ 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,6 +45,7 @@ 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,16 +122,6 @@ bool is_ground_vehicle(const vehicle_status_s &current_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 &current_status)
{
return current_status.system_type == VEHICLE_TYPE_GROUND_ROVER;
}
bool is_boat_type(const vehicle_status_s &current_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};
-2
View File
@@ -56,8 +56,6 @@ bool is_vtol(const vehicle_status_s &current_status);
bool is_vtol_tailsitter(const vehicle_status_s &current_status);
bool is_fixed_wing(const vehicle_status_s &current_status);
bool is_ground_vehicle(const vehicle_status_s &current_status);
bool is_rover_type(const vehicle_status_s &current_status);
bool is_boat_type(const vehicle_status_s &current_status);
int buzzer_init(void);
void buzzer_deinit(void);
+10 -10
View File
@@ -192,16 +192,16 @@ FailsafeBase::ActionOptions Failsafe::fromBatteryWarningActParam(int param_value
switch (battery_warning) {
default:
case battery_status_s::WARNING_NONE:
case battery_status_s::BATTERY_WARNING_NONE:
options.action = Action::None;
break;
case battery_status_s::WARNING_LOW:
case battery_status_s::BATTERY_WARNING_LOW:
options.action = Action::Warn;
options.cause = Cause::BatteryLow;
break;
case battery_status_s::WARNING_CRITICAL:
case battery_status_s::BATTERY_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::WARNING_EMERGENCY:
case battery_status_s::BATTERY_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::WARNING_LOW:
case battery_status_s::BATTERY_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::WARNING_LOW));
true, fromBatteryWarningActParam(low_battery_action, battery_status_s::BATTERY_WARNING_LOW));
break;
case battery_status_s::WARNING_CRITICAL:
case battery_status_s::BATTERY_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::WARNING_CRITICAL));
true, fromBatteryWarningActParam(low_battery_action, battery_status_s::BATTERY_WARNING_CRITICAL));
break;
case battery_status_s::WARNING_EMERGENCY:
case battery_status_s::BATTERY_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::WARNING_EMERGENCY));
true, fromBatteryWarningActParam(low_battery_action, battery_status_s::BATTERY_WARNING_EMERGENCY));
break;
default:
-8
View File
@@ -11,11 +11,3 @@ 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
+1 -40
View File
@@ -65,14 +65,12 @@ __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);
@@ -90,7 +88,6 @@ 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,
@@ -99,7 +96,6 @@ 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,
@@ -153,11 +149,9 @@ 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,
@@ -247,7 +241,6 @@ 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)
@@ -325,7 +318,6 @@ _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)
@@ -370,7 +362,6 @@ 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)
@@ -451,7 +442,6 @@ _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)
{
@@ -485,7 +475,6 @@ static int _ram_clear(dm_item_t item)
return result;
}
#ifdef CONFIG_DATAMAN_PERSISTENT_STORAGE
static int
_file_clear(dm_item_t item)
{
@@ -539,9 +528,7 @@ _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)
{
@@ -607,7 +594,6 @@ _file_initialize(unsigned max_offset)
return 0;
}
#endif
static int
_ram_initialize(unsigned max_offset)
@@ -628,14 +614,12 @@ _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()
@@ -649,12 +633,9 @@ 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;
@@ -699,13 +680,10 @@ 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);
@@ -893,7 +871,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 depending on the board:
Multiple backends are supported:
- a file (eg. on the SD card)
- RAM (this is obviously not persistent)
@@ -907,13 +885,9 @@ 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();
}
@@ -956,14 +930,9 @@ 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':
@@ -982,22 +951,16 @@ 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;
}
@@ -1013,10 +976,8 @@ 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();
-1
View File
@@ -38,7 +38,6 @@ 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
+1 -1
View File
@@ -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::SOURCE_ESCS)
_battery(1, this, ESC_BATTERY_INTERVAL_US, battery_status_s::BATTERY_SOURCE_ESCS)
{
}
+2 -2
View File
@@ -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::WARNING_CRITICAL || _critical_battery) {
if (_battery_status_sub.get().warning == battery_status_s::BATTERY_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::WARNING_LOW || _low_battery) {
} else if (_battery_status_sub.get().warning == battery_status_s::BATTERY_WARNING_LOW || _low_battery) {
_led_control.color = led_control_s::COLOR_RED;
_led_control.mode = led_control_s::MODE_FLASH;
_low_battery = true;
@@ -253,15 +253,9 @@ 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);
+4 -13
View File
@@ -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::WARNING_EMERGENCY;
battery_status.warning = battery_status_s::BATTERY_WARNING_EMERGENCY;
} else if (battery_status.remaining < _param_bat_crit_thr.get()) {
battery_status.warning = battery_status_s::WARNING_CRITICAL;
battery_status.warning = battery_status_s::BATTERY_WARNING_CRITICAL;
} else if (battery_status.remaining < _param_bat_low_thr.get()) {
battery_status.warning = battery_status_s::WARNING_LOW;
battery_status.warning = battery_status_s::BATTERY_WARNING_LOW;
}
_battery_pub.publish(battery_status);
@@ -1976,16 +1976,7 @@ 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");
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;
}
_mavlink_tunnel_pub.publish(tunnel);
}
-1
View File
@@ -307,7 +307,6 @@ 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::WARNING_NONE):
case (battery_status_s::BATTERY_WARNING_NONE):
bat_msg.charge_state = MAV_BATTERY_CHARGE_STATE_OK;
break;
case (battery_status_s::WARNING_LOW):
case (battery_status_s::BATTERY_WARNING_LOW):
bat_msg.charge_state = MAV_BATTERY_CHARGE_STATE_LOW;
break;
case (battery_status_s::WARNING_CRITICAL):
case (battery_status_s::BATTERY_WARNING_CRITICAL):
bat_msg.charge_state = MAV_BATTERY_CHARGE_STATE_CRITICAL;
break;
case (battery_status_s::WARNING_EMERGENCY):
case (battery_status_s::BATTERY_WARNING_EMERGENCY):
bat_msg.charge_state = MAV_BATTERY_CHARGE_STATE_EMERGENCY;
break;
case (battery_status_s::WARNING_FAILED):
case (battery_status_s::BATTERY_WARNING_FAILED):
bat_msg.charge_state = MAV_BATTERY_CHARGE_STATE_FAILED;
break;
case (battery_status_s::STATE_UNHEALTHY):
case (battery_status_s::BATTERY_STATE_UNHEALTHY):
bat_msg.charge_state = MAV_BATTERY_CHARGE_STATE_UNHEALTHY;
break;
case (battery_status_s::STATE_CHARGING):
case (battery_status_s::BATTERY_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::WARNING_LOW) {
if (battery.warning > battery_status_s::BATTERY_WARNING_LOW) {
msg->failure_flags |= HL_FAILURE_FLAG_BATTERY;
}
}
+2 -3
View File
@@ -206,9 +206,8 @@ 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
|| _navigator->get_vstatus()->vehicle_type == vehicle_status_s::VEHICLE_TYPE_BOAT)) {
} else if (_mission_item.nav_cmd == NAV_CMD_TAKEOFF
&& _navigator->get_vstatus()->vehicle_type == vehicle_status_s::VEHICLE_TYPE_ROVER) {
// 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;
+1 -2
View File
@@ -1137,8 +1137,7 @@ 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
|| get_vstatus()->vehicle_type == vehicle_status_s::VEHICLE_TYPE_BOAT) {
} else if (get_vstatus()->vehicle_type == vehicle_status_s::VEHICLE_TYPE_ROVER) {
return INFINITY;
} else {
+13 -17
View File
@@ -721,6 +721,10 @@ 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));
@@ -747,7 +751,6 @@ 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:
@@ -904,26 +907,19 @@ Replay::run()
ulog_message_header_s message_header;
replay_file.seekg(_data_section_start);
while (true) {
//we are in the Definition & Data Section Message Header section
//we know the next message must be an ADD_LOGGED_MSG
ReadAndAndAddSubResult res;
do {
replay_file.read((char *)&message_header, ULOG_MSG_HEADER_LEN);
res = readAndAddSubscription(replay_file, message_header.msg_size);
if (!replay_file) {
break;
if (res == ReadAndAndAddSubResult::kFailure) {
PX4_ERR("Failed to read subscription");
return;
}
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);
}
}
} while (res != ReadAndAndAddSubResult::kSuccess);
const uint64_t timestamp_offset = getTimestampOffset();
uint32_t nr_published_messages = 0;
@@ -50,3 +50,5 @@ 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)
@@ -45,7 +45,7 @@
* @min 0
* @max 1000
* @unit Hz
* @reboot_required false
* @reboot_required true
* @group Sensors
*/
PARAM_DEFINE_FLOAT(IMU_GYRO_NF0_FRQ, 0.0f);
@@ -60,7 +60,7 @@ PARAM_DEFINE_FLOAT(IMU_GYRO_NF0_FRQ, 0.0f);
* @min 0
* @max 100
* @unit Hz
* @reboot_required false
* @reboot_required true
* @group Sensors
*/
PARAM_DEFINE_FLOAT(IMU_GYRO_NF0_BW, 20.0f);
@@ -79,7 +79,7 @@ PARAM_DEFINE_FLOAT(IMU_GYRO_NF0_BW, 20.0f);
* @min 0
* @max 1000
* @unit Hz
* @reboot_required false
* @reboot_required true
* @group Sensors
*/
PARAM_DEFINE_FLOAT(IMU_GYRO_NF1_FRQ, 0.0f);
@@ -94,7 +94,7 @@ PARAM_DEFINE_FLOAT(IMU_GYRO_NF1_FRQ, 0.0f);
* @min 0
* @max 100
* @unit Hz
* @reboot_required false
* @reboot_required true
* @group Sensors
*/
PARAM_DEFINE_FLOAT(IMU_GYRO_NF1_BW, 20.0f);
@@ -112,7 +112,7 @@ PARAM_DEFINE_FLOAT(IMU_GYRO_NF1_BW, 20.0f);
* @min 0
* @max 1000
* @unit Hz
* @reboot_required false
* @reboot_required true
* @group Sensors
*/
PARAM_DEFINE_FLOAT(IMU_GYRO_CUTOFF, 40.0f);
@@ -154,7 +154,7 @@ PARAM_DEFINE_INT32(IMU_GYRO_RATEMAX, 400);
* @min 0
* @max 1000
* @unit Hz
* @reboot_required false
* @reboot_required true
* @group Sensors
*/
PARAM_DEFINE_FLOAT(IMU_DGYRO_CUTOFF, 30.0f);
@@ -36,7 +36,7 @@
BatterySimulator::BatterySimulator() :
ModuleParams(nullptr),
ScheduledWorkItem(MODULE_NAME, px4::wq_configurations::hp_default),
_battery(1, this, BATTERY_SIMLATOR_SAMPLE_INTERVAL_US, battery_status_s::SOURCE_POWER_MODULE)
_battery(1, this, BATTERY_SIMLATOR_SAMPLE_INTERVAL_US, battery_status_s::BATTERY_SOURCE_POWER_MODULE)
{
}
+46 -57
View File
@@ -1,6 +1,6 @@
############################################################################
#
# Copyright (c) 2025 PX4 Development Team. All rights reserved.
# Copyright (c) 2022-2023 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,42 +31,21 @@
#
############################################################################
if(NOT DEFINED ENV{GZ_DISTRO})
set(GZ_DISTRO "harmonic" CACHE STRING "Gazebo distribution to use")
else()
set(GZ_DISTRO $ENV{GZ_DISTRO})
endif()
# Find the gz_Transport library
# Look for GZ Ionic or Harmonic
find_package(gz-transport NAMES gz-transport14 gz-transport13)
# Define library version combinations for different Gazebo distributions
# https://github.com/gazebo-tooling/gazebodistro/blob/master/collection-harmonic.yaml
if(GZ_DISTRO STREQUAL "harmonic")
set(GZ_CMAKE_VERSION "3")
set(GZ_MSGS_VERSION "10")
set(GZ_TRANSPORT_VERSION "13")
set(GZ_PLUGIN_VERSION "2")
set(GZ_SIM_VERSION "8")
set(GZ_SENSORS_VERSION "8")
message(STATUS "Using Gazebo Harmonic (cmake:${GZ_CMAKE_VERSION}, msgs:${GZ_MSGS_VERSION}, transport:${GZ_TRANSPORT_VERSION})")
elseif(GZ_DISTRO STREQUAL "ionic")
set(GZ_CMAKE_VERSION "4")
set(GZ_MSGS_VERSION "11")
set(GZ_TRANSPORT_VERSION "14")
set(GZ_PLUGIN_VERSION "3")
set(GZ_SIM_VERSION "9")
set(GZ_SENSORS_VERSION "9")
message(STATUS "Using Gazebo Ionic (cmake:${GZ_CMAKE_VERSION}, msgs:${GZ_MSGS_VERSION}, transport:${GZ_TRANSPORT_VERSION})")
else()
message(FATAL_ERROR "Unknown Gazebo distribution: ${GZ_DISTRO}. Valid options are: harmonic or ionic")
endif()
if(gz-transport_FOUND)
# Use gz-transport as litmus test for prescence of gz
find_package(gz-transport${GZ_TRANSPORT_VERSION})
add_compile_options(-frtti -fexceptions)
if (gz-transport${GZ_TRANSPORT_VERSION}_FOUND)
set(GZ_TRANSPORT_VER ${gz-transport_VERSION_MAJOR})
find_package(gz-cmake${GZ_CMAKE_VERSION} REQUIRED)
find_package(gz-msgs${GZ_MSGS_VERSION} REQUIRED)
find_package(Protobuf REQUIRED)
if(GZ_TRANSPORT_VER GREATER_EQUAL 12)
set(GZ_TRANSPORT_LIB gz-transport${GZ_TRANSPORT_VER}::core)
else()
set(GZ_TRANSPORT_LIB ignition-transport${GZ_TRANSPORT_VER}::core)
endif()
px4_add_module(
MODULE modules__simulation__gz_bridge
@@ -87,19 +66,11 @@ if (gz-transport${GZ_TRANSPORT_VERSION}_FOUND)
DEPENDS
mixer_module
px4_work_queue
gz-transport${GZ_TRANSPORT_VERSION}::core
${GZ_TRANSPORT_LIB}
MODULE_CONFIG
module.yaml
)
target_include_directories(modules__simulation__gz_bridge
PUBLIC
${PX4_GZ_MSGS_BINARY_DIR}
)
target_include_directories(modules__simulation__gz_bridge PUBLIC px4_gz_msgs)
target_link_libraries(modules__simulation__gz_bridge PUBLIC px4_gz_msgs)
px4_add_git_submodule(TARGET git_gz PATH "${PX4_SOURCE_DIR}/Tools/simulation/gz")
include(ExternalProject)
ExternalProject_Add(gz
@@ -111,41 +82,59 @@ if (gz-transport${GZ_TRANSPORT_VERSION}_FOUND)
USES_TERMINAL_CONFIGURE true
USES_TERMINAL_BUILD true
EXCLUDE_FROM_ALL true
BUILD_ALWAYS 1
)
# Below we setup the build targets for our worlds and models
# Syntax: gz_<model_name>_<world_name>
# Example: gz_x500_flow_forest
file(GLOB gz_worlds ${PX4_SOURCE_DIR}/Tools/simulation/gz/worlds/*.sdf)
file(GLOB gz_airframes ${PX4_SOURCE_DIR}/ROMFS/px4fmu_common/init.d-posix/airframes/*_gz_*)
set(gz_worlds
default
windy
baylands
lawn
aruco
rover
walls
)
# find corresponding airframes
file(GLOB gz_airframes
RELATIVE ${PX4_SOURCE_DIR}/ROMFS/px4fmu_common/init.d-posix/airframes
${PX4_SOURCE_DIR}/ROMFS/px4fmu_common/init.d-posix/airframes/*_gz_*
)
# remove any .post files
foreach(gz_airframe IN LISTS gz_airframes)
if(gz_airframe MATCHES ".post")
list(REMOVE_ITEM gz_airframes ${gz_airframe})
endif()
endforeach()
list(REMOVE_DUPLICATES gz_airframes)
foreach(gz_airframe IN LISTS gz_airframes)
set(model_name)
string(REGEX REPLACE ".*_gz_" "" model_name ${gz_airframe})
set(model_only)
string(REGEX REPLACE ".*_gz_" "" model_only ${gz_airframe})
foreach(world ${gz_worlds})
get_filename_component("world_name" ${world} NAME_WE)
if(world_name STREQUAL "default")
add_custom_target(gz_${model_name}
COMMAND ${CMAKE_COMMAND} -E env PX4_SIM_MODEL=gz_${model_name} $<TARGET_FILE:px4>
add_custom_target(gz_${model_only}
COMMAND ${CMAKE_COMMAND} -E env PX4_SIM_MODEL=gz_${model_only} $<TARGET_FILE:px4>
WORKING_DIRECTORY ${SITL_WORKING_DIR}
USES_TERMINAL
DEPENDS px4 px4_gz_plugins
DEPENDS px4
)
else()
add_custom_target(gz_${model_name}_${world_name}
COMMAND ${CMAKE_COMMAND} -E env PX4_SIM_MODEL=gz_${model_name} PX4_GZ_WORLD=${world_name} $<TARGET_FILE:px4>
add_custom_target(gz_${model_only}_${world_name}
COMMAND ${CMAKE_COMMAND} -E env PX4_SIM_MODEL=gz_${model_only} PX4_GZ_WORLD=${world_name} $<TARGET_FILE:px4>
WORKING_DIRECTORY ${SITL_WORKING_DIR}
USES_TERMINAL
DEPENDS px4 px4_gz_plugins
DEPENDS px4
)
endif()
endforeach()
endforeach()
# Setup the environment variables: PX4_GZ_MODELS, PX4_GZ_WORLDS, GZ_SIM_RESOURCE_PATH
# PX4_GZ_MODELS, PX4_GZ_WORLDS, GZ_SIM_RESOURCE_PATH
configure_file(gz_env.sh.in ${PX4_BINARY_DIR}/rootfs/gz_env.sh)
endif()
File diff suppressed because it is too large Load Diff
+83 -57
View File
@@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2025 PX4 Development Team. All rights reserved.
* Copyright (c) 2022-2023 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
@@ -44,28 +44,24 @@
#include <px4_platform_common/module_params.h>
#include <px4_platform_common/posix.h>
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
#include <lib/drivers/device/Device.hpp>
#include <lib/geo/geo.h>
#include <uORB/PublicationMulti.hpp>
#include <uORB/Subscription.hpp>
#include <uORB/SubscriptionInterval.hpp>
#include <uORB/topics/parameter_update.h>
#include <uORB/topics/differential_pressure.h>
#include <uORB/topics/distance_sensor.h>
#include <lib/drivers/device/Device.hpp>
#include <uORB/topics/sensor_accel.h>
#include <uORB/topics/sensor_gyro.h>
#include <uORB/topics/sensor_gps.h>
#include <uORB/topics/sensor_baro.h>
#include <uORB/topics/sensor_mag.h>
#include <uORB/topics/sensor_optical_flow.h>
#include <uORB/topics/obstacle_distance.h>
#include <uORB/topics/wheel_encoders.h>
#include <uORB/topics/vehicle_angular_velocity.h>
#include <uORB/topics/vehicle_attitude.h>
#include <uORB/topics/vehicle_global_position.h>
#include <uORB/topics/vehicle_local_position.h>
#include <uORB/topics/sensor_baro.h>
#include <uORB/topics/vehicle_odometry.h>
#include <uORB/topics/wheel_encoders.h>
#include <uORB/topics/obstacle_distance.h>
#include <gz/math.hh>
#include <gz/msgs.hh>
@@ -79,15 +75,13 @@
#include <gz/msgs/laserscan.pb.h>
#include <gz/msgs/stringmsg.pb.h>
#include <gz/msgs/scene.pb.h>
// Custom PX4 proto
#include <opticalflow.pb.h>
using namespace time_literals;
class GZBridge : public ModuleBase<GZBridge>, public ModuleParams, public px4::ScheduledWorkItem
{
public:
GZBridge(const std::string &world, const std::string &model_name);
GZBridge(const char *world, const char *name, const char *model, const char *pose_str);
~GZBridge() override;
/** @see ModuleBase */
@@ -104,28 +98,76 @@ public:
/** @see ModuleBase::print_status() */
int print_status() override;
uint64_t world_time_us() const { return _world_time_us.load(); }
private:
void Run() override;
void clockCallback(const gz::msgs::Clock &msg);
void airspeedCallback(const gz::msgs::AirSpeed &msg);
void barometerCallback(const gz::msgs::FluidPressure &msg);
void imuCallback(const gz::msgs::IMU &msg);
void poseInfoCallback(const gz::msgs::Pose_V &msg);
void odometryCallback(const gz::msgs::OdometryWithCovariance &msg);
void navSatCallback(const gz::msgs::NavSat &msg);
void laserScantoLidarSensorCallback(const gz::msgs::LaserScan &msg);
void laserScanCallback(const gz::msgs::LaserScan &msg);
void opticalFlowCallback(const px4::msgs::OpticalFlow &msg);
void magnetometerCallback(const gz::msgs::Magnetometer &msg);
bool updateClock(const uint64_t tv_sec, const uint64_t tv_nsec);
void clockCallback(const gz::msgs::Clock &clock);
void airspeedCallback(const gz::msgs::AirSpeed &air_speed);
void barometerCallback(const gz::msgs::FluidPressure &air_pressure);
void imuCallback(const gz::msgs::IMU &imu);
void poseInfoCallback(const gz::msgs::Pose_V &pose);
void odometryCallback(const gz::msgs::OdometryWithCovariance &odometry);
void navSatCallback(const gz::msgs::NavSat &nav_sat);
void laserScantoLidarSensorCallback(const gz::msgs::LaserScan &scan);
void laserScanCallback(const gz::msgs::LaserScan &scan);
/**
* @brief Call Entityfactory service
*
* @param req
* @return true
* @return false
*/
bool callEntityFactoryService(const std::string &service, const gz::msgs::EntityFactory &req);
/**
* @brief Call scene info service
*
* @param service
* @param req
* @return true
* @return false
*/
bool callSceneInfoMsgService(const std::string &service);
/**
* @brief Call String service
*
* @param service
* @param req
* @return true
* @return false
*/
bool callStringMsgService(const std::string &service, const gz::msgs::StringMsg &req);
/**
* @brief Call Vector3d Service
*
* @param service
* @param req
* @return true
* @return false
*/
bool callVector3dService(const std::string &service, const gz::msgs::Vector3d &req);
/**
*
* Convert a quaterion from FLU_to_ENU frames (ROS convention)
* to FRD_to_NED frames (PX4 convention)
*
* @param q_FRD_to_NED output quaterion in PX4 conventions
* @param q_FLU_to_ENU input quaterion in ROS conventions
*/
static void rotateQuaternion(gz::math::Quaterniond &q_FRD_to_NED, const gz::math::Quaterniond q_FLU_to_ENU);
void addGpsNoise(double &latitude, double &longitude, double &altitude,
float &vel_north, float &vel_east, float &vel_down);
uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s};
// Subscriptions
uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s};
uORB::Publication<distance_sensor_s> _distance_sensor_pub{ORB_ID(distance_sensor)};
uORB::Publication<differential_pressure_s> _differential_pressure_pub{ORB_ID(differential_pressure)};
@@ -134,23 +176,23 @@ private:
uORB::Publication<vehicle_attitude_s> _attitude_ground_truth_pub{ORB_ID(vehicle_attitude_groundtruth)};
uORB::Publication<vehicle_global_position_s> _gpos_ground_truth_pub{ORB_ID(vehicle_global_position_groundtruth)};
uORB::Publication<vehicle_local_position_s> _lpos_ground_truth_pub{ORB_ID(vehicle_local_position_groundtruth)};
uORB::PublicationMulti<sensor_gps_s> _sensor_gps_pub{ORB_ID(sensor_gps)};
uORB::PublicationMulti<sensor_baro_s> _sensor_baro_pub{ORB_ID(sensor_baro)};
uORB::PublicationMulti<sensor_accel_s> _sensor_accel_pub{ORB_ID(sensor_accel)};
uORB::PublicationMulti<sensor_gyro_s> _sensor_gyro_pub{ORB_ID(sensor_gyro)};
uORB::PublicationMulti<sensor_mag_s> _sensor_mag_pub{ORB_ID(sensor_mag)};
uORB::PublicationMulti<vehicle_odometry_s> _visual_odometry_pub{ORB_ID(vehicle_visual_odometry)};
uORB::PublicationMulti<sensor_optical_flow_s> _optical_flow_pub{ORB_ID(sensor_optical_flow)};
uORB::PublicationMulti<sensor_baro_s> _sensor_baro_pub{ORB_ID(sensor_baro)};
uORB::PublicationMulti<sensor_accel_s> _sensor_accel_pub{ORB_ID(sensor_accel)};
uORB::PublicationMulti<sensor_gyro_s> _sensor_gyro_pub{ORB_ID(sensor_gyro)};
uORB::PublicationMulti<vehicle_odometry_s> _visual_odometry_pub{ORB_ID(vehicle_visual_odometry)};
GZMixingInterfaceESC _mixing_interface_esc{_node};
GZMixingInterfaceServo _mixing_interface_servo{_node};
GZMixingInterfaceWheel _mixing_interface_wheel{_node};
GZMixingInterfaceESC _mixing_interface_esc{_node, _node_mutex};
GZMixingInterfaceServo _mixing_interface_servo{_node, _node_mutex};
GZMixingInterfaceWheel _mixing_interface_wheel{_node, _node_mutex};
GZGimbal _gimbal{_node, _node_mutex};
GZGimbal _gimbal{_node};
px4::atomic<uint64_t> _world_time_us{0};
pthread_mutex_t _node_mutex;
MapProjection _pos_ref{};
double _alt_ref{};
double _alt_ref{}; // starting altitude reference
matrix::Vector3d _position_prev{};
matrix::Vector3d _velocity_prev{};
@@ -159,26 +201,10 @@ private:
const std::string _world_name;
const std::string _model_name;
const std::string _model_sim;
const std::string _model_pose;
float _temperature{288.15}; // 15 degrees
gz::transport::Node _node;
// GPS noise model
float _gps_pos_noise_n = 0.0f;
float _gps_pos_noise_e = 0.0f;
float _gps_pos_noise_d = 0.0f;
float _gps_vel_noise_n = 0.0f;
float _gps_vel_noise_e = 0.0f;
float _gps_vel_noise_d = 0.0f;
const float _pos_noise_amplitude = 0.8f; // Position noise amplitude [m]
const float _pos_random_walk = 0.01f; // Position random walk coefficient
const float _pos_markov_time = 0.95f; // Position Markov process coefficient
const float _vel_noise_amplitude = 0.05f; // Velocity noise amplitude [m/s]
const float _vel_noise_density = 0.2f; // Velocity noise process density
const float _vel_markov_time = 0.85f; // Velocity Markov process coefficient
DEFINE_PARAMETERS(
(ParamInt<px4::params::SIM_GPS_USED>) _sim_gps_used
)
};
@@ -49,8 +49,6 @@ bool GZGimbal::init(const std::string &world_name, const std::string &model_name
return false;
}
pthread_mutex_init(&_node_mutex, nullptr);
updateParameters();
ScheduleOnInterval(200_ms); // @5Hz
@@ -27,17 +27,18 @@ using namespace time_literals;
class GZGimbal : public px4::ScheduledWorkItem, public ModuleParams
{
public:
GZGimbal(gz::transport::Node &node) :
GZGimbal(gz::transport::Node &node, pthread_mutex_t &node_mutex) :
px4::ScheduledWorkItem(MODULE_NAME "-gimbal", px4::wq_configurations::rate_ctrl),
ModuleParams(nullptr),
_node(node)
_node(node),
_node_mutex(node_mutex)
{}
private:
friend class GZBridge;
gz::transport::Node &_node;
pthread_mutex_t _node_mutex;
pthread_mutex_t &_node_mutex;
uORB::Subscription _gimbal_device_set_attitude_sub{ORB_ID(gimbal_device_set_attitude)};
uORB::Subscription _gimbal_controls_sub{ORB_ID(gimbal_controls)};
@@ -55,8 +55,6 @@ bool GZMixingInterfaceESC::init(const std::string &model_name)
_esc_status_pub.advertise();
pthread_mutex_init(&_node_mutex, nullptr);
ScheduleNow();
return true;
@@ -50,9 +50,10 @@ class GZMixingInterfaceESC : public OutputModuleInterface
public:
static constexpr int MAX_ACTUATORS = MixingOutput::MAX_ACTUATORS;
GZMixingInterfaceESC(gz::transport::Node &node) :
GZMixingInterfaceESC(gz::transport::Node &node, pthread_mutex_t &node_mutex) :
OutputModuleInterface(MODULE_NAME "-actuators-esc", px4::wq_configurations::rate_ctrl),
_node(node)
_node(node),
_node_mutex(node_mutex)
{}
bool updateOutputs(bool stop_motors, uint16_t outputs[MAX_ACTUATORS],
@@ -76,7 +77,7 @@ private:
void motorSpeedCallback(const gz::msgs::Actuators &actuators);
gz::transport::Node &_node;
pthread_mutex_t _node_mutex;
pthread_mutex_t &_node_mutex;
MixingOutput _mixing_output{"SIM_GZ_EC", MAX_ACTUATORS, *this, MixingOutput::SchedulingPolicy::Auto, false, false};
@@ -121,8 +121,6 @@ bool GZMixingInterfaceServo::init(const std::string &model_name)
_angular_range_rad.push_back(max_val - min_val);
}
pthread_mutex_init(&_node_mutex, nullptr);
ScheduleNow();
return true;

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