Skip to content

Commit

Permalink
Added support for hitl testing for vtol and fw
Browse files Browse the repository at this point in the history
On branch adding_hitl_testing_for_vtol_and_fw
Changes to be committed:
	new file:   ROMFS/px4fmu_common/init.d/airframes/1404_ssrc_standard_vtol.hil
	new file:   ROMFS/px4fmu_common/init.d/airframes/1440_ssrc_skywalker_x8.hil
	modified:   ROMFS/px4fmu_common/init.d/airframes/CMakeLists.txt
	modified:   ROMFS/px4fmu_common/init.d/rc.hitl_testing
	modified:   Tools/simulation/gz/hitl_run.sh
	new file:   Tools/simulation/gz/models/ssrc_skywalker_x8/model_hitl.sdf
	modified:   Tools/simulation/gz/plugins/px4-gzsim-plugins
	modified:   boards/ssrc/saluki-v2
	modified:   src/modules/simulation/simulator_mavlink/sitl_targets_gz-sim.cmake
	modified:   test/mavsdk_tests/CMakeLists.txt
	modified:   test/mavsdk_tests/configs/hitl_gz_harm.json
	new file:   test/mavsdk_tests/fw_mission.plan
	modified:   test/mavsdk_tests/mavsdk_test_runner.py
	new file:   test/mavsdk_tests/test_fw_mission.cpp
  • Loading branch information
Ilia-Loginov committed Oct 24, 2024
1 parent 0783eaf commit 99d08d5
Show file tree
Hide file tree
Showing 14 changed files with 387 additions and 10 deletions.
97 changes: 97 additions & 0 deletions ROMFS/px4fmu_common/init.d/airframes/1404_ssrc_standard_vtol.hil
Original file line number Diff line number Diff line change
@@ -0,0 +1,97 @@
#!/bin/sh
#
# @name Standard VTOL
#
# @type Standard VTOL
#
# @class VTOL

. ${R}etc/init.d/rc.vtol_defaults
. ${R}etc/init.d/rc.hitl_testing

# Default rates
param set-default CA_AIRFRAME 2

param set-default CA_ROTOR_COUNT 5
param set-default CA_ROTOR0_PX 0.1515
param set-default CA_ROTOR0_PY 0.245
param set-default CA_ROTOR0_KM 0.05
param set-default CA_ROTOR1_PX -0.1515
param set-default CA_ROTOR1_PY -0.1875
param set-default CA_ROTOR1_KM 0.05
param set-default CA_ROTOR2_PX 0.1515
param set-default CA_ROTOR2_PY -0.245
param set-default CA_ROTOR2_KM -0.05
param set-default CA_ROTOR3_PX -0.1515
param set-default CA_ROTOR3_PY 0.1875
param set-default CA_ROTOR3_KM -0.05
param set-default CA_ROTOR4_AX 1.0
param set-default CA_ROTOR4_AZ 0.0
param set-default CA_ROTOR4_PX 0.2

# HITL PWM functions
param set-default HIL_ACT_FUNC1 101
param set-default HIL_ACT_MIN1 10
param set-default HIL_ACT_MAX1 1500
param set-default HIL_ACT_FUNC2 102
param set-default HIL_ACT_MIN2 10
param set-default HIL_ACT_MAX2 1500
param set-default HIL_ACT_FUNC3 103
param set-default HIL_ACT_MIN3 10
param set-default HIL_ACT_MAX3 1500
param set-default HIL_ACT_FUNC4 104
param set-default HIL_ACT_MIN4 10
param set-default HIL_ACT_MAX4 1500
param set-default HIL_ACT_FUNC5 105
param set-default HIL_ACT_MIN5 0
param set-default HIL_ACT_MAX5 3500
param set-default HIL_ACT_FUNC6 201
param set-default HIL_ACT_DIS6 500
param set-default HIL_ACT_FUNC7 202
param set-default HIL_ACT_DIS7 500
param set-default HIL_ACT_FUNC8 203
param set-default HIL_ACT_DIS8 500


param set-default ASPD_PRIMARY 1

param set-default CA_SV_CS_COUNT 3
param set-default CA_SV_CS0_TYPE 1
param set-default CA_SV_CS0_TRQ_R -0.5
param set-default CA_SV_CS1_TYPE 2
param set-default CA_SV_CS1_TRQ_R 0.5
param set-default CA_SV_CS2_TYPE 3
param set-default CA_SV_CS2_TRQ_P 1.0
param set-default CA_SV_CS3_TRQ_Y 0.0
param set-default CA_SV_CS3_TYPE 0

param set-default FW_PR_FF 0.2
param set-default FW_PR_P 0.9
param set-default FW_PSP_OFF 2
param set-default FW_P_LIM_MIN -15
param set-default FW_RR_FF 0.1
param set-default FW_RR_P 0.3
param set-default FW_THR_TRIM 0.25
param set-default FW_THR_MAX 0.6
param set-default FW_THR_MIN 0.05
param set-default FW_T_CLMB_MAX 8
param set-default FW_T_SINK_MAX 2.7
param set-default FW_T_SINK_MIN 2.2

param set-default MC_AIRMODE 1
param set-default MC_ROLLRATE_P 0.3
param set-default MC_YAW_P 1.6

param set-default MIS_TAKEOFF_ALT 10

param set-default MPC_XY_P 0.8
param set-default MPC_XY_VEL_P_ACC 3
param set-default MPC_XY_VEL_I_ACC 4
param set-default MPC_XY_VEL_D_ACC 0.1

param set-default NAV_ACC_RAD 5

param set-default VT_FWD_THRUST_EN 4
param set-default VT_F_TRANS_THR 0.75
param set-default VT_TYPE 2
param set-default FD_ESCS_EN 0
83 changes: 83 additions & 0 deletions ROMFS/px4fmu_common/init.d/airframes/1440_ssrc_skywalker_x8.hil
Original file line number Diff line number Diff line change
@@ -0,0 +1,83 @@
#!/bin/sh
#
# @name SSRC Skywalker X8
#
# @type Flying Wing
# @class Plane
#

. ${R}etc/init.d/rc.fw_defaults
. ${R}etc/init.d/rc.hitl_testing

# Control allocator parameters
param set-default CA_AIRFRAME 1
param set-default CA_ROTOR_COUNT 1
param set-default CA_SV_CS_COUNT 2
param set-default CA_SV_CS0_TYPE 5
param set-default CA_SV_CS0_TRQ_P 0.5
param set-default CA_SV_CS0_TRQ_R -0.5
param set-default CA_SV_CS1_TYPE 6
param set-default CA_SV_CS1_TRQ_P 0.5
param set-default CA_SV_CS1_TRQ_R 0.5

# HITL PWM functions
param set-default HIL_ACT_FUNC1 201
param set-default HIL_ACT_DIS1 500
param set-default HIL_ACT_FUNC2 202
param set-default HIL_ACT_DIS2 500
param set-default HIL_ACT_FUNC4 101
param set-default HIL_ACT_MIN4 150
param set-default HIL_ACT_MAX4 3000

# Airspeed parameters
param set-default ASPD_PRIMARY 1
param set-default FW_AIRSPD_MAX 22.0
param set-default FW_AIRSPD_MIN 14.0
param set-default FW_AIRSPD_STALL 12.0
param set-default FW_AIRSPD_TRIM 18.0

# Maximum landing slope angle in deg
param set-default FW_LND_ANG 8

# RC loss failsafe to HOLD mode
param set-default COM_RC_IN_MODE 1

# Maximum manual roll angle
param set-default FW_MAN_R_MAX 60.0

# Fixed wing control
# Pitch rate
param set-default FW_PR_P 0.9
param set-default FW_PR_FF 0.5
param set-default FW_PR_I 0.5
param set-default TRIM_PITCH -0.15
# Pitch angle in deg
param set-default FW_PSP_OFF 0
param set-default FW_P_LIM_MIN -15
# Roll rate
param set-default FW_RR_FF 0.5
param set-default FW_RR_P 0.3
param set-default FW_RR_I 0.5
# Yaw rate
param set-default FW_YR_FF 0.5
param set-default FW_YR_P 0.6
param set-default FW_YR_I 0.5
#Throttle limit
param set-default FW_THR_MAX 0.6
param set-default FW_THR_MIN 0.05
param set-default FW_THR_TRIM 0.25
# Climb and sink rate
param set-default FW_T_CLMB_MAX 8
param set-default FW_T_SINK_MAX 2.7
param set-default FW_T_SINK_MIN 2.2

# Navigation
param set-default NAV_ACC_RAD 15
param set-default NAV_DLL_ACT 2

# Misc
param set-default RTL_RETURN_ALT 30.0
param set-default RTL_DESCEND_ALT 30.0
param set-default FW_LND_USETER 0
param set-default RWTO_TKOFF 1
param set-default FD_ESCS_EN 0
2 changes: 2 additions & 0 deletions ROMFS/px4fmu_common/init.d/airframes/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -41,6 +41,8 @@ px4_add_romfs_files(
1101_rc_plane_sih.hil
1102_tailsitter_duo_sih.hil
1401_ssrc_holybro_x500.hil
1404_ssrc_standard_vtol.hil
1440_ssrc_skywalker_x8.hil

# [2000, 2999] Standard planes"
2100_standard_plane
Expand Down
15 changes: 12 additions & 3 deletions ROMFS/px4fmu_common/init.d/rc.hitl_testing
Original file line number Diff line number Diff line change
Expand Up @@ -4,11 +4,11 @@
#


param set SYS_HITL 1
param set UAVCAN_ENABLE 0
param set-default SYS_HITL 1
param set-default UAVCAN_ENABLE 0
param set-default SYS_FAILURE_EN 1

param set MAV_HITL_SHOME 0
param set-default MAV_HITL_SHOME 0

param set-default SENS_EN_GPSSIM 1
param set-default SENS_EN_BAROSIM 1
Expand All @@ -19,4 +19,13 @@ param set-default SENS_EN_ARSPDSIM 1
# - without real battery
param set-default CBRK_SUPPLY_CHK 894281
# - without safety switch
param set-default COM_PREARM_MODE 0
param set-default CBRK_IO_SAFETY 22027


# Disable RC loss failsafe check
param set-default COM_RC_LOSS_T 180
param set-default NAV_RCL_ACT 1

# Disable RC input requirement
param set-default COM_RC_IN_MODE 1
4 changes: 2 additions & 2 deletions Tools/simulation/gz/hitl_run.sh
Original file line number Diff line number Diff line change
Expand Up @@ -20,8 +20,8 @@ fi
source $(pwd)/build/px4_sitl_default/rootfs/gz_env.sh

if [ ! -f $GZ_SIM_SYSTEM_PLUGIN_PATH/libmavlink_hitl_gazebosim.so ]; then
echo "You should build gz-sim"
echo "make px4_sitl gz-sim"
echo "You should build gzsim-plugins"
echo "make px4_sitl gzsim-plugins"
exit
fi

Expand Down
18 changes: 18 additions & 0 deletions Tools/simulation/gz/models/ssrc_skywalker_x8/model_hitl.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,18 @@
<?xml version="1.0" encoding="UTF-8"?>
<sdf version='1.9'>
<model name='ssrc_skywalker_x8_hitl'>
<include merge='true'>
<uri>model://ssrc_skywalker_x8</uri>
</include>
<plugin filename="libmavlink_hitl_gazebosim.so" name="mavlink_interface::GazeboMavlinkInterface">
<robotNamespace/>
<imuSubTopic>/link/base_link/sensor/imu_sensor/imu</imuSubTopic>
<poseSubTopic>/pose/info</poseSubTopic>
<mavlink_addr>192.168.200.101</mavlink_addr>
<mavlink_udp_local_port>14542</mavlink_udp_local_port>
<mavlink_udp_remote_port>14543</mavlink_udp_remote_port>
<mavlink_tcp_port>4560</mavlink_tcp_port>
<use_tcp>0</use_tcp>
</plugin>
</model>
</sdf>
2 changes: 1 addition & 1 deletion boards/ssrc/saluki-v2
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@ if(gz-sim8_FOUND)

include(ExternalProject)

ExternalProject_Add(gz-sim
ExternalProject_Add(gzsim-plugins
SOURCE_DIR ${PX4_SOURCE_DIR}/Tools/simulation/gz/plugins/px4-gzsim-plugins/
BINARY_DIR ${PX4_BINARY_DIR}/build_gz-sim_plugins
INSTALL_COMMAND ""
Expand Down
1 change: 1 addition & 0 deletions test/mavsdk_tests/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,7 @@ if(MAVSDK_FOUND)
test_multicopter_offboard.cpp
test_multicopter_manual.cpp
test_vtol_mission.cpp
test_fw_mission.cpp
# test_multicopter_follow_me.cpp
)

Expand Down
10 changes: 9 additions & 1 deletion test/mavsdk_tests/configs/hitl_gz_harm.json
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@
"vehicle": "ssrc_holybro_x500",
"model_file": "model_hitl",
"sys_autostart": 1401,
"test_filter": "[multicopter],[offboard][offboard_attitude]",
"test_filter": "[multicopter],[offboard],[offboard_attitude]",
"timeout_min": 10
},
{
Expand All @@ -19,6 +19,14 @@
"sys_autostart": 1404,
"test_filter": "[vtol], [vtol_wind], [vtol_airspeed_fail]",
"timeout_min": 10
},
{
"model": "ssrc_skywalker_x8",
"vehicle": "ssrc_skywalker_x8",
"model_file": "model_hitl",
"sys_autostart": 1440,
"test_filter": "[fw]",
"timeout_min": 10
}
]
}
Loading

0 comments on commit 99d08d5

Please sign in to comment.