Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

SIH-SITL integration tests #24237

Draft
wants to merge 25 commits into
base: main
Choose a base branch
from
Draft
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
25 commits
Select commit Hold shift + click to select a range
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
153 changes: 153 additions & 0 deletions .github/workflows/sitl_sih_tests.yml
Original file line number Diff line number Diff line change
@@ -0,0 +1,153 @@
# NOTE: this workflow is now running on Dronecode / PX4 AWS account.
# - If you want to keep the tests running in GitHub Actions you need to uncomment the "runs-on: ubuntu-latest" lines
# and comment the "runs-on: [runs-on,runner=..." lines.
# - If you would like to duplicate this setup try setting up "RunsOn" on your own AWS account try https://runs-on.com

name: SITL Tests using SIH

on:
push:
branches:
- 'main'
pull_request:
branches:
- '*'

jobs:
build:
name: Testing PX4 ${{ matrix.config.model }}
runs-on: [runs-on,runner=16cpu-linux-x64,image=ubuntu22-full-x64,"run-id=${{ github.run_id }}",spot=false]
container:
image: px4io/px4-dev-simulation-focal:2021-09-08
options: --privileged --ulimit core=-1 --security-opt seccomp=unconfined
strategy:
fail-fast: false
matrix:
config:
- {model: "quadx", latitude: "59.617693", longitude: "-151.145316", altitude: "48", build_type: "RelWithDebInfo" } # Alaska
- {model: "xvert" , latitude: "29.660316", longitude: "-82.316658", altitude: "30", build_type: "RelWithDebInfo" } # Florida
- {model: "standard_vtol", latitude: "47.397742", longitude: "8.545594", altitude: "488", build_type: "Coverage" } # Zurich

steps:
- uses: actions/checkout@v4
with:
fetch-depth: 0

- name: Git Ownership Workaround
run: git config --system --add safe.directory '*'

- id: set-timestamp
name: Set timestamp for cache
run: echo "::set-output name=timestamp::$(date +"%Y%m%d%H%M%S")"

- name: Cache Key Config
uses: actions/cache@v4
with:
path: ~/.ccache
key: sitl-ccache-${{ steps.set-timestamp.outputs.timestamp }}
restore-keys: sitl-ccache-${{ steps.set-timestamp.outputs.timestamp }}

- name: Cache Conf Config
run: |
mkdir -p ~/.ccache
echo "base_dir = ${GITHUB_WORKSPACE}" > ~/.ccache/ccache.conf
echo "compression = true" >> ~/.ccache/ccache.conf
echo "compression_level = 6" >> ~/.ccache/ccache.conf
echo "max_size = 120M" >> ~/.ccache/ccache.conf
echo "hash_dir = false" >> ~/.ccache/ccache.conf
ccache -s
ccache -z

- name: Build PX4
env:
PX4_CMAKE_BUILD_TYPE: ${{matrix.config.build_type}}
run: make px4_sitl_default

- name: Cache Post-Run [px4_sitl_default]
run: ccache -s

- name: Build SITL Gazebo
env:
PX4_CMAKE_BUILD_TYPE: ${{matrix.config.build_type}}
run: make px4_sitl_default sitl_gazebo-classic

- name: Cache Post-Run [sitl_gazebo-classic]
run: ccache -s

- name: Download MAVSDK
run: wget "https://github.com/mavlink/MAVSDK/releases/download/v$(cat test/mavsdk_tests/MAVSDK_VERSION)/libmavsdk-dev_$(cat test/mavsdk_tests/MAVSDK_VERSION)_ubuntu20.04_amd64.deb"

- name: Install MAVSDK
run: dpkg -i "libmavsdk-dev_$(cat test/mavsdk_tests/MAVSDK_VERSION)_ubuntu20.04_amd64.deb"

- name: Check PX4 Environment Variables
env:
PX4_HOME_LAT: ${{matrix.config.latitude}}
PX4_HOME_LON: ${{matrix.config.longitude}}
PX4_HOME_ALT: ${{matrix.config.altitude}}
PX4_CMAKE_BUILD_TYPE: ${{matrix.config.build_type}}
run: |
export
ulimit -a

- name: Build PX4 / MAVSDK tests
env:
PX4_CMAKE_BUILD_TYPE: ${{matrix.config.build_type}}
DONT_RUN: 1
run: make px4_sitl_default gazebo mavsdk_tests

- name: Cache Post-Run [px4_sitl_default sitl_gazebo-classic mavsdk_tests]
run: ccache -s

- name: Core Dump Settings
run: |
ulimit -c unlimited
echo "`pwd`/%e.core" > /proc/sys/kernel/core_pattern

- name: Run SITL / MAVSDK Tests
env:
PX4_HOME_LAT: ${{matrix.config.latitude}}
PX4_HOME_LON: ${{matrix.config.longitude}}
PX4_HOME_ALT: ${{matrix.config.altitude}}
PX4_CMAKE_BUILD_TYPE: ${{matrix.config.build_type}}
run: test/mavsdk_tests/mavsdk_test_runner.py --speed-factor 1 --model ${{matrix.config.model}} --upload test/mavsdk_tests/configs/sitl_sih.json --verbose
timeout-minutes: 45

- name: Upload failed logs
if: failure()
uses: actions/upload-artifact@v4
with:
name: failed-${{matrix.config.model}}-logs.zip
path: |
logs/**/**/**/*.log
logs/**/**/**/*.ulg
build/px4_sitl_default/tmp_mavsdk_tests/rootfs/*.ulg

- name: Look at Core files
if: failure() && ${{ hashFiles('px4.core') != '' }}
run: gdb build/px4_sitl_default/bin/px4 px4.core -ex "thread apply all bt" -ex "quit"

- name: Upload PX4 coredump
if: failure() && ${{ hashFiles('px4.core') != '' }}
uses: actions/upload-artifact@v4
with:
name: coredump
path: px4.core

- name: Setup & Generate Coverage Report
if: contains(matrix.config.build_type, 'Coverage')
run: |
git config --global credential.helper "" # disable the keychain credential helper
git config --global --add credential.helper store # enable the local store credential helper
echo "https://x-access-token:${{ secrets.ACCESS_TOKEN }}@github.com" >> ~/.git-credentials # add credential
git config --global url."https://github.com/".insteadof [email protected]: # credentials add credential
mkdir -p coverage
lcov --directory build/px4_sitl_default --base-directory build/px4_sitl_default --gcov-tool gcov --capture -o coverage/lcov.info

- name: Upload Coverage Information to Codecov
if: contains(matrix.config.build_type, 'Coverage')
uses: codecov/codecov-action@v4
with:
token: ${{ secrets.CODECOV_TOKEN }}
flags: mavsdk
file: coverage/lcov.info
6 changes: 6 additions & 0 deletions ROMFS/px4fmu_common/init.d-posix/airframes/10040_sihsim_quadx
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,12 @@ param set-default CA_ROTOR3_PX -1
param set-default CA_ROTOR3_PY 1
param set-default CA_ROTOR3_KM -0.05

# again follows from CA_* params. remove redundancy sometime
param set-default SIH_L_PITCH 1 # = CA_ROTOR0_PX
param set-default SIH_L_ROLL 1 # = CA_ROTOR0_PY
param set-default SIH_T_MAX 6.5 # = default value of CA_ROTOR0_CT
param set-default SIH_Q_MAX 0.325 # = CA_ROTOR0_KM * SIH_T_MAX

param set-default PWM_MAIN_FUNC1 101
param set-default PWM_MAIN_FUNC2 102
param set-default PWM_MAIN_FUNC3 103
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@ param set-default EKF2_FUSE_BETA 0 # side slip fusion is currently not supported
param set-default SENS_EN_GPSSIM 1
param set-default SENS_EN_BAROSIM 1
param set-default SENS_EN_MAGSIM 1
param set-default SENS_EN_ARSPDSIM 1

param set-default VT_B_TRANS_DUR 5
param set-default VT_ELEV_MC_LOCK 0
Expand All @@ -37,7 +38,10 @@ param set-default SIH_IYY 0.000625
param set-default SIH_IZZ 0.00300
param set-default SIH_IXZ 0
param set-default SIH_KDV 0.2
param set-default SIH_L_ROLL 0.145

# SIH_L_ROLL = CA_ROTOR0_PX. this is redundant, should in future use CA rotor
# geometry info in sih...
param set-default SIH_L_ROLL 1

# sih as tailsitter
param set-default SIH_VEHICLE_TYPE 2
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -61,9 +61,9 @@ param set-default CA_SV_CS1_TYPE 3 # elevator
param set-default CA_SV_CS2_TRQ_Y 1
param set-default CA_SV_CS2_TYPE 4 # rudder

param set-default FW_AIRSPD_MIN 7
param set-default FW_AIRSPD_TRIM 10
param set-default FW_AIRSPD_MAX 12
param set-default FW_AIRSPD_MIN 10
param set-default FW_AIRSPD_TRIM 15
param set-default FW_AIRSPD_MAX 20

param set-default PWM_MAIN_FUNC1 101
param set-default PWM_MAIN_FUNC2 102
Expand All @@ -81,8 +81,35 @@ param set-default MAV_TYPE 22

param set-default SENS_DPRES_OFF 0.001


#
# # gazebo model:
# # https://github.com/PX4/PX4-gazebo-models/blob/main/models/standard_vtol/model.sdf
# # notes about gazebo models:
# # https://github.com/mvernacc/gazebo_motor_model_docs/blob/master/notes.pdf
#
# # max thrust = maxRotVelocity**2 * motorConstant
# param set SIH_T_MAX 45
#
# # max torque = ??
# param set SIH_Q_MAX 0.0165
#
# # = base_link mass (rest irrelevant)
# param set SIH_MASS 5
#
# param set SIH_IXX 0.4777
# param set SIH_IYY 0.3417
# param set SIH_IZZ 0.8110
# param set SIH_IXZ 0
#
# param set SIH_KDV 0.2
#
# param set SIH_T_MAX 6.5
# param set SIH_MASS 0.65

param set SIH_T_MAX 2.0
param set SIH_Q_MAX 0.0165

param set SIH_MASS 0.2
# IXX and IZZ are inverted from the thesis as the body frame is pitched by 90 deg
param set SIH_IXX 0.00354
Expand Down
5 changes: 5 additions & 0 deletions ROMFS/px4fmu_common/init.d-posix/px4-rc.simulator
Original file line number Diff line number Diff line change
Expand Up @@ -36,11 +36,16 @@ if [ "$PX4_SIMULATOR" = "sihsim" ] || [ "$(param show -q SYS_AUTOSTART)" -eq "0"
then
sensor_mag_sim start
fi
if param compare -s SENS_EN_ARSPDSIM 1
then
sensor_airspeed_sim start
fi
if param compare -s SENS_EN_AGPSIM 1
then
sensor_agp_sim start
fi


else
echo "ERROR [init] simulator_sih failed to start"
exit 1
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -75,7 +75,10 @@ param set SIH_IYY 0.000625
param set SIH_IZZ 0.00300
param set SIH_IXZ 0
param set SIH_KDV 0.2
param set SIH_L_ROLL 0.145

# SIH_L_ROLL = CA_ROTOR0_PX. this is redundant, should in future use CA rotor
# geometry info in sih...
param set SIH_L_ROLL 1

# sih as tailsitter
param set SIH_VEHICLE_TYPE 2
Expand Down
23 changes: 21 additions & 2 deletions src/modules/sensors/data_validator/DataValidator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,11 @@
#include <px4_platform_common/log.h>
#include <drivers/drv_hrt.h>

DataValidator::DataValidator() :
ModuleParams(nullptr)
{
}

void DataValidator::put(uint64_t timestamp, float val, uint32_t error_count_in, uint8_t priority_in)
{
float data[dimensions] = {val}; // sets the first value and all others to 0
Expand Down Expand Up @@ -99,6 +104,16 @@ void DataValidator::put(uint64_t timestamp, const float val[dimensions], uint32_

float DataValidator::confidence(uint64_t timestamp)
{
// Check if parameters have changed
if (_parameter_update_sub.updated()) {
// clear update
parameter_update_s param_update;
_parameter_update_sub.copy(&param_update);

updateParams();
_noise_scale = _sih_noise_scale.get();
}


float ret = 1.0f;

Expand All @@ -112,8 +127,12 @@ float DataValidator::confidence(uint64_t timestamp)
_error_mask |= ERROR_FLAG_TIMEOUT;
ret = 0.0f;

} else if (_value_equal_count > _value_equal_count_threshold) {
/* we got the exact same sensor value N times in a row */
} else if (_value_equal_count > _value_equal_count_threshold && !(fabsf(_noise_scale) < 0.000001f)) {
/*
we got the exact same sensor value N times in a row
If SIH noise scale is very low, constant sensor data are to be expected. In that case, don't
reject it as stale.
*/
_error_mask |= ERROR_FLAG_STALE_DATA;
ret = 0.0f;

Expand Down
25 changes: 23 additions & 2 deletions src/modules/sensors/data_validator/DataValidator.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,12 +44,22 @@
#include <math.h>
#include <stdint.h>

class DataValidator
#include <px4_platform_common/module_params.h>

#include <uORB/SubscriptionInterval.hpp>
#include <uORB/topics/parameter_update.h>

using namespace time_literals;



class DataValidator : public ModuleParams
{
public:
static const unsigned dimensions = 3;

DataValidator() = default;

DataValidator();
~DataValidator() = default;

/**
Expand Down Expand Up @@ -182,6 +192,8 @@ class DataValidator
float _rms[dimensions] {}; /**< root mean square error */
float _value[dimensions] {}; /**< last value */

float _noise_scale{1.};

unsigned _value_equal_count{0}; /**< equal values in a row */
unsigned _value_equal_count_threshold{
VALUE_EQUAL_COUNT_DEFAULT}; /**< when to consider an equal count as a problem */
Expand All @@ -197,4 +209,13 @@ class DataValidator
/* we don't want this class to be copied */
DataValidator(const DataValidator &) = delete;
DataValidator operator=(const DataValidator &) = delete;

uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s};

DEFINE_PARAMETERS(
(ParamFloat<px4::params::SIH_NOISE_SCALE>) _sih_noise_scale
)



};
Loading
Loading