From dee3f520a37a07f70fe7eed0cfdab4b26983c6d5 Mon Sep 17 00:00:00 2001 From: Alireza Ghaderi Date: Tue, 5 Dec 2023 10:58:07 +0000 Subject: [PATCH 01/25] added c172 and ehang4 SITL --- .../init.d-posix/airframes/5001_xplane_c172 | 152 +++++++++++++ .../init.d-posix/airframes/5010_xplane_ehang4 | 215 ++++++++++++++++++ .../init.d-posix/airframes/CMakeLists.txt | 3 + .../simulator_mavlink/CMakeLists.txt | 25 ++ 4 files changed, 395 insertions(+) create mode 100644 ROMFS/px4fmu_common/init.d-posix/airframes/5001_xplane_c172 create mode 100644 ROMFS/px4fmu_common/init.d-posix/airframes/5010_xplane_ehang4 diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/5001_xplane_c172 b/ROMFS/px4fmu_common/init.d-posix/airframes/5001_xplane_c172 new file mode 100644 index 000000000000..d34308d6988f --- /dev/null +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/5001_xplane_c172 @@ -0,0 +1,152 @@ +#!/bin/sh +# +# PX4 SITL Configuration Script for Cessna 172 Skyhawk in X-Plane +# +# This script configures PX4 SITL for a Cessna 172 Skyhawk, a standard fixed-wing plane. +# It's tailored for integration with X-Plane, a custom simulator, facilitating real-world scale simulation. +# +# Usage: Run with 'make px4_sitl xplane_c172'. +# +# Airframe: Cessna 172 Skyhawk +# Compatible Simulator: X-Plane +# Type: Standard Plane +# Class: Plane +# Author: alireza787b +# Date: Nov 2023 +# Project URL: https://github.com/alireza787b/px4xplane/ +# +# ---- Start of Configuration ---- + +# Load default configuration for fixed-wing aircraft +. ${R}etc/init.d/rc.fw_defaults + +# ---- Airframe Configuration Parameters ---- +# These parameters define the physical configuration of the Cessna 172 Skyhawk airframe +param set-default CA_AIRFRAME 1 +param set-default CA_ROTOR_COUNT 1 +param set-default CA_ROTOR0_PX 0.3 + +# ---- Control Surface Configuration ---- +# Configuration of control surfaces for flight control and maneuvering +param set-default CA_SV_CS_COUNT 4 +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_TYPE 4 +param set-default CA_SV_CS3_TRQ_Y 1.0 + +# ---- Simulator Sensor Configuration ---- +# Enabling simulated sensors for integration with X-Plane +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 + +# ---- PWM Output Configuration ---- +# Assignments for PWM main outputs +param set-default PWM_MAIN_FUNC1 201 +param set-default PWM_MAIN_FUNC2 202 +param set-default PWM_MAIN_FUNC3 203 +param set-default PWM_MAIN_FUNC4 101 +param set-default PWM_MAIN_FUNC5 204 +param set-default PWM_MAIN_FUNC6 204 + +# ---- Fixed-wing Specific Parameters ---- +# Parameters specific to fixed-wing flight dynamics +param set-default FW_AIRSPD_MAX 65.0000 +param set-default FW_AIRSPD_MIN 32.0000 +param set-default FW_AIRSPD_STALL 28.0000 +param set-default FW_AIRSPD_TRIM 45.0000 +param set-default MIS_DIST_1WP 3000.0000 +param set-default ASPD_FALLBACK_GW 1 +param set-default FW_AIRSPD_STALL 20.0000 +param set-default FW_PN_R_SLEW_MAX 15.0000 +param set-default FW_PR_D 0.2650 +param set-default FW_PR_FF 5.3000 +param set-default FW_PR_I 0.0600 +param set-default FW_PR_P 0.4800 +param set-default FW_P_TC 0.3000 +param set-default FW_RR_FF 4.8000 +param set-default FW_RR_P 0.3500 +param set-default FW_R_LIM 30.0000 +param set-default FW_R_RMAX 50.0000 +param set-default LNDFW_AIRSPD_MAX 20.0000 +param set-default LNDFW_VEL_XY_MAX 15.0000 +param set-default FW_LND_FLALT 5.0000 +param set-default RTL_LOITER_RAD 1000.0000 +param set-default FW_LND_FL_PMAX 20.0000 + +# ---- PWM Reversals ---- +# Configuration for reversing the PWM signal +param set-default PWM_MAIN_REV 7 + +# ---- Logging Configuration ---- +# Settings related to flight data logging +param set-default SDLOG_MODE 0 + +# ---- Circuit Breakers ---- +# Disabling various system checks (use with caution) +param set-default CBRK_USB_CHK 197848 # Disable USB check +param set-default CBRK_SUPPLY_CHK 894281 # Disable real battery check +param set-default CBRK_IO_SAFETY 22027 # Disable safety switch check +param set-default CBRK_AIRSPD_CHK 1612128 # Disable airspeed sensor check + +# ---- End of Configuration ---- +#new + +param set-default FW_TKO_AIRSPD 32.0000 +param set-default FW_TKO_PITCH_MIN 20.0000 +param set-default FW_T_CLMB_MAX 6.0000 +param set-default FW_WING_HEIGHT 2.5000 +param set-default FW_WING_SPAN 11.0000 +param set-default MIS_DIST_1WP 5000.0000 +param set-default MIS_TAKEOFF_ALT 100.0000 +param set-default MIS_TKO_LAND_REQ 0 +param set-default NAV_ACC_RAD 100.0000 +param set-default NAV_FW_ALT_RAD 30.0000 +param set-default NAV_LOITER_RAD 1000.0000 +param set-default NAV_MIN_LTR_ALT 300.0000 +param set-default RTL_MIN_DIST 50.0000 +param set-default WEIGHT_BASE 1000.0000 +param set-default WEIGHT_GROSS 1000.0000 +param set-default CA_R0_SLEW 4.0000 +param set-default CA_ROTOR0_PX 1.2000 + + +param set-default CA_R0_SLEW 2.0000 +param set-default EKF2_ABL_ACCLIM 35.0000 +param set-default EKF2_MAG_DELAY 1.0000 +param set-default FW_LND_ABORT 0 +param set-default FW_PN_R_SLEW_MAX 50.0000 +param set-default FW_PR_D 0.5600 +param set-default FW_PR_FF 3.4000 +param set-default FW_PR_I 0.0450 +param set-default FW_PR_P 0.3650 +param set-default FW_P_LIM_MAX 20.0000 +param set-default FW_P_LIM_MIN -15.0000 +param set-default FW_P_TC 0.4500 +param set-default FW_RR_FF 3.6500 +param set-default FW_RR_P 0.4700 +param set-default FW_R_LIM 35.0000 +param set-default FW_R_RMAX 10.0000 +param set-default FW_R_TC 0.6000 +param set-default FW_T_ALT_TC 10.0000 +param set-default FW_T_I_GAIN_THR 0.0200 +param set-default FW_T_RLL2THR 5.0000 +param set-default FW_T_STE_R_TC 2.5000 +param set-default FW_T_THR_DAMP 0.0000 +param set-default LNDFW_AIRSPD_MAX 30.0000 +param set-default MIS_YAW_ERR 15.0000 +param set-default NAV_ACC_RAD 300.0000 +param set-default NAV_FW_ALT_RAD 50.0000 +param set-default NAV_MIN_LTR_ALT -1.0000 + +param set-default EKF2_MAG_TYPE 0 +param set-default FW_LND_AIRSPD 36.0000 +param set-default FW_PR_D 0.3550 +param set-default FW_RR_D 0.0850 +param set-default FW_RR_I 0.1300 +param set-default SYS_HAS_MAG 1 diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/5010_xplane_ehang4 b/ROMFS/px4fmu_common/init.d-posix/airframes/5010_xplane_ehang4 new file mode 100644 index 000000000000..9b83ecbc59ff --- /dev/null +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/5010_xplane_ehang4 @@ -0,0 +1,215 @@ +#!/bin/sh +# +# @name Generic Iris Quadrotor SITL +# +# @type Quadrotor Wide +# +#!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!! +. ${R}etc/init.d/rc.mc_defaults + + +param set-default CA_AIRFRAME 0 + +param set-default CA_ROTOR_COUNT 4 +param set-default CA_ROTOR0_PX 0.1515 +param set-default CA_ROTOR0_PY 0.245 +param set-default CA_ROTOR0_KM 0.05 +param set-default CA_ROTOR1_PX -0.1515 +param set-default CA_ROTOR1_PY -0.1875 +param set-default CA_ROTOR1_KM 0.05 +param set-default CA_ROTOR2_PX 0.1515 +param set-default CA_ROTOR2_PY -0.245 +param set-default CA_ROTOR2_KM -0.05 +param set-default CA_ROTOR3_PX -0.1515 +param set-default CA_ROTOR3_PY 0.1875 +param set-default CA_ROTOR3_KM -0.05 + +param set-default PWM_MAIN_FUNC1 101 +param set-default PWM_MAIN_FUNC2 102 +param set-default PWM_MAIN_FUNC3 103 +param set-default PWM_MAIN_FUNC4 104 + +param set-default CA_FAILURE_MODE 0 +param set-default CA_METHOD 2 +param set-default CA_R0_SLEW 0.0000 +param set-default CA_R10_SLEW 0.0000 +param set-default CA_R11_SLEW 0.0000 +param set-default CA_R1_SLEW 0.0000 +param set-default CA_R2_SLEW 0.0000 +param set-default CA_R3_SLEW 0.0000 +param set-default CA_R4_SLEW 0.0000 +param set-default CA_R5_SLEW 0.0000 +param set-default CA_R6_SLEW 0.0000 +param set-default CA_R7_SLEW 0.0000 +param set-default CA_R8_SLEW 0.0000 +param set-default CA_R9_SLEW 0.0000 +param set-default CA_ROTOR0_AX 0.0000 +param set-default CA_ROTOR0_AY 0.0000 +param set-default CA_ROTOR0_AZ -1.0000 +param set-default CA_ROTOR0_CT 6.5000 +param set-default CA_ROTOR0_KM -0.0500 +param set-default CA_ROTOR0_PX 1.4000 +param set-default CA_ROTOR0_PY -1.4000 +param set-default CA_ROTOR0_PZ 0.0000 +param set-default CA_ROTOR10_AX 0.0000 +param set-default CA_ROTOR10_AY 0.0000 +param set-default CA_ROTOR10_AZ -1.0000 +param set-default CA_ROTOR10_CT 6.5000 +param set-default CA_ROTOR10_KM 0.0500 +param set-default CA_ROTOR10_PX 0.0000 +param set-default CA_ROTOR10_PY 0.0000 +param set-default CA_ROTOR10_PZ 0.0000 +param set-default CA_ROTOR11_AX 0.0000 +param set-default CA_ROTOR11_AY 0.0000 +param set-default CA_ROTOR11_AZ -1.0000 +param set-default CA_ROTOR11_CT 6.5000 +param set-default CA_ROTOR11_KM 0.0500 +param set-default CA_ROTOR11_PX 0.0000 +param set-default CA_ROTOR11_PY 0.0000 +param set-default CA_ROTOR11_PZ 0.0000 +param set-default CA_ROTOR1_AX 0.0000 +param set-default CA_ROTOR1_AY 0.0000 +param set-default CA_ROTOR1_AZ -1.0000 +param set-default CA_ROTOR1_CT 6.5000 +param set-default CA_ROTOR1_PX 1.4000 +param set-default CA_ROTOR1_PY 1.4000 +param set-default CA_ROTOR1_PZ 0.0000 +param set-default CA_ROTOR2_AX 0.0000 +param set-default CA_ROTOR2_AY 0.0000 +param set-default CA_ROTOR2_AZ -1.0000 +param set-default CA_ROTOR2_CT 6.5000 +param set-default CA_ROTOR2_KM 0.0500 +param set-default CA_ROTOR2_PX -1.4000 +param set-default CA_ROTOR2_PY -1.4000 +param set-default CA_ROTOR2_PZ 0.0000 +param set-default CA_ROTOR3_AX 0.0000 +param set-default CA_ROTOR3_AY 0.0000 +param set-default CA_ROTOR3_AZ -1.0000 +param set-default CA_ROTOR3_CT 6.5000 +param set-default CA_ROTOR3_PX -1.4000 +param set-default CA_ROTOR3_PY 1.4000 +param set-default CA_ROTOR3_PZ 0.0000 + +param set-default CP_DELAY 0.4000 +param set-default CP_DIST -1.0000 +param set-default CP_GO_NO_DATA 0 +param set-default CP_GUIDE_ANG 30.0000 +param set-default EKF2_TAS_GATE 3.0000 +param set-default EKF2_WIND_NSD 0.0100 +param set-default FLW_TGT_ALT_M 0 +param set-default FLW_TGT_DST 8.0000 +param set-default FLW_TGT_FA 180.0000 +param set-default FLW_TGT_HT 8.0000 +param set-default FLW_TGT_MAX_VEL 5.0000 +param set-default FLW_TGT_RS 0.1000 +param set-default FW_PSP_OFF 0.0000 +param set-default GPS_UBX_DYNMODEL 6 +param set-default HTE_ACC_GATE 3.0000 +param set-default HTE_HT_ERR_INIT 0.1000 +param set-default HTE_HT_NOISE 0.0036 +param set-default HTE_THR_RANGE 0.2000 +param set-default HTE_VXY_THR 10.0000 +param set-default HTE_VZ_THR 2.0000 +param set-default IMU_GYRO_RATEMAX 800 +param set-default LNDMC_ALT_GND 2.0000 +param set-default LNDMC_ROT_MAX 20.0000 +param set-default LNDMC_TRIG_TIME 1.0000 +param set-default LNDMC_XY_VEL_MAX 1.5000 +param set-default LNDMC_Z_VEL_MAX 0.2500 +param set-default MC_ACRO_EXPO 0.0000 +param set-default MC_ACRO_EXPO_Y 0.0000 +param set-default MC_ACRO_P_MAX 100.0000 +param set-default MC_ACRO_R_MAX 100.0000 +param set-default MC_ACRO_SUPEXPO 0.0000 +param set-default MC_ACRO_SUPEXPOY 0.0000 +param set-default MC_ACRO_Y_MAX 100.0000 +param set-default MC_AT_APPLY 1 +param set-default MC_AT_RISE_TIME 0.1400 +param set-default MC_AT_START 0 +param set-default MC_AT_SYSID_AMP 0.7000 +param set-default MC_BAT_SCALE_EN 0 +param set-default MC_MAN_TILT_TAU 0.0000 +param set-default MC_ORBIT_RAD_MAX 1000.0000 +param set-default MC_PITCHRATE_D 0.0100 +param set-default MC_PITCHRATE_FF 0.0000 +param set-default MC_PITCHRATE_I 0.1000 +param set-default MC_PITCHRATE_K 3.0000 +param set-default MC_PITCHRATE_MAX 220.0000 +param set-default MC_PITCHRATE_P 0.1500 +param set-default MC_PITCH_P 1.0000 +param set-default MC_PR_INT_LIM 0.3000 +param set-default MC_ROLLRATE_D 0.0100 +param set-default MC_ROLLRATE_FF 0.0000 +param set-default MC_ROLLRATE_I 0.1000 +param set-default MC_ROLLRATE_K 2.2500 +param set-default MC_ROLLRATE_MAX 220.0000 +param set-default MC_ROLLRATE_P 0.1500 +param set-default MC_ROLL_P 1.0000 +param set-default MC_RR_INT_LIM 0.3000 +param set-default MC_YAWRATE_D 2.0000 +param set-default MC_YAWRATE_FF 0.0000 +param set-default MC_YAWRATE_I 0.0000 +param set-default MC_YAWRATE_K 0.6000 +param set-default MC_YAWRATE_MAX 200.0000 +param set-default MC_YAWRATE_P 1.0000 +param set-default MC_YAW_P 1.0000 +param set-default MC_YAW_WEIGHT 0.4000 +param set-default MC_YR_INT_LIM 0.1000 +param set-default MPC_ALT_MODE 0 +param set-default MPC_HOLD_DZ 0.1000 +param set-default MPC_HOLD_MAX_XY 0.8000 +param set-default MPC_HOLD_MAX_Z 0.6000 +param set-default MPC_LAND_ALT1 10.0000 +param set-default MPC_LAND_ALT2 5.0000 +param set-default MPC_LAND_ALT3 1.0000 +param set-default MPC_LAND_CRWL 0.3000 +param set-default MPC_LAND_RADIUS 1000.0000 +param set-default MPC_LAND_RC_HELP 0 +param set-default MPC_MANTHR_MIN 0.0800 +param set-default MPC_MAN_TILT_MAX 35.0000 +param set-default MPC_MAN_Y_MAX 150.0000 +param set-default MPC_MAN_Y_TAU 0.0800 +param set-default MPC_POS_MODE 4 +param set-default MPC_THR_CURVE 0 +param set-default MPC_THR_HOVER 0.5000 +param set-default MPC_THR_MAX 1.0000 +param set-default MPC_THR_MIN 0.1200 +param set-default MPC_THR_XY_MARG 0.3000 +param set-default MPC_TILTMAX_AIR 45.0000 +param set-default MPC_TILTMAX_LND 12.0000 +param set-default MPC_TKO_RAMP_T 3.0000 +param set-default MPC_TKO_SPEED 1.5000 +param set-default MPC_USE_HTE 1 +param set-default MPC_VELD_LP 5.0000 +param set-default MPC_VEL_MANUAL 10.0000 +param set-default MPC_VEL_MAN_BACK -1.0000 +param set-default MPC_VEL_MAN_SIDE -1.0000 +param set-default MPC_XY_CRUISE 12.0000 +param set-default MPC_XY_ERR_MAX 2.0000 +param set-default MPC_XY_MAN_EXPO 0.6000 +param set-default MPC_XY_P 0.0500 +param set-default MPC_XY_TRAJ_P 0.5000 +param set-default MPC_XY_VEL_ALL -10.0000 +param set-default MPC_XY_VEL_D_ACC 1.5000 +param set-default MPC_XY_VEL_I_ACC 0.2000 +param set-default MPC_XY_VEL_MAX 12.0000 +param set-default MPC_XY_VEL_P_ACC 1.2000 +param set-default MPC_YAWRAUTO_MAX 45.0000 +param set-default MPC_YAW_EXPO 0.6000 +param set-default MPC_YAW_MODE 0 +param set-default MPC_Z_MAN_EXPO 0.6000 +param set-default MPC_Z_P 0.2500 +param set-default MPC_Z_VEL_ALL -3.0000 +param set-default MPC_Z_VEL_D_ACC 0.2000 +param set-default MPC_Z_VEL_I_ACC 2.0000 +param set-default MPC_Z_VEL_MAX_DN 1.5000 +param set-default MPC_Z_VEL_MAX_UP 3.0000 +param set-default MPC_Z_VEL_P_ACC 3.0000 +param set-default NAV_ACC_RAD 2.0000 +param set-default RTL_DESCEND_ALT 10.0000 +param set-default RTL_RETURN_ALT 30.0000 +param set-default SYS_VEHICLE_RESP -0.4000 +param set-default WV_EN 0 +param set-default WV_GAIN 1.0000 +param set-default WV_ROLL_MIN 1.0000 +param set-default WV_YRATE_MAX 90.0000 diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/CMakeLists.txt b/ROMFS/px4fmu_common/init.d-posix/airframes/CMakeLists.txt index 74925d102c99..d93298fd355b 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/CMakeLists.txt +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/CMakeLists.txt @@ -81,6 +81,9 @@ px4_add_romfs_files( 4006_gz_px4vision 4008_gz_advanced_plane + 5001_xplane_c172 + 5010_xplane_ehang4 + 6011_gazebo-classic_typhoon_h480 6011_gazebo-classic_typhoon_h480.post diff --git a/src/modules/simulation/simulator_mavlink/CMakeLists.txt b/src/modules/simulation/simulator_mavlink/CMakeLists.txt index fc4fa94aa4b4..4eecc4a8741b 100644 --- a/src/modules/simulation/simulator_mavlink/CMakeLists.txt +++ b/src/modules/simulation/simulator_mavlink/CMakeLists.txt @@ -71,3 +71,28 @@ add_custom_target(none_iris ${PX4_SOURCE_DIR}/ROMFS/px4fmu_common/init.d-posix/airframes/10016_none_iris COMMENT "launching px4 none_iris (SYS_AUTOSTART=10016)" ) + + +# xplane_c172 (legacy compatibility launch helper) +add_custom_target(xplane_c172 + COMMAND ${CMAKE_COMMAND} -E env PX4_SYS_AUTOSTART=5001 $ + WORKING_DIRECTORY ${SITL_WORKING_DIR} + USES_TERMINAL + DEPENDS + px4 + ${PX4_SOURCE_DIR}/ROMFS/px4fmu_common/init.d-posix/airframes/5001_xplane_c172 + COMMENT "launching px4 none_plane (SYS_AUTOSTART=5001)" +) + + +# xplane_ehang4 (legacy compatibility launch helper) +add_custom_target(xplane_ehang4 + COMMAND ${CMAKE_COMMAND} -E env PX4_SYS_AUTOSTART=5010 $ + WORKING_DIRECTORY ${SITL_WORKING_DIR} + USES_TERMINAL + DEPENDS + px4 + ${PX4_SOURCE_DIR}/ROMFS/px4fmu_common/init.d-posix/airframes/5010_xplane_ehang4 + COMMENT "launching px4 none_plane (SYS_AUTOSTART=5010)" +) + From 36741d87e6053b5a47cb0af9b0ab5d7f59ba8abb Mon Sep 17 00:00:00 2001 From: Alireza Ghaderi Date: Wed, 6 Dec 2023 06:01:26 +0000 Subject: [PATCH 02/25] setting params for ehang and cessna172 --- .../init.d-posix/airframes/5001_xplane_c172 | 7 +- .../init.d-posix/airframes/5010_xplane_ehang4 | 338 ++++++++---------- 2 files changed, 158 insertions(+), 187 deletions(-) diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/5001_xplane_c172 b/ROMFS/px4fmu_common/init.d-posix/airframes/5001_xplane_c172 index d34308d6988f..362f1ef3fbca 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/5001_xplane_c172 +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/5001_xplane_c172 @@ -9,11 +9,10 @@ # # Airframe: Cessna 172 Skyhawk # Compatible Simulator: X-Plane -# Type: Standard Plane -# Class: Plane -# Author: alireza787b +# @type Standard Plane +# @maintainer alireza787b # Date: Nov 2023 -# Project URL: https://github.com/alireza787b/px4xplane/ +# @url https://github.com/alireza787b/px4xplane/ # # ---- Start of Configuration ---- diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/5010_xplane_ehang4 b/ROMFS/px4fmu_common/init.d-posix/airframes/5010_xplane_ehang4 index 9b83ecbc59ff..f49a9b349311 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/5010_xplane_ehang4 +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/5010_xplane_ehang4 @@ -1,215 +1,187 @@ #!/bin/sh # -# @name Generic Iris Quadrotor SITL +# PX4 SITL Configuration Script for Ehang Airtaxi (QuadCopter) in X-Plane # -# @type Quadrotor Wide +# This script configures PX4 SITL for the Ehang Airtaxi, modelled as a quadcopter. +# It's specifically designed for X-Plane simulation, representing a more sophisticated Multirotor simulation. +# +# Usage: Run with 'make px4_sitl xplane_ehang4'. # -#!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!! +# Airframe: Ehang Airtaxi +# Compatible Simulator: X-Plane +# @name ehang4 (QuadCopter) X-Plane SITL +# @type Quadrotor Wide +# @maintainer alireza787b +# Date: Nov 2023 +# @url https://github.com/alireza787b/px4xplane/ + +# ---- Start of Configuration ---- + + . ${R}etc/init.d/rc.mc_defaults param set-default CA_AIRFRAME 0 - param set-default CA_ROTOR_COUNT 4 -param set-default CA_ROTOR0_PX 0.1515 -param set-default CA_ROTOR0_PY 0.245 -param set-default CA_ROTOR0_KM 0.05 -param set-default CA_ROTOR1_PX -0.1515 -param set-default CA_ROTOR1_PY -0.1875 param set-default CA_ROTOR1_KM 0.05 -param set-default CA_ROTOR2_PX 0.1515 -param set-default CA_ROTOR2_PY -0.245 -param set-default CA_ROTOR2_KM -0.05 -param set-default CA_ROTOR3_PX -0.1515 -param set-default CA_ROTOR3_PY 0.1875 param set-default CA_ROTOR3_KM -0.05 - param set-default PWM_MAIN_FUNC1 101 param set-default PWM_MAIN_FUNC2 102 param set-default PWM_MAIN_FUNC3 103 param set-default PWM_MAIN_FUNC4 104 - param set-default CA_FAILURE_MODE 0 param set-default CA_METHOD 2 -param set-default CA_R0_SLEW 0.0000 -param set-default CA_R10_SLEW 0.0000 -param set-default CA_R11_SLEW 0.0000 -param set-default CA_R1_SLEW 0.0000 -param set-default CA_R2_SLEW 0.0000 -param set-default CA_R3_SLEW 0.0000 -param set-default CA_R4_SLEW 0.0000 -param set-default CA_R5_SLEW 0.0000 -param set-default CA_R6_SLEW 0.0000 -param set-default CA_R7_SLEW 0.0000 -param set-default CA_R8_SLEW 0.0000 -param set-default CA_R9_SLEW 0.0000 -param set-default CA_ROTOR0_AX 0.0000 -param set-default CA_ROTOR0_AY 0.0000 -param set-default CA_ROTOR0_AZ -1.0000 -param set-default CA_ROTOR0_CT 6.5000 -param set-default CA_ROTOR0_KM -0.0500 -param set-default CA_ROTOR0_PX 1.4000 -param set-default CA_ROTOR0_PY -1.4000 -param set-default CA_ROTOR0_PZ 0.0000 -param set-default CA_ROTOR10_AX 0.0000 -param set-default CA_ROTOR10_AY 0.0000 -param set-default CA_ROTOR10_AZ -1.0000 -param set-default CA_ROTOR10_CT 6.5000 -param set-default CA_ROTOR10_KM 0.0500 -param set-default CA_ROTOR10_PX 0.0000 -param set-default CA_ROTOR10_PY 0.0000 -param set-default CA_ROTOR10_PZ 0.0000 -param set-default CA_ROTOR11_AX 0.0000 -param set-default CA_ROTOR11_AY 0.0000 -param set-default CA_ROTOR11_AZ -1.0000 -param set-default CA_ROTOR11_CT 6.5000 -param set-default CA_ROTOR11_KM 0.0500 -param set-default CA_ROTOR11_PX 0.0000 -param set-default CA_ROTOR11_PY 0.0000 -param set-default CA_ROTOR11_PZ 0.0000 -param set-default CA_ROTOR1_AX 0.0000 -param set-default CA_ROTOR1_AY 0.0000 -param set-default CA_ROTOR1_AZ -1.0000 -param set-default CA_ROTOR1_CT 6.5000 -param set-default CA_ROTOR1_PX 1.4000 -param set-default CA_ROTOR1_PY 1.4000 -param set-default CA_ROTOR1_PZ 0.0000 -param set-default CA_ROTOR2_AX 0.0000 -param set-default CA_ROTOR2_AY 0.0000 -param set-default CA_ROTOR2_AZ -1.0000 -param set-default CA_ROTOR2_CT 6.5000 -param set-default CA_ROTOR2_KM 0.0500 -param set-default CA_ROTOR2_PX -1.4000 -param set-default CA_ROTOR2_PY -1.4000 -param set-default CA_ROTOR2_PZ 0.0000 -param set-default CA_ROTOR3_AX 0.0000 -param set-default CA_ROTOR3_AY 0.0000 -param set-default CA_ROTOR3_AZ -1.0000 -param set-default CA_ROTOR3_CT 6.5000 -param set-default CA_ROTOR3_PX -1.4000 -param set-default CA_ROTOR3_PY 1.4000 -param set-default CA_ROTOR3_PZ 0.0000 +param set-default CA_ROTOR0_AZ -1 +param set-default CA_ROTOR0_CT 6.5 +param set-default CA_ROTOR0_KM -0.05 +param set-default CA_ROTOR0_PX 1.4 +param set-default CA_ROTOR0_PY -1.4 +param set-default CA_ROTOR1_AX 0 +param set-default CA_ROTOR1_AY 0 +param set-default CA_ROTOR1_AZ -1 +param set-default CA_ROTOR1_CT 6.5 +param set-default CA_ROTOR1_PX 1.4 +param set-default CA_ROTOR1_PY 1.4 +param set-default CA_ROTOR1_PZ 0 +param set-default CA_ROTOR2_AX 0 +param set-default CA_ROTOR2_AY 0 +param set-default CA_ROTOR2_AZ -1 +param set-default CA_ROTOR2_CT 6.5 +param set-default CA_ROTOR2_KM 0.05 +param set-default CA_ROTOR2_PX -1.4 +param set-default CA_ROTOR2_PY -1.4 +param set-default CA_ROTOR2_PZ 0 +param set-default CA_ROTOR3_AX 0 +param set-default CA_ROTOR3_AY 0 +param set-default CA_ROTOR3_AZ -1 +param set-default CA_ROTOR3_CT 6.5 +param set-default CA_ROTOR3_PX -1.4 +param set-default CA_ROTOR3_PY 1.4 +param set-default CA_ROTOR3_PZ 0 -param set-default CP_DELAY 0.4000 -param set-default CP_DIST -1.0000 +param set-default CP_DELAY 0.4 +param set-default CP_DIST -1 param set-default CP_GO_NO_DATA 0 -param set-default CP_GUIDE_ANG 30.0000 -param set-default EKF2_TAS_GATE 3.0000 -param set-default EKF2_WIND_NSD 0.0100 +param set-default CP_GUIDE_ANG 30 +param set-default EKF2_TAS_GATE 3 +param set-default EKF2_WIND_NSD 0.01 param set-default FLW_TGT_ALT_M 0 -param set-default FLW_TGT_DST 8.0000 -param set-default FLW_TGT_FA 180.0000 -param set-default FLW_TGT_HT 8.0000 -param set-default FLW_TGT_MAX_VEL 5.0000 -param set-default FLW_TGT_RS 0.1000 -param set-default FW_PSP_OFF 0.0000 +param set-default FLW_TGT_DST 8 +param set-default FLW_TGT_FA 180 +param set-default FLW_TGT_HT 8 +param set-default FLW_TGT_MAX_VEL 5 +param set-default FLW_TGT_RS 0.1 +param set-default FW_PSP_OFF 0 param set-default GPS_UBX_DYNMODEL 6 -param set-default HTE_ACC_GATE 3.0000 -param set-default HTE_HT_ERR_INIT 0.1000 +param set-default HTE_ACC_GATE 3 +param set-default HTE_HT_ERR_INIT 0.1 param set-default HTE_HT_NOISE 0.0036 -param set-default HTE_THR_RANGE 0.2000 -param set-default HTE_VXY_THR 10.0000 -param set-default HTE_VZ_THR 2.0000 +param set-default HTE_THR_RANGE 0.2 +param set-default HTE_VXY_THR 10 +param set-default HTE_VZ_THR 2 param set-default IMU_GYRO_RATEMAX 800 -param set-default LNDMC_ALT_GND 2.0000 -param set-default LNDMC_ROT_MAX 20.0000 -param set-default LNDMC_TRIG_TIME 1.0000 -param set-default LNDMC_XY_VEL_MAX 1.5000 -param set-default LNDMC_Z_VEL_MAX 0.2500 -param set-default MC_ACRO_EXPO 0.0000 -param set-default MC_ACRO_EXPO_Y 0.0000 -param set-default MC_ACRO_P_MAX 100.0000 -param set-default MC_ACRO_R_MAX 100.0000 -param set-default MC_ACRO_SUPEXPO 0.0000 -param set-default MC_ACRO_SUPEXPOY 0.0000 -param set-default MC_ACRO_Y_MAX 100.0000 +param set-default LNDMC_ALT_GND 2 +param set-default LNDMC_ROT_MAX 20 +param set-default LNDMC_TRIG_TIME 1 +param set-default LNDMC_XY_VEL_MAX 1.5 +param set-default LNDMC_Z_VEL_MAX 0.25 +param set-default MC_ACRO_EXPO 0 +param set-default MC_ACRO_EXPO_Y 0 +param set-default MC_ACRO_P_MAX 100 +param set-default MC_ACRO_R_MAX 100 +param set-default MC_ACRO_SUPEXPO 0 +param set-default MC_ACRO_SUPEXPOY 0 +param set-default MC_ACRO_Y_MAX 100 param set-default MC_AT_APPLY 1 -param set-default MC_AT_RISE_TIME 0.1400 +param set-default MC_AT_RISE_TIME 0.14 param set-default MC_AT_START 0 -param set-default MC_AT_SYSID_AMP 0.7000 +param set-default MC_AT_SYSID_AMP 0.7 param set-default MC_BAT_SCALE_EN 0 -param set-default MC_MAN_TILT_TAU 0.0000 -param set-default MC_ORBIT_RAD_MAX 1000.0000 -param set-default MC_PITCHRATE_D 0.0100 -param set-default MC_PITCHRATE_FF 0.0000 -param set-default MC_PITCHRATE_I 0.1000 -param set-default MC_PITCHRATE_K 3.0000 -param set-default MC_PITCHRATE_MAX 220.0000 -param set-default MC_PITCHRATE_P 0.1500 -param set-default MC_PITCH_P 1.0000 -param set-default MC_PR_INT_LIM 0.3000 -param set-default MC_ROLLRATE_D 0.0100 -param set-default MC_ROLLRATE_FF 0.0000 -param set-default MC_ROLLRATE_I 0.1000 -param set-default MC_ROLLRATE_K 2.2500 -param set-default MC_ROLLRATE_MAX 220.0000 -param set-default MC_ROLLRATE_P 0.1500 -param set-default MC_ROLL_P 1.0000 -param set-default MC_RR_INT_LIM 0.3000 -param set-default MC_YAWRATE_D 2.0000 -param set-default MC_YAWRATE_FF 0.0000 -param set-default MC_YAWRATE_I 0.0000 -param set-default MC_YAWRATE_K 0.6000 -param set-default MC_YAWRATE_MAX 200.0000 -param set-default MC_YAWRATE_P 1.0000 -param set-default MC_YAW_P 1.0000 -param set-default MC_YAW_WEIGHT 0.4000 -param set-default MC_YR_INT_LIM 0.1000 +param set-default MC_MAN_TILT_TAU 0 +param set-default MC_ORBIT_RAD_MAX 1000 +param set-default MC_PITCHRATE_D 0.01 +param set-default MC_PITCHRATE_FF 0 +param set-default MC_PITCHRATE_I 0.1 +param set-default MC_PITCHRATE_K 3 +param set-default MC_PITCHRATE_MAX 220 +param set-default MC_PITCHRATE_P 0.15 +param set-default MC_PR_INT_LIM 0.3 +param set-default MC_ROLLRATE_D 0.01 +param set-default MC_ROLLRATE_FF 0 +param set-default MC_ROLLRATE_I 0.1 +param set-default MC_ROLLRATE_K 2.25 +param set-default MC_ROLLRATE_MAX 220 +param set-default MC_ROLLRATE_P 0.15 +param set-default MC_RR_INT_LIM 0.3 +param set-default MC_YAWRATE_I 0 +param set-default MC_YAWRATE_K 0.6 +param set-default MC_YAW_WEIGHT 0.4 param set-default MPC_ALT_MODE 0 -param set-default MPC_HOLD_DZ 0.1000 -param set-default MPC_HOLD_MAX_XY 0.8000 -param set-default MPC_HOLD_MAX_Z 0.6000 -param set-default MPC_LAND_ALT1 10.0000 -param set-default MPC_LAND_ALT2 5.0000 -param set-default MPC_LAND_ALT3 1.0000 -param set-default MPC_LAND_CRWL 0.3000 -param set-default MPC_LAND_RADIUS 1000.0000 -param set-default MPC_LAND_RC_HELP 0 -param set-default MPC_MANTHR_MIN 0.0800 -param set-default MPC_MAN_TILT_MAX 35.0000 -param set-default MPC_MAN_Y_MAX 150.0000 -param set-default MPC_MAN_Y_TAU 0.0800 +param set-default MPC_HOLD_MAX_XY 0.8 +param set-default MPC_HOLD_MAX_Z 0.6 +param set-default MPC_LAND_ALT1 10 +param set-default MPC_LAND_ALT2 5 +param set-default MPC_LAND_ALT3 1 +param set-default MPC_LAND_CRWL 0.3 +param set-default MPC_LAND_RADIUS 1000 +param set-default MPC_MANTHR_MIN 0.08 +param set-default MPC_MAN_TILT_MAX 35 +param set-default MPC_MAN_Y_TAU 0.08 param set-default MPC_POS_MODE 4 param set-default MPC_THR_CURVE 0 -param set-default MPC_THR_HOVER 0.5000 -param set-default MPC_THR_MAX 1.0000 -param set-default MPC_THR_MIN 0.1200 -param set-default MPC_THR_XY_MARG 0.3000 -param set-default MPC_TILTMAX_AIR 45.0000 -param set-default MPC_TILTMAX_LND 12.0000 -param set-default MPC_TKO_RAMP_T 3.0000 -param set-default MPC_TKO_SPEED 1.5000 +param set-default MPC_THR_HOVER 0.5 +param set-default MPC_THR_MAX 1 +param set-default MPC_THR_MIN 0.12 +param set-default MPC_THR_XY_MARG 0.3 +param set-default MPC_TILTMAX_AIR 45 +param set-default MPC_TILTMAX_LND 12 +param set-default MPC_TKO_RAMP_T 3 +param set-default MPC_TKO_SPEED 1.5 param set-default MPC_USE_HTE 1 -param set-default MPC_VELD_LP 5.0000 -param set-default MPC_VEL_MANUAL 10.0000 -param set-default MPC_VEL_MAN_BACK -1.0000 -param set-default MPC_VEL_MAN_SIDE -1.0000 -param set-default MPC_XY_CRUISE 12.0000 -param set-default MPC_XY_ERR_MAX 2.0000 -param set-default MPC_XY_MAN_EXPO 0.6000 -param set-default MPC_XY_P 0.0500 -param set-default MPC_XY_TRAJ_P 0.5000 -param set-default MPC_XY_VEL_ALL -10.0000 -param set-default MPC_XY_VEL_D_ACC 1.5000 -param set-default MPC_XY_VEL_I_ACC 0.2000 -param set-default MPC_XY_VEL_MAX 12.0000 -param set-default MPC_XY_VEL_P_ACC 1.2000 -param set-default MPC_YAWRAUTO_MAX 45.0000 -param set-default MPC_YAW_EXPO 0.6000 +param set-default MPC_VELD_LP 5 +param set-default MPC_VEL_MANUAL 10 +param set-default MPC_VEL_MAN_BACK -1 +param set-default MPC_VEL_MAN_SIDE -1 +param set-default MPC_XY_ERR_MAX 2 +param set-default MPC_XY_MAN_EXPO 0.6 +param set-default MPC_XY_P 0.05 +param set-default MPC_XY_TRAJ_P 0.5 +param set-default MPC_XY_VEL_ALL -10 +param set-default MPC_XY_VEL_D_ACC 1.5 +param set-default MPC_XY_VEL_I_ACC 0.2 +param set-default MPC_XY_VEL_MAX 12 +param set-default MPC_XY_VEL_P_ACC 1.2 +param set-default MPC_YAW_EXPO 0.6 param set-default MPC_YAW_MODE 0 -param set-default MPC_Z_MAN_EXPO 0.6000 -param set-default MPC_Z_P 0.2500 -param set-default MPC_Z_VEL_ALL -3.0000 -param set-default MPC_Z_VEL_D_ACC 0.2000 -param set-default MPC_Z_VEL_I_ACC 2.0000 -param set-default MPC_Z_VEL_MAX_DN 1.5000 -param set-default MPC_Z_VEL_MAX_UP 3.0000 -param set-default MPC_Z_VEL_P_ACC 3.0000 -param set-default NAV_ACC_RAD 2.0000 -param set-default RTL_DESCEND_ALT 10.0000 -param set-default RTL_RETURN_ALT 30.0000 -param set-default SYS_VEHICLE_RESP -0.4000 +param set-default MPC_Z_MAN_EXPO 0.6 +param set-default MPC_Z_P 0.25 +param set-default MPC_Z_VEL_ALL -3 +param set-default MPC_Z_VEL_D_ACC 0.2 +param set-default MPC_Z_VEL_I_ACC 2 +param set-default MPC_Z_VEL_MAX_DN 1.5 +param set-default MPC_Z_VEL_MAX_UP 3 +param set-default MPC_Z_VEL_P_ACC 3 +param set-default NAV_ACC_RAD 2 +param set-default RTL_DESCEND_ALT 10 +param set-default RTL_RETURN_ALT 30 +param set-default SYS_VEHICLE_RESP -0.4 param set-default WV_EN 0 -param set-default WV_GAIN 1.0000 -param set-default WV_ROLL_MIN 1.0000 -param set-default WV_YRATE_MAX 90.0000 +param set-default WV_GAIN 1 +param set-default WV_ROLL_MIN 1 +param set-default WV_YRATE_MAX 90 +param set-default MC_PITCH_P 0.3 +param set-default MC_ROLL_P 0.3 +param set-default MC_YAWRATE_D 0 +param set-default MC_YAWRATE_FF 0.2 +param set-default MC_YAWRATE_MAX 100 +param set-default MC_YAWRATE_P 2 +param set-default MC_YAW_P 0.6 +param set-default MC_YR_INT_LIM 0.3 +param set-default MPC_HOLD_DZ 0.3 +param set-default MPC_JERK_AUTO 1 +param set-default MPC_JERK_MAX 3 +param set-default MPC_LAND_RC_HELP 1 +param set-default MPC_MAN_Y_MAX 30 +param set-default MPC_XY_CRUISE 10 +param set-default MPC_YAWRAUTO_ACC 20 +param set-default MPC_YAWRAUTO_MAX 30 From 47f71a0e0ef5fe6268995a5aecd24afb8ec9cf0d Mon Sep 17 00:00:00 2001 From: Alireza Ghaderi Date: Wed, 6 Dec 2023 19:16:34 +0000 Subject: [PATCH 03/25] setting params name for ehang and cessna172 --- ROMFS/px4fmu_common/init.d-posix/airframes/5001_xplane_c172 | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/5001_xplane_c172 b/ROMFS/px4fmu_common/init.d-posix/airframes/5001_xplane_c172 index 362f1ef3fbca..f8021500f66b 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/5001_xplane_c172 +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/5001_xplane_c172 @@ -7,7 +7,7 @@ # # Usage: Run with 'make px4_sitl xplane_c172'. # -# Airframe: Cessna 172 Skyhawk +# @name: Cessna 172 Skyhawk # Compatible Simulator: X-Plane # @type Standard Plane # @maintainer alireza787b From f1c17aaff42516d395fcbbdadfa90e20679e7194 Mon Sep 17 00:00:00 2001 From: Alireza Ghaderi Date: Thu, 7 Dec 2023 05:27:49 +0000 Subject: [PATCH 04/25] changes airspeed and roll perfomance params --- .../init.d-posix/airframes/5001_xplane_c172 | 27 +++---------------- 1 file changed, 4 insertions(+), 23 deletions(-) diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/5001_xplane_c172 b/ROMFS/px4fmu_common/init.d-posix/airframes/5001_xplane_c172 index f8021500f66b..a7dab9005228 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/5001_xplane_c172 +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/5001_xplane_c172 @@ -23,7 +23,6 @@ # These parameters define the physical configuration of the Cessna 172 Skyhawk airframe param set-default CA_AIRFRAME 1 param set-default CA_ROTOR_COUNT 1 -param set-default CA_ROTOR0_PX 0.3 # ---- Control Surface Configuration ---- # Configuration of control surfaces for flight control and maneuvering @@ -55,28 +54,17 @@ param set-default PWM_MAIN_FUNC6 204 # ---- Fixed-wing Specific Parameters ---- # Parameters specific to fixed-wing flight dynamics -param set-default FW_AIRSPD_MAX 65.0000 -param set-default FW_AIRSPD_MIN 32.0000 -param set-default FW_AIRSPD_STALL 28.0000 +param set-default FW_AIRSPD_MAX 75.0000 +param set-default FW_AIRSPD_MIN 30.0000 +param set-default FW_AIRSPD_STALL 25.0000 param set-default FW_AIRSPD_TRIM 45.0000 -param set-default MIS_DIST_1WP 3000.0000 param set-default ASPD_FALLBACK_GW 1 -param set-default FW_AIRSPD_STALL 20.0000 -param set-default FW_PN_R_SLEW_MAX 15.0000 -param set-default FW_PR_D 0.2650 -param set-default FW_PR_FF 5.3000 -param set-default FW_PR_I 0.0600 -param set-default FW_PR_P 0.4800 -param set-default FW_P_TC 0.3000 param set-default FW_RR_FF 4.8000 -param set-default FW_RR_P 0.3500 param set-default FW_R_LIM 30.0000 -param set-default FW_R_RMAX 50.0000 -param set-default LNDFW_AIRSPD_MAX 20.0000 param set-default LNDFW_VEL_XY_MAX 15.0000 param set-default FW_LND_FLALT 5.0000 param set-default RTL_LOITER_RAD 1000.0000 -param set-default FW_LND_FL_PMAX 20.0000 +param set-default FW_LND_FL_PMAX 35.0000 # ---- PWM Reversals ---- # Configuration for reversing the PWM signal @@ -104,14 +92,10 @@ param set-default FW_WING_SPAN 11.0000 param set-default MIS_DIST_1WP 5000.0000 param set-default MIS_TAKEOFF_ALT 100.0000 param set-default MIS_TKO_LAND_REQ 0 -param set-default NAV_ACC_RAD 100.0000 -param set-default NAV_FW_ALT_RAD 30.0000 param set-default NAV_LOITER_RAD 1000.0000 -param set-default NAV_MIN_LTR_ALT 300.0000 param set-default RTL_MIN_DIST 50.0000 param set-default WEIGHT_BASE 1000.0000 param set-default WEIGHT_GROSS 1000.0000 -param set-default CA_R0_SLEW 4.0000 param set-default CA_ROTOR0_PX 1.2000 @@ -120,16 +104,13 @@ param set-default EKF2_ABL_ACCLIM 35.0000 param set-default EKF2_MAG_DELAY 1.0000 param set-default FW_LND_ABORT 0 param set-default FW_PN_R_SLEW_MAX 50.0000 -param set-default FW_PR_D 0.5600 param set-default FW_PR_FF 3.4000 param set-default FW_PR_I 0.0450 param set-default FW_PR_P 0.3650 param set-default FW_P_LIM_MAX 20.0000 param set-default FW_P_LIM_MIN -15.0000 param set-default FW_P_TC 0.4500 -param set-default FW_RR_FF 3.6500 param set-default FW_RR_P 0.4700 -param set-default FW_R_LIM 35.0000 param set-default FW_R_RMAX 10.0000 param set-default FW_R_TC 0.6000 param set-default FW_T_ALT_TC 10.0000 From de5be47bdb593ff6e7a247354a3eef0f86399e3d Mon Sep 17 00:00:00 2001 From: Alireza Ghaderi Date: Sat, 9 Dec 2023 12:56:24 +0000 Subject: [PATCH 05/25] Refactor X-Plane SITL targets into dedicated CMake file --- .../simulator_mavlink/CMakeLists.txt | 25 +---------- .../sitl_targets_xplane.cmake | 43 +++++++++++++++++++ 2 files changed, 44 insertions(+), 24 deletions(-) create mode 100644 src/modules/simulation/simulator_mavlink/sitl_targets_xplane.cmake diff --git a/src/modules/simulation/simulator_mavlink/CMakeLists.txt b/src/modules/simulation/simulator_mavlink/CMakeLists.txt index 4eecc4a8741b..37dca1b98607 100644 --- a/src/modules/simulation/simulator_mavlink/CMakeLists.txt +++ b/src/modules/simulation/simulator_mavlink/CMakeLists.txt @@ -59,6 +59,7 @@ include(sitl_targets_flightgear.cmake) include(sitl_targets_gazebo-classic.cmake) include(sitl_targets_jmavsim.cmake) include(sitl_targets_jsbsim.cmake) +include(sitl_targets_xplane.cmake) # none_iris (legacy compatibility launch helper) @@ -72,27 +73,3 @@ add_custom_target(none_iris COMMENT "launching px4 none_iris (SYS_AUTOSTART=10016)" ) - -# xplane_c172 (legacy compatibility launch helper) -add_custom_target(xplane_c172 - COMMAND ${CMAKE_COMMAND} -E env PX4_SYS_AUTOSTART=5001 $ - WORKING_DIRECTORY ${SITL_WORKING_DIR} - USES_TERMINAL - DEPENDS - px4 - ${PX4_SOURCE_DIR}/ROMFS/px4fmu_common/init.d-posix/airframes/5001_xplane_c172 - COMMENT "launching px4 none_plane (SYS_AUTOSTART=5001)" -) - - -# xplane_ehang4 (legacy compatibility launch helper) -add_custom_target(xplane_ehang4 - COMMAND ${CMAKE_COMMAND} -E env PX4_SYS_AUTOSTART=5010 $ - WORKING_DIRECTORY ${SITL_WORKING_DIR} - USES_TERMINAL - DEPENDS - px4 - ${PX4_SOURCE_DIR}/ROMFS/px4fmu_common/init.d-posix/airframes/5010_xplane_ehang4 - COMMENT "launching px4 none_plane (SYS_AUTOSTART=5010)" -) - diff --git a/src/modules/simulation/simulator_mavlink/sitl_targets_xplane.cmake b/src/modules/simulation/simulator_mavlink/sitl_targets_xplane.cmake new file mode 100644 index 000000000000..0fd09386d133 --- /dev/null +++ b/src/modules/simulation/simulator_mavlink/sitl_targets_xplane.cmake @@ -0,0 +1,43 @@ +# sitl_targets_xplane.cmake +# +# This CMake configuration file creates custom targets for SITL airframes +# that are specifically designed to work with the X-Plane simulator. +# +# To add a new X-Plane airframe target, use the macro add_xplane_target defined below. +# This macro simplifies the process of adding new airframe configurations and ensures +# that each target adheres to the required structure for SITL simulation with X-Plane. +# +# Usage: +# add_xplane_target( ) +# Where: +# is the custom target name used for the make command. +# is the unique identifier for the airframe. +# is the name of the airframe file located in the PX4 ROMFS directory. + +# Define a macro to add new X-Plane airframe targets. +macro(add_xplane_target TARGET_NAME SYS_AUTOSTART AIRFRAME_FILE) + add_custom_target(${TARGET_NAME} + COMMAND ${CMAKE_COMMAND} -E env PX4_SYS_AUTOSTART=${SYS_AUTOSTART} $ + WORKING_DIRECTORY ${SITL_WORKING_DIR} + USES_TERMINAL + DEPENDS + px4 + ${PX4_SOURCE_DIR}/ROMFS/px4fmu_common/init.d-posix/airframes/${AIRFRAME_FILE} + COMMENT "Launching PX4 with X-Plane airframe (SYS_AUTOSTART=${SYS_AUTOSTART})" + ) +endmacro() + +# X-Plane Cessna 172 Configuration +add_xplane_target(xplane_c172 5001 5001_xplane_c172) + +# X-Plane eVTOL Air Taxi - ehang4 Configuration +add_xplane_target(xplane_ehang4 5010 5010_xplane_ehang4) + +# Instructions for adding more X-Plane configurations: +# To add additional airframe configurations for X-Plane, follow these steps: +# 1. Ensure the airframe file is present in the PX4 ROMFS directory under init.d-posix/airframes. +# 2. Use the add_xplane_target macro with appropriate parameters to add a new target. +# Example: +# add_xplane_target(new_airframe 1234 1234_new_airframe) +# Replace 'new_airframe' with your target's name, '1234' with your SYS_AUTOSTART ID, +# and '1234_new_airframe' with the corresponding airframe file name. From 2d1332f042e6027b18307a2f4676231ced148245 Mon Sep 17 00:00:00 2001 From: Alireza Ghaderi Date: Sun, 10 Dec 2023 05:29:33 +0000 Subject: [PATCH 06/25] added jerk limitation to smooth the inputs in cessna 172 --- ROMFS/px4fmu_common/init.d-posix/airframes/5001_xplane_c172 | 2 ++ 1 file changed, 2 insertions(+) diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/5001_xplane_c172 b/ROMFS/px4fmu_common/init.d-posix/airframes/5001_xplane_c172 index a7dab9005228..3f58ffac9306 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/5001_xplane_c172 +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/5001_xplane_c172 @@ -109,6 +109,8 @@ param set-default FW_PR_I 0.0450 param set-default FW_PR_P 0.3650 param set-default FW_P_LIM_MAX 20.0000 param set-default FW_P_LIM_MIN -15.0000 +param set-default MPC_JERK_AUTO 1.0000 +param set-default MPC_JERK_MAX 3.0000 param set-default FW_P_TC 0.4500 param set-default FW_RR_P 0.4700 param set-default FW_R_RMAX 10.0000 From 58361eb6542eb373b854c5c66cdbac63a218a0d8 Mon Sep 17 00:00:00 2001 From: Alireza Ghaderi Date: Wed, 20 Dec 2023 06:26:18 +0000 Subject: [PATCH 07/25] added Alia 250 and c172 and ehang4 name changed --- ...5001_xplane_c172 => 5001_xplane_cessna172} | 2 +- ...010_xplane_ehang4 => 5010_xplane_ehang184} | 4 +- .../airframes/5020_xplane_alia250 | 317 ++++++++++++++++++ .../init.d-posix/airframes/CMakeLists.txt | 5 +- .../sitl_targets_xplane.cmake | 9 +- 5 files changed, 329 insertions(+), 8 deletions(-) rename ROMFS/px4fmu_common/init.d-posix/airframes/{5001_xplane_c172 => 5001_xplane_cessna172} (98%) rename ROMFS/px4fmu_common/init.d-posix/airframes/{5010_xplane_ehang4 => 5010_xplane_ehang184} (97%) create mode 100644 ROMFS/px4fmu_common/init.d-posix/airframes/5020_xplane_alia250 diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/5001_xplane_c172 b/ROMFS/px4fmu_common/init.d-posix/airframes/5001_xplane_cessna172 similarity index 98% rename from ROMFS/px4fmu_common/init.d-posix/airframes/5001_xplane_c172 rename to ROMFS/px4fmu_common/init.d-posix/airframes/5001_xplane_cessna172 index 3f58ffac9306..45d3d976d8ec 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/5001_xplane_c172 +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/5001_xplane_cessna172 @@ -5,7 +5,7 @@ # This script configures PX4 SITL for a Cessna 172 Skyhawk, a standard fixed-wing plane. # It's tailored for integration with X-Plane, a custom simulator, facilitating real-world scale simulation. # -# Usage: Run with 'make px4_sitl xplane_c172'. +# Usage: Run with 'make px4_sitl xplane_cessna172'. # # @name: Cessna 172 Skyhawk # Compatible Simulator: X-Plane diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/5010_xplane_ehang4 b/ROMFS/px4fmu_common/init.d-posix/airframes/5010_xplane_ehang184 similarity index 97% rename from ROMFS/px4fmu_common/init.d-posix/airframes/5010_xplane_ehang4 rename to ROMFS/px4fmu_common/init.d-posix/airframes/5010_xplane_ehang184 index f49a9b349311..f08631b8c89e 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/5010_xplane_ehang4 +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/5010_xplane_ehang184 @@ -2,10 +2,10 @@ # # PX4 SITL Configuration Script for Ehang Airtaxi (QuadCopter) in X-Plane # -# This script configures PX4 SITL for the Ehang Airtaxi, modelled as a quadcopter. +# This script configures PX4 SITL for the Ehang 184 Airtaxi, modelled as a quadcopter. # It's specifically designed for X-Plane simulation, representing a more sophisticated Multirotor simulation. # -# Usage: Run with 'make px4_sitl xplane_ehang4'. +# Usage: Run with 'make px4_sitl xplane_ehang184'. # # Airframe: Ehang Airtaxi # Compatible Simulator: X-Plane diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/5020_xplane_alia250 b/ROMFS/px4fmu_common/init.d-posix/airframes/5020_xplane_alia250 new file mode 100644 index 000000000000..2f89bd9d18be --- /dev/null +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/5020_xplane_alia250 @@ -0,0 +1,317 @@ +#!/bin/sh +# +# PX4 SITL Configuration Script for Alia-250 eVTOL in X-Plane +# +# This script configures PX4 SITL for the Alia-250, modeled as an eVTOL aircraft. +# It's tailored for X-Plane simulation, aiming to replicate the unique flight characteristics +# of the Alia-250, with its distributed direct-drive electric propulsion system. +# +# Usage: Run with 'make px4_sitl xplane_alia250'. +# +# Airframe: Alia-250 +# Compatible Simulator: X-Plane +# @name Alia-250 eVTOL X-Plane SITL +# @type Quadrotor VTOL +# @maintainer alireza787b +# Date: dec 2023 +# @url https://github.com/alireza787b/px4xplane/ +# +# ---- Start of Configuration ---- + + + + +. ${R}etc/init.d/rc.vtol_defaults + +param set-default CA_AIRFRAME 2 +param set-default CA_ROTOR_COUNT 5 +param set-default CA_ROTOR1_KM 0.05 +param set-default PWM_MAIN_FUNC1 101 +param set-default PWM_MAIN_FUNC2 102 +param set-default PWM_MAIN_FUNC3 103 +param set-default PWM_MAIN_FUNC4 104 +param set-default CA_FAILURE_MODE 0 +param set-default CA_METHOD 2 +param set-default CA_ROTOR0_AZ -1 +param set-default CA_ROTOR0_CT 6.5 +param set-default CA_ROTOR0_KM -0.05 +param set-default CA_ROTOR1_AX 0 +param set-default CA_ROTOR1_AY 0 +param set-default CA_ROTOR1_AZ -1 +param set-default CA_ROTOR1_CT 6.5 +param set-default CA_ROTOR1_PZ 0 +param set-default CA_ROTOR2_AX 0 +param set-default CA_ROTOR2_AY 0 +param set-default CA_ROTOR2_AZ -1 +param set-default CA_ROTOR2_CT 6.5 +param set-default CA_ROTOR2_PZ 0 +param set-default CA_ROTOR3_AX 0 +param set-default CA_ROTOR3_AY 0 +param set-default CA_ROTOR3_AZ -1 +param set-default CA_ROTOR3_CT 6.5 +param set-default CA_ROTOR3_PZ 0 + +param set-default CP_DELAY 0.4 +param set-default CP_DIST -1 +param set-default CP_GO_NO_DATA 0 +param set-default CP_GUIDE_ANG 30 +param set-default EKF2_TAS_GATE 3 +param set-default EKF2_WIND_NSD 0.01 +param set-default FLW_TGT_ALT_M 0 +param set-default FLW_TGT_DST 8 +param set-default FLW_TGT_FA 180 +param set-default FLW_TGT_HT 8 +param set-default FLW_TGT_MAX_VEL 5 +param set-default FLW_TGT_RS 0.1 +param set-default FW_PSP_OFF 0 +param set-default GPS_UBX_DYNMODEL 6 +param set-default HTE_ACC_GATE 3 +param set-default HTE_HT_ERR_INIT 0.1 +param set-default HTE_HT_NOISE 0.0036 +param set-default HTE_THR_RANGE 0.2 +param set-default HTE_VXY_THR 10 +param set-default HTE_VZ_THR 2 +param set-default IMU_GYRO_RATEMAX 800 +param set-default LNDMC_ALT_GND 2 +param set-default LNDMC_ROT_MAX 20 +param set-default LNDMC_TRIG_TIME 1 +param set-default LNDMC_XY_VEL_MAX 1.5 +param set-default LNDMC_Z_VEL_MAX 0.25 +param set-default MC_ACRO_EXPO 0 +param set-default MC_ACRO_EXPO_Y 0 +param set-default MC_ACRO_P_MAX 100 +param set-default MC_ACRO_R_MAX 100 +param set-default MC_ACRO_SUPEXPO 0 +param set-default MC_ACRO_SUPEXPOY 0 +param set-default MC_ACRO_Y_MAX 100 +param set-default MC_AT_APPLY 1 +param set-default MC_AT_RISE_TIME 0.14 +param set-default MC_AT_START 0 +param set-default MC_AT_SYSID_AMP 0.7 +param set-default MC_BAT_SCALE_EN 0 +param set-default MC_MAN_TILT_TAU 0 +param set-default MC_ORBIT_RAD_MAX 1000 +param set-default MC_PITCHRATE_D 0.01 +param set-default MC_PITCHRATE_FF 0 +param set-default MC_PITCHRATE_I 0.1 +param set-default MC_PITCHRATE_K 3 +param set-default MC_PITCHRATE_MAX 220 +param set-default MC_PITCHRATE_P 0.15 +param set-default MC_PR_INT_LIM 0.3 +param set-default MC_ROLLRATE_D 0.01 +param set-default MC_ROLLRATE_FF 0 +param set-default MC_ROLLRATE_I 0.1 +param set-default MC_ROLLRATE_K 2.25 +param set-default MC_ROLLRATE_MAX 220 +param set-default MC_ROLLRATE_P 0.15 +param set-default MC_RR_INT_LIM 0.3 +param set-default MC_YAWRATE_I 0 +param set-default MC_YAWRATE_K 0.6 +param set-default MC_YAW_WEIGHT 0.4 +param set-default MPC_ALT_MODE 0 +param set-default MPC_HOLD_MAX_XY 0.8 +param set-default MPC_HOLD_MAX_Z 0.6 +param set-default MPC_LAND_ALT1 10 +param set-default MPC_LAND_ALT2 5 +param set-default MPC_LAND_ALT3 1 +param set-default MPC_LAND_CRWL 0.3 +param set-default MPC_LAND_RADIUS 1000 +param set-default MPC_MANTHR_MIN 0.08 +param set-default MPC_MAN_TILT_MAX 35 +param set-default MPC_MAN_Y_TAU 0.08 +param set-default MPC_POS_MODE 4 +param set-default MPC_THR_CURVE 0 +param set-default MPC_THR_HOVER 0.5 +param set-default MPC_THR_MAX 1 +param set-default MPC_THR_MIN 0.12 +param set-default MPC_THR_XY_MARG 0.3 +param set-default MPC_TILTMAX_AIR 45 +param set-default MPC_TILTMAX_LND 12 +param set-default MPC_TKO_RAMP_T 3 +param set-default MPC_TKO_SPEED 1.5 +param set-default MPC_USE_HTE 1 +param set-default MPC_VELD_LP 5 +param set-default MPC_VEL_MANUAL 10 +param set-default MPC_VEL_MAN_BACK -1 +param set-default MPC_VEL_MAN_SIDE -1 +param set-default MPC_XY_ERR_MAX 2 +param set-default MPC_XY_MAN_EXPO 0.6 +param set-default MPC_XY_P 0.05 +param set-default MPC_XY_TRAJ_P 0.5 +param set-default MPC_XY_VEL_ALL -10 +param set-default MPC_XY_VEL_D_ACC 1.5 +param set-default MPC_XY_VEL_I_ACC 0.2 +param set-default MPC_XY_VEL_MAX 12 +param set-default MPC_XY_VEL_P_ACC 1.2 +param set-default MPC_YAW_EXPO 0.6 +param set-default MPC_YAW_MODE 0 +param set-default MPC_Z_MAN_EXPO 0.6 +param set-default MPC_Z_P 0.25 +param set-default MPC_Z_VEL_ALL -3 +param set-default MPC_Z_VEL_D_ACC 0.2 +param set-default MPC_Z_VEL_I_ACC 2 +param set-default MPC_Z_VEL_MAX_DN 1.5 +param set-default MPC_Z_VEL_MAX_UP 3 +param set-default MPC_Z_VEL_P_ACC 3 +param set-default NAV_ACC_RAD 2 +param set-default RTL_DESCEND_ALT 10 +param set-default RTL_RETURN_ALT 30 +param set-default SYS_VEHICLE_RESP -0.4 +param set-default WV_EN 0 +param set-default WV_GAIN 1 +param set-default WV_ROLL_MIN 1 +param set-default WV_YRATE_MAX 90 +param set-default MC_PITCH_P 0.3 +param set-default MC_ROLL_P 0.3 +param set-default MC_YAWRATE_D 0 +param set-default MC_YAWRATE_FF 0.2 +param set-default MC_YAWRATE_MAX 100 +param set-default MC_YAWRATE_P 2 +param set-default MC_YAW_P 0.6 +param set-default MC_YR_INT_LIM 0.3 +param set-default MPC_HOLD_DZ 0.3 +param set-default MPC_JERK_AUTO 1 +param set-default MPC_JERK_MAX 3 +param set-default MPC_LAND_RC_HELP 1 +param set-default MPC_MAN_Y_MAX 30 +param set-default MPC_XY_CRUISE 10 +param set-default MPC_YAWRAUTO_ACC 20 +param set-default MPC_YAWRAUTO_MAX 30 +# ---- Fixed-wing Specific Parameters ---- +# Parameters specific to fixed-wing flight dynamics + +param set-default ASPD_FALLBACK_GW 1 +param set-default FW_RR_FF 4.8000 +param set-default FW_R_LIM 30.0000 +param set-default LNDFW_VEL_XY_MAX 15.0000 +param set-default FW_LND_FLALT 5.0000 +param set-default RTL_LOITER_RAD 1000.0000 +param set-default FW_LND_FL_PMAX 35.0000 + + + +param set-default CA_ROTOR0_PX 3.0000 +param set-default CA_ROTOR0_PY 2.5000 +param set-default CA_ROTOR1_PX 3.0000 +param set-default CA_ROTOR1_PY -2.5000 +param set-default CA_ROTOR2_KM -0.0500 +param set-default CA_ROTOR2_PX -3.0000 +param set-default CA_ROTOR2_PY -2.5000 +param set-default CA_ROTOR3_KM 0.0500 +param set-default CA_ROTOR3_PX -3.0000 +param set-default CA_ROTOR3_PY 2.5000 +param set-default CA_ROTOR4_AX 1.0000 +param set-default CA_ROTOR4_AZ 0.0000 +param set-default CA_ROTOR4_KM -0.0500 +param set-default CA_ROTOR4_PX 5.0000 +param set-default CA_SV_CS0_TRQ_R -0.5000 +param set-default CA_SV_CS0_TYPE 1 +param set-default CA_SV_CS1_TRQ_R 0.5000 +param set-default CA_SV_CS1_TYPE 2 +param set-default CA_SV_CS2_TRQ_P 1.0000 +param set-default CA_SV_CS2_TYPE 3 +param set-default CA_SV_CS3_TRQ_Y 1.0000 +param set-default CA_SV_CS3_TYPE 4 +param set-default CA_SV_CS_COUNT 4 +param set-default MC_PITCHRATE_I 0.0000 +param set-default MC_PITCHRATE_K 4.0000 +param set-default MC_PITCHRATE_P 0.4000 +param set-default MC_PITCH_P 0.5000 +param set-default MC_ROLLRATE_D 0.0030 +param set-default MC_ROLLRATE_I 0.0000 +param set-default MC_ROLLRATE_K 5.0000 +param set-default MC_ROLLRATE_P 0.4000 +param set-default MC_ROLL_P 0.5000 +param set-default MC_YAWRATE_FF 1.0000 +param set-default MC_YAWRATE_K 5.0000 +param set-default MC_YAWRATE_MAX 30.0000 +param set-default MC_YAWRATE_P 1.0000 +param set-default MC_YAW_P 1.0000 +param set-default PWM_MAIN_FUNC5 201 +param set-default PWM_MAIN_FUNC6 202 +param set-default PWM_MAIN_FUNC7 203 +param set-default PWM_MAIN_FUNC8 204 +param set-default PWM_MAIN_FUNC9 105 +param set-default PWM_MAIN_REV 112 +param set-default VT_ARSP_BLEND 25.0000 +param set-default VT_ARSP_TRANS 45.0000 +param set-default VT_B_TRANS_DUR 30.0000 +param set-default VT_B_TRANS_RAMP 5.0000 +param set-default VT_ELEV_MC_LOCK 0 +param set-default VT_FWD_THRUST_EN 0 +param set-default VT_F_TRANS_DUR 30.0000 +param set-default VT_QC_T_ALT_LOSS 100.0000 +param set-default VTO_LOITER_ALT 200.0000 +param set-default VT_TRANS_MIN_TM 8.0000 +param set-default VT_TRANS_TIMEOUT 60.0000 +param set-default VT_TYPE 2 +param set-default EKF2_ABL_ACCLIM 35.0000 +param set-default EKF2_MAG_DELAY 1.0000 +param set-default FW_LND_ABORT 0 +param set-default FW_PN_R_SLEW_MAX 50.0000 +param set-default FW_PR_FF 3.4000 +param set-default FW_PR_I 0.0450 +param set-default FW_PR_P 0.3650 +param set-default FW_P_LIM_MAX 20.0000 +param set-default FW_P_LIM_MIN -15.0000 +param set-default MPC_JERK_AUTO 1.0000 +param set-default MPC_JERK_MAX 3.0000 +param set-default FW_P_TC 0.4500 +param set-default FW_RR_P 0.4700 +param set-default FW_R_RMAX 10.0000 +param set-default FW_R_TC 0.6000 +param set-default FW_T_ALT_TC 10.0000 +param set-default FW_T_I_GAIN_THR 0.0200 +param set-default FW_T_RLL2THR 5.0000 +param set-default FW_T_STE_R_TC 2.5000 +param set-default FW_T_THR_DAMP 0.0000 +param set-default MIS_YAW_ERR 15.0000 +param set-default NAV_ACC_RAD 300.0000 +param set-default NAV_FW_ALT_RAD 50.0000 +param set-default NAV_MIN_LTR_ALT -1.0000 + +param set-default EKF2_MAG_TYPE 0param +param set-default FW_LND_AIRSPD 36.0000 +param set-default FW_PR_D 0.3550 +param set-default FW_RR_D 0.0850 +param set-default FW_RR_I 0.1300 + + +param set-default FW_WING_HEIGHT 3.5000 +param set-default FW_WING_SPAN 17.0000 +param set-default MIS_DIST_1WP 5000.0000 +param set-default MIS_TAKEOFF_ALT 100.0000 +param set-default MIS_TKO_LAND_REQ 0 +param set-default NAV_LOITER_RAD 1000.0000 +param set-default RTL_MIN_DIST 50.0000 +param set-default WEIGHT_BASE 3100.0000 +param set-default WEIGHT_GROSS 3500.0000 + + +param set-default EKF2_ABL_ACCLIM 35.0000 +param set-default EKF2_MAG_DELAY 1.0000 +param set-default FW_LND_ABORT 0 +param set-default FW_PN_R_SLEW_MAX 50.0000 +param set-default FW_PR_FF 3.4000 +param set-default FW_PR_I 0.0450 +param set-default FW_PR_P 0.3650 +param set-default FW_P_LIM_MAX 20.0000 +param set-default FW_P_LIM_MIN -15.0000 +param set-default MPC_JERK_AUTO 1.0000 +param set-default MPC_JERK_MAX 3.0000 +param set-default FW_P_TC 0.4500 +param set-default FW_RR_P 0.4700 +param set-default FW_R_RMAX 10.0000 +param set-default FW_R_TC 0.6000 +param set-default FW_T_ALT_TC 10.0000 +param set-default FW_T_I_GAIN_THR 0.0200 +param set-default FW_T_RLL2THR 5.0000 +param set-default FW_T_STE_R_TC 2.5000 +param set-default FW_T_THR_DAMP 0.0000 + + +param set-default FW_AIRSPD_MAX 70.0000 +param set-default FW_AIRSPD_MIN 35.0000 +param set-default FW_AIRSPD_STALL 30.0000 +param set-default FW_AIRSPD_TRIM 50.0000 +param set-default MC_ORBIT_RAD_MAX 1500.0000 diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/CMakeLists.txt b/ROMFS/px4fmu_common/init.d-posix/airframes/CMakeLists.txt index d93298fd355b..4eb0f153fdd7 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/CMakeLists.txt +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/CMakeLists.txt @@ -81,8 +81,9 @@ px4_add_romfs_files( 4006_gz_px4vision 4008_gz_advanced_plane - 5001_xplane_c172 - 5010_xplane_ehang4 + 5001_xplane_cessna172 + 5010_xplane_ehang184 + 5020_xplane_alia250 6011_gazebo-classic_typhoon_h480 6011_gazebo-classic_typhoon_h480.post diff --git a/src/modules/simulation/simulator_mavlink/sitl_targets_xplane.cmake b/src/modules/simulation/simulator_mavlink/sitl_targets_xplane.cmake index 0fd09386d133..8f62f60d73a4 100644 --- a/src/modules/simulation/simulator_mavlink/sitl_targets_xplane.cmake +++ b/src/modules/simulation/simulator_mavlink/sitl_targets_xplane.cmake @@ -28,10 +28,13 @@ macro(add_xplane_target TARGET_NAME SYS_AUTOSTART AIRFRAME_FILE) endmacro() # X-Plane Cessna 172 Configuration -add_xplane_target(xplane_c172 5001 5001_xplane_c172) +add_xplane_target(xplane_cessna172 5001 5001_xplane_cessna172) -# X-Plane eVTOL Air Taxi - ehang4 Configuration -add_xplane_target(xplane_ehang4 5010 5010_xplane_ehang4) +# X-Plane eVTOL Air Taxi (Quad Copter) - ehang184 Configuration +add_xplane_target(xplane_ehang184 5010 5010_xplane_ehang184) + +# X-Plane eVTOL Air Taxi (Quad VTOL) - Alia-250 Configuration +add_xplane_target(xplane_alia250 5020 5020_xplane_alia250) # Instructions for adding more X-Plane configurations: # To add additional airframe configurations for X-Plane, follow these steps: From 3625e75d44f9664ea52ab3c3716ff0364b31958a Mon Sep 17 00:00:00 2001 From: Alireza Ghaderi Date: Sun, 7 Jan 2024 07:20:14 +0000 Subject: [PATCH 08/25] updated performance specs for better flight --- .../airframes/5020_xplane_alia250 | 89 ++++++------------- 1 file changed, 27 insertions(+), 62 deletions(-) diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/5020_xplane_alia250 b/ROMFS/px4fmu_common/init.d-posix/airframes/5020_xplane_alia250 index 2f89bd9d18be..7c6b0c259507 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/5020_xplane_alia250 +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/5020_xplane_alia250 @@ -93,20 +93,20 @@ param set-default MC_MAN_TILT_TAU 0 param set-default MC_ORBIT_RAD_MAX 1000 param set-default MC_PITCHRATE_D 0.01 param set-default MC_PITCHRATE_FF 0 -param set-default MC_PITCHRATE_I 0.1 -param set-default MC_PITCHRATE_K 3 +param set-default MC_PITCHRATE_I 0 +param set-default MC_PITCHRATE_K 4 param set-default MC_PITCHRATE_MAX 220 -param set-default MC_PITCHRATE_P 0.15 +param set-default MC_PITCHRATE_P 0.4 param set-default MC_PR_INT_LIM 0.3 -param set-default MC_ROLLRATE_D 0.01 +param set-default MC_ROLLRATE_D 0.003 param set-default MC_ROLLRATE_FF 0 -param set-default MC_ROLLRATE_I 0.1 -param set-default MC_ROLLRATE_K 2.25 +param set-default MC_ROLLRATE_I 0 +param set-default MC_ROLLRATE_K 5 param set-default MC_ROLLRATE_MAX 220 -param set-default MC_ROLLRATE_P 0.15 +param set-default MC_ROLLRATE_P 0.4 param set-default MC_RR_INT_LIM 0.3 param set-default MC_YAWRATE_I 0 -param set-default MC_YAWRATE_K 0.6 +param set-default MC_YAWRATE_K 5 param set-default MC_YAW_WEIGHT 0.4 param set-default MPC_ALT_MODE 0 param set-default MPC_HOLD_MAX_XY 0.8 @@ -153,21 +153,20 @@ param set-default MPC_Z_VEL_I_ACC 2 param set-default MPC_Z_VEL_MAX_DN 1.5 param set-default MPC_Z_VEL_MAX_UP 3 param set-default MPC_Z_VEL_P_ACC 3 -param set-default NAV_ACC_RAD 2 -param set-default RTL_DESCEND_ALT 10 -param set-default RTL_RETURN_ALT 30 +param set-default RTL_DESCEND_ALT 600 +param set-default RTL_RETURN_ALT 100 param set-default SYS_VEHICLE_RESP -0.4 param set-default WV_EN 0 param set-default WV_GAIN 1 param set-default WV_ROLL_MIN 1 param set-default WV_YRATE_MAX 90 -param set-default MC_PITCH_P 0.3 -param set-default MC_ROLL_P 0.3 +param set-default MC_PITCH_P 0.5 +param set-default MC_ROLL_P 0.5 param set-default MC_YAWRATE_D 0 -param set-default MC_YAWRATE_FF 0.2 -param set-default MC_YAWRATE_MAX 100 -param set-default MC_YAWRATE_P 2 -param set-default MC_YAW_P 0.6 +param set-default MC_YAWRATE_FF 1 +param set-default MC_YAWRATE_MAX 30 +param set-default MC_YAWRATE_P 1 +param set-default MC_YAW_P 1 param set-default MC_YR_INT_LIM 0.3 param set-default MPC_HOLD_DZ 0.3 param set-default MPC_JERK_AUTO 1 @@ -181,7 +180,7 @@ param set-default MPC_YAWRAUTO_MAX 30 # Parameters specific to fixed-wing flight dynamics param set-default ASPD_FALLBACK_GW 1 -param set-default FW_RR_FF 4.8000 +param set-default FW_RR_FF 1 param set-default FW_R_LIM 30.0000 param set-default LNDFW_VEL_XY_MAX 15.0000 param set-default FW_LND_FLALT 5.0000 @@ -213,20 +212,6 @@ param set-default CA_SV_CS2_TYPE 3 param set-default CA_SV_CS3_TRQ_Y 1.0000 param set-default CA_SV_CS3_TYPE 4 param set-default CA_SV_CS_COUNT 4 -param set-default MC_PITCHRATE_I 0.0000 -param set-default MC_PITCHRATE_K 4.0000 -param set-default MC_PITCHRATE_P 0.4000 -param set-default MC_PITCH_P 0.5000 -param set-default MC_ROLLRATE_D 0.0030 -param set-default MC_ROLLRATE_I 0.0000 -param set-default MC_ROLLRATE_K 5.0000 -param set-default MC_ROLLRATE_P 0.4000 -param set-default MC_ROLL_P 0.5000 -param set-default MC_YAWRATE_FF 1.0000 -param set-default MC_YAWRATE_K 5.0000 -param set-default MC_YAWRATE_MAX 30.0000 -param set-default MC_YAWRATE_P 1.0000 -param set-default MC_YAW_P 1.0000 param set-default PWM_MAIN_FUNC5 201 param set-default PWM_MAIN_FUNC6 202 param set-default PWM_MAIN_FUNC7 203 @@ -241,7 +226,7 @@ param set-default VT_ELEV_MC_LOCK 0 param set-default VT_FWD_THRUST_EN 0 param set-default VT_F_TRANS_DUR 30.0000 param set-default VT_QC_T_ALT_LOSS 100.0000 -param set-default VTO_LOITER_ALT 200.0000 +param set-default VTO_LOITER_ALT 1000.0000 param set-default VT_TRANS_MIN_TM 8.0000 param set-default VT_TRANS_TIMEOUT 60.0000 param set-default VT_TYPE 2 @@ -254,11 +239,9 @@ param set-default FW_PR_I 0.0450 param set-default FW_PR_P 0.3650 param set-default FW_P_LIM_MAX 20.0000 param set-default FW_P_LIM_MIN -15.0000 -param set-default MPC_JERK_AUTO 1.0000 -param set-default MPC_JERK_MAX 3.0000 param set-default FW_P_TC 0.4500 param set-default FW_RR_P 0.4700 -param set-default FW_R_RMAX 10.0000 +param set-default FW_R_RMAX 20.0000 param set-default FW_R_TC 0.6000 param set-default FW_T_ALT_TC 10.0000 param set-default FW_T_I_GAIN_THR 0.0200 @@ -271,7 +254,7 @@ param set-default NAV_FW_ALT_RAD 50.0000 param set-default NAV_MIN_LTR_ALT -1.0000 param set-default EKF2_MAG_TYPE 0param -param set-default FW_LND_AIRSPD 36.0000 +param set-default FW_LND_AIRSPD 0 param set-default FW_PR_D 0.3550 param set-default FW_RR_D 0.0850 param set-default FW_RR_I 0.1300 @@ -288,30 +271,12 @@ param set-default WEIGHT_BASE 3100.0000 param set-default WEIGHT_GROSS 3500.0000 -param set-default EKF2_ABL_ACCLIM 35.0000 -param set-default EKF2_MAG_DELAY 1.0000 -param set-default FW_LND_ABORT 0 -param set-default FW_PN_R_SLEW_MAX 50.0000 -param set-default FW_PR_FF 3.4000 -param set-default FW_PR_I 0.0450 -param set-default FW_PR_P 0.3650 -param set-default FW_P_LIM_MAX 20.0000 -param set-default FW_P_LIM_MIN -15.0000 -param set-default MPC_JERK_AUTO 1.0000 -param set-default MPC_JERK_MAX 3.0000 -param set-default FW_P_TC 0.4500 -param set-default FW_RR_P 0.4700 -param set-default FW_R_RMAX 10.0000 -param set-default FW_R_TC 0.6000 -param set-default FW_T_ALT_TC 10.0000 -param set-default FW_T_I_GAIN_THR 0.0200 -param set-default FW_T_RLL2THR 5.0000 -param set-default FW_T_STE_R_TC 2.5000 -param set-default FW_T_THR_DAMP 0.0000 - -param set-default FW_AIRSPD_MAX 70.0000 -param set-default FW_AIRSPD_MIN 35.0000 -param set-default FW_AIRSPD_STALL 30.0000 -param set-default FW_AIRSPD_TRIM 50.0000 +param set-default FW_AIRSPD_MAX 75.0000 +param set-default FW_AIRSPD_MIN 43.0000 +param set-default FW_AIRSPD_STALL 40.0000 +param set-default FW_AIRSPD_TRIM 52.0000 param set-default MC_ORBIT_RAD_MAX 1500.0000 + +param set-default FW_T_SINK_MAX 6.0000 +param set-default FW_T_SINK_MIN 3.0000 From 997f5306009d5105d514f1cda3328c4ded930bd6 Mon Sep 17 00:00:00 2001 From: Alireza Ghaderi Date: Tue, 9 Jan 2024 07:35:59 +0000 Subject: [PATCH 09/25] improved Alia250 performance speeds --- .../init.d-posix/airframes/5020_xplane_alia250 | 14 +++++++------- 1 file changed, 7 insertions(+), 7 deletions(-) diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/5020_xplane_alia250 b/ROMFS/px4fmu_common/init.d-posix/airframes/5020_xplane_alia250 index 7c6b0c259507..2afe4d12d1ea 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/5020_xplane_alia250 +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/5020_xplane_alia250 @@ -98,10 +98,10 @@ param set-default MC_PITCHRATE_K 4 param set-default MC_PITCHRATE_MAX 220 param set-default MC_PITCHRATE_P 0.4 param set-default MC_PR_INT_LIM 0.3 -param set-default MC_ROLLRATE_D 0.003 +param set-default MC_ROLLRATE_D 0.0044 param set-default MC_ROLLRATE_FF 0 param set-default MC_ROLLRATE_I 0 -param set-default MC_ROLLRATE_K 5 +param set-default MC_ROLLRATE_K 2.25 param set-default MC_ROLLRATE_MAX 220 param set-default MC_ROLLRATE_P 0.4 param set-default MC_RR_INT_LIM 0.3 @@ -153,7 +153,7 @@ param set-default MPC_Z_VEL_I_ACC 2 param set-default MPC_Z_VEL_MAX_DN 1.5 param set-default MPC_Z_VEL_MAX_UP 3 param set-default MPC_Z_VEL_P_ACC 3 -param set-default RTL_DESCEND_ALT 600 +param set-default RTL_DESCEND_ALT 300 param set-default RTL_RETURN_ALT 100 param set-default SYS_VEHICLE_RESP -0.4 param set-default WV_EN 0 @@ -161,7 +161,7 @@ param set-default WV_GAIN 1 param set-default WV_ROLL_MIN 1 param set-default WV_YRATE_MAX 90 param set-default MC_PITCH_P 0.5 -param set-default MC_ROLL_P 0.5 +param set-default MC_ROLL_P 0.3 param set-default MC_YAWRATE_D 0 param set-default MC_YAWRATE_FF 1 param set-default MC_YAWRATE_MAX 30 @@ -219,7 +219,7 @@ param set-default PWM_MAIN_FUNC8 204 param set-default PWM_MAIN_FUNC9 105 param set-default PWM_MAIN_REV 112 param set-default VT_ARSP_BLEND 25.0000 -param set-default VT_ARSP_TRANS 45.0000 +param set-default VT_ARSP_TRANS 40.0000 param set-default VT_B_TRANS_DUR 30.0000 param set-default VT_B_TRANS_RAMP 5.0000 param set-default VT_ELEV_MC_LOCK 0 @@ -273,8 +273,8 @@ param set-default WEIGHT_GROSS 3500.0000 param set-default FW_AIRSPD_MAX 75.0000 -param set-default FW_AIRSPD_MIN 43.0000 -param set-default FW_AIRSPD_STALL 40.0000 +param set-default FW_AIRSPD_MIN 40.0000 +param set-default FW_AIRSPD_STALL 38.0000 param set-default FW_AIRSPD_TRIM 52.0000 param set-default MC_ORBIT_RAD_MAX 1500.0000 From b84f97454105e932970cfd27578558fcffd98f16 Mon Sep 17 00:00:00 2001 From: Alireza Ghaderi Date: Sun, 14 Apr 2024 15:19:18 +0000 Subject: [PATCH 10/25] added tb2 --- .../init.d-posix/airframes/5002_xplane_tb2 | 60 +++++++++++++++++++ .../init.d-posix/airframes/CMakeLists.txt | 1 + .../sitl_targets_xplane.cmake | 3 + 3 files changed, 64 insertions(+) create mode 100644 ROMFS/px4fmu_common/init.d-posix/airframes/5002_xplane_tb2 diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/5002_xplane_tb2 b/ROMFS/px4fmu_common/init.d-posix/airframes/5002_xplane_tb2 new file mode 100644 index 000000000000..d657e360722d --- /dev/null +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/5002_xplane_tb2 @@ -0,0 +1,60 @@ +#!/bin/sh +# +# @name TB2 Fixed Wing Aircraft +# +# @type Plane A-Tail +# @class Plane +# +# @output Motor1 throttle +# @output Servo1 aileron right +# @output Servo2 aileron left +# @output Servo3 v-tail right +# @output Servo4 v-tail left +# @output Servo5 wheel +# @output Servo6 flaps right +# @output Servo7 flaps left +# +# @maintainer Alireza Ghaderi @alireza787b +# +# + +. ${R}etc/init.d/rc.fw_defaults + +param set-default FW_MAN_P_MAX 55 +param set-default FW_MAN_R_MAX 55 +param set-default FW_R_LIM 55 + +param set-default FW_WR_FF 0.2 +param set-default FW_WR_I 0.2 +param set-default FW_WR_IMAX 0.8 +param set-default FW_WR_P 1 +param set-default FW_W_RMAX 0 + +param set-default CA_AIRFRAME 1 +param set-default CA_ROTOR_COUNT 1 +param set-default CA_SV_CS_COUNT 7 +param set-default CA_SV_CS0_TRQ_R -0.5 +param set-default CA_SV_CS0_TYPE 1 #left aileron +param set-default CA_SV_CS1_TRQ_R 0.5 +param set-default CA_SV_CS1_TYPE 2 #right aileron +param set-default CA_SV_CS2_TRQ_P 0.5 +param set-default CA_SV_CS2_TRQ_Y -0.5 +param set-default CA_SV_CS2_TYPE 13 #left V-tail +param set-default CA_SV_CS3_TRQ_P 0.5 +param set-default CA_SV_CS3_TRQ_Y 0.5 +param set-default CA_SV_CS3_TYPE 14 #right V-tail +param set-default CA_SV_CS4_TRQ_Y 1 +param set-default CA_SV_CS4_TYPE 12 #wheel +param set-default CA_SV_CS5_TYPE 9 #left flap +param set-default CA_SV_CS6_TYPE 10 #right flap +param set-default PWM_MAIN_FUNC1 201 +param set-default PWM_MAIN_FUNC2 202 +param set-default PWM_MAIN_FUNC3 203 +param set-default PWM_MAIN_FUNC4 204 +param set-default PWM_MAIN_FUNC5 101 +param set-default PWM_MAIN_FUNC6 205 +param set-default PWM_MAIN_FUNC7 206 +param set-default PWM_MAIN_FUNC8 207 + + + diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/CMakeLists.txt b/ROMFS/px4fmu_common/init.d-posix/airframes/CMakeLists.txt index b4d4c4d08218..4c25737fdf85 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/CMakeLists.txt +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/CMakeLists.txt @@ -85,6 +85,7 @@ px4_add_romfs_files( 4011_gz_lawnmower 5001_xplane_cessna172 + 5002_xplane_tb2 5010_xplane_ehang184 5020_xplane_alia250 diff --git a/src/modules/simulation/simulator_mavlink/sitl_targets_xplane.cmake b/src/modules/simulation/simulator_mavlink/sitl_targets_xplane.cmake index 8f62f60d73a4..8fd72558f647 100644 --- a/src/modules/simulation/simulator_mavlink/sitl_targets_xplane.cmake +++ b/src/modules/simulation/simulator_mavlink/sitl_targets_xplane.cmake @@ -30,6 +30,9 @@ endmacro() # X-Plane Cessna 172 Configuration add_xplane_target(xplane_cessna172 5001 5001_xplane_cessna172) +# X-Plane TB 2 Fixed Wing A-Tail Configuration +add_xplane_target(xplane_tb2 5002 5002_xplane_tb2) + # X-Plane eVTOL Air Taxi (Quad Copter) - ehang184 Configuration add_xplane_target(xplane_ehang184 5010 5010_xplane_ehang184) From 8450e19441b27052fcba3311faf8cab918fb1c52 Mon Sep 17 00:00:00 2001 From: Alireza Ghaderi Date: Tue, 16 Apr 2024 06:33:22 +0000 Subject: [PATCH 11/25] added 5002_xplane_tb2 --- .../init.d-posix/airframes/5002_xplane_tb2 | 83 ++++++++++++++----- 1 file changed, 62 insertions(+), 21 deletions(-) diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/5002_xplane_tb2 b/ROMFS/px4fmu_common/init.d-posix/airframes/5002_xplane_tb2 index d657e360722d..bf73056b07ab 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/5002_xplane_tb2 +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/5002_xplane_tb2 @@ -1,7 +1,6 @@ #!/bin/sh # # @name TB2 Fixed Wing Aircraft -# # @type Plane A-Tail # @class Plane # @@ -14,39 +13,33 @@ # @output Servo6 flaps right # @output Servo7 flaps left # -# @maintainer Alireza Ghaderi @alireza787b -# +# @maintainer Alireza Ghaderi # . ${R}etc/init.d/rc.fw_defaults -param set-default FW_MAN_P_MAX 55 -param set-default FW_MAN_R_MAX 55 -param set-default FW_R_LIM 55 - -param set-default FW_WR_FF 0.2 -param set-default FW_WR_I 0.2 -param set-default FW_WR_IMAX 0.8 -param set-default FW_WR_P 1 -param set-default FW_W_RMAX 0 - +# --- Aircraft Configuration --- param set-default CA_AIRFRAME 1 param set-default CA_ROTOR_COUNT 1 param set-default CA_SV_CS_COUNT 7 + +# --- Control Surface Configuration --- +param set-default CA_SV_CS0_TYPE 1 # Left aileron param set-default CA_SV_CS0_TRQ_R -0.5 -param set-default CA_SV_CS0_TYPE 1 #left aileron +param set-default CA_SV_CS1_TYPE 2 # Right aileron param set-default CA_SV_CS1_TRQ_R 0.5 -param set-default CA_SV_CS1_TYPE 2 #right aileron +param set-default CA_SV_CS2_TYPE 13 # Left V-tail param set-default CA_SV_CS2_TRQ_P 0.5 param set-default CA_SV_CS2_TRQ_Y -0.5 -param set-default CA_SV_CS2_TYPE 13 #left V-tail +param set-default CA_SV_CS3_TYPE 14 # Right V-tail param set-default CA_SV_CS3_TRQ_P 0.5 param set-default CA_SV_CS3_TRQ_Y 0.5 -param set-default CA_SV_CS3_TYPE 14 #right V-tail -param set-default CA_SV_CS4_TRQ_Y 1 -param set-default CA_SV_CS4_TYPE 12 #wheel -param set-default CA_SV_CS5_TYPE 9 #left flap -param set-default CA_SV_CS6_TYPE 10 #right flap +param set-default CA_SV_CS4_TYPE 16 # Wheel +param set-default CA_SV_CS4_TRQ_Y 0 +param set-default CA_SV_CS5_TYPE 9 # Left flap +param set-default CA_SV_CS6_TYPE 10 # Right flap + +# --- PWM Configuration and Reversals --- param set-default PWM_MAIN_FUNC1 201 param set-default PWM_MAIN_FUNC2 202 param set-default PWM_MAIN_FUNC3 203 @@ -55,6 +48,54 @@ param set-default PWM_MAIN_FUNC5 101 param set-default PWM_MAIN_FUNC6 205 param set-default PWM_MAIN_FUNC7 206 param set-default PWM_MAIN_FUNC8 207 +param set-default PWM_MAIN_REV 15 # PWM signal reversal configuration + +# --- Flight Performance Parameters --- +param set-default FW_MAN_P_MAX 55 +param set-default FW_MAN_R_MAX 55 +param set-default FW_R_LIM 30 +param set-default FW_WR_FF 0.2 +param set-default FW_WR_I 0.2 +param set-default FW_WR_IMAX 0.8 +param set-default FW_WR_P 1 +param set-default FW_W_RMAX 0 + +# --- Sensor Simulation --- +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 + +# --- Airspeed and Flight Mode Settings --- +param set-default FW_AIRSPD_MAX 80 +param set-default FW_AIRSPD_MIN 30 +param set-default FW_AIRSPD_STALL 25 +param set-default FW_AIRSPD_TRIM 45 +param set-default ASPD_FALLBACK_GW 1 + +# --- Landing and RTL Parameters --- +param set-default FW_LND_FLALT 5 +param set-default RTL_LOITER_RAD 1000 +param set-default FW_LND_FL_PMAX 35 +param set-default FW_TKO_AIRSPD 32 +param set-default FW_TKO_PITCH_MIN 20 +param set-default FW_T_CLMB_MAX 6 +param set-default FW_WING_HEIGHT 2.5 +param set-default FW_WING_SPAN 11 +param set-default MIS_DIST_1WP 5000 +param set-default MIS_TAKEOFF_ALT 100 +param set-default MIS_TKO_LAND_REQ 0 +param set-default RTL_MIN_DIST 50 +# --- Safety and Breakers --- +param set-default CBRK_USB_CHK 197848 # Disable USB check +param set-default CBRK_SUPPLY_CHK 894281 # Disable real battery check +param set-default CBRK_IO_SAFETY 22027 # Disable safety switch check +# --- Miscellaneous Settings --- +param set-default SDLOG_MODE 0 +param set-default SYS_HAS_MAG 1 +param set-default NAV_LOITER_RAD 1000 +param set-default EKF2_MAG_TYPE 0 +# --- End of Configuration --- From e109c1280c594448c485393cf83b3293ab9ba41b Mon Sep 17 00:00:00 2001 From: Alireza Ghaderi Date: Sat, 20 Jul 2024 06:16:04 +0000 Subject: [PATCH 12/25] fix duplicated empty line --- src/modules/simulation/simulator_mavlink/CMakeLists.txt | 1 - 1 file changed, 1 deletion(-) diff --git a/src/modules/simulation/simulator_mavlink/CMakeLists.txt b/src/modules/simulation/simulator_mavlink/CMakeLists.txt index 37dca1b98607..222d948f4003 100644 --- a/src/modules/simulation/simulator_mavlink/CMakeLists.txt +++ b/src/modules/simulation/simulator_mavlink/CMakeLists.txt @@ -72,4 +72,3 @@ add_custom_target(none_iris ${PX4_SOURCE_DIR}/ROMFS/px4fmu_common/init.d-posix/airframes/10016_none_iris COMMENT "launching px4 none_iris (SYS_AUTOSTART=10016)" ) - From 87dca6e3efa4adee6926def3b819542ebbcb9725 Mon Sep 17 00:00:00 2001 From: Alireza Ghaderi Date: Sat, 24 Aug 2024 12:37:06 +0000 Subject: [PATCH 13/25] fixed missed params --- ROMFS/px4fmu_common/init.d-posix/airframes/5010_xplane_ehang184 | 1 + ROMFS/px4fmu_common/init.d-posix/airframes/5020_xplane_alia250 | 2 -- 2 files changed, 1 insertion(+), 2 deletions(-) diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/5010_xplane_ehang184 b/ROMFS/px4fmu_common/init.d-posix/airframes/5010_xplane_ehang184 index f08631b8c89e..46ea7b86709c 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/5010_xplane_ehang184 +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/5010_xplane_ehang184 @@ -59,6 +59,7 @@ param set-default CA_ROTOR3_PX -1.4 param set-default CA_ROTOR3_PY 1.4 param set-default CA_ROTOR3_PZ 0 +param set-default EKF2_ABL_TAU 1 param set-default CP_DELAY 0.4 param set-default CP_DIST -1 param set-default CP_GO_NO_DATA 0 diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/5020_xplane_alia250 b/ROMFS/px4fmu_common/init.d-posix/airframes/5020_xplane_alia250 index 2afe4d12d1ea..f793c3014251 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/5020_xplane_alia250 +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/5020_xplane_alia250 @@ -244,10 +244,8 @@ param set-default FW_RR_P 0.4700 param set-default FW_R_RMAX 20.0000 param set-default FW_R_TC 0.6000 param set-default FW_T_ALT_TC 10.0000 -param set-default FW_T_I_GAIN_THR 0.0200 param set-default FW_T_RLL2THR 5.0000 param set-default FW_T_STE_R_TC 2.5000 -param set-default FW_T_THR_DAMP 0.0000 param set-default MIS_YAW_ERR 15.0000 param set-default NAV_ACC_RAD 300.0000 param set-default NAV_FW_ALT_RAD 50.0000 From 122b312a903ab3ecc61d224728b9baf101c6d0d2 Mon Sep 17 00:00:00 2001 From: Alireza Ghaderi Date: Mon, 26 Aug 2024 04:50:41 +0000 Subject: [PATCH 14/25] Update 5010_xplane_ehang184 --- ROMFS/px4fmu_common/init.d-posix/airframes/5010_xplane_ehang184 | 2 ++ 1 file changed, 2 insertions(+) diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/5010_xplane_ehang184 b/ROMFS/px4fmu_common/init.d-posix/airframes/5010_xplane_ehang184 index 46ea7b86709c..d59f896fb7bc 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/5010_xplane_ehang184 +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/5010_xplane_ehang184 @@ -60,6 +60,8 @@ param set-default CA_ROTOR3_PY 1.4 param set-default CA_ROTOR3_PZ 0 param set-default EKF2_ABL_TAU 1 +param set-default EKF2_ABL_LIM 1 +param set-default COM_ARM_EKF_VEL 1 param set-default CP_DELAY 0.4 param set-default CP_DIST -1 param set-default CP_GO_NO_DATA 0 From 29998b97439d8eb1d11c950563724db4560aa830 Mon Sep 17 00:00:00 2001 From: Alireza Ghaderi Date: Mon, 26 Aug 2024 05:11:11 +0000 Subject: [PATCH 15/25] Update 5010_xplane_ehang184 --- ROMFS/px4fmu_common/init.d-posix/airframes/5010_xplane_ehang184 | 1 - 1 file changed, 1 deletion(-) diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/5010_xplane_ehang184 b/ROMFS/px4fmu_common/init.d-posix/airframes/5010_xplane_ehang184 index d59f896fb7bc..b3cadee1260c 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/5010_xplane_ehang184 +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/5010_xplane_ehang184 @@ -61,7 +61,6 @@ param set-default CA_ROTOR3_PZ 0 param set-default EKF2_ABL_TAU 1 param set-default EKF2_ABL_LIM 1 -param set-default COM_ARM_EKF_VEL 1 param set-default CP_DELAY 0.4 param set-default CP_DIST -1 param set-default CP_GO_NO_DATA 0 From c0da531c6db11488742a9a110cbe856649724e57 Mon Sep 17 00:00:00 2001 From: Alireza Ghaderi Date: Thu, 29 Aug 2024 06:42:34 +0000 Subject: [PATCH 16/25] accel bias ekf2 and baro --- .../init.d-posix/airframes/5010_xplane_ehang184 | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/5010_xplane_ehang184 b/ROMFS/px4fmu_common/init.d-posix/airframes/5010_xplane_ehang184 index d59f896fb7bc..c0dff5ae7b03 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/5010_xplane_ehang184 +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/5010_xplane_ehang184 @@ -59,9 +59,8 @@ param set-default CA_ROTOR3_PX -1.4 param set-default CA_ROTOR3_PY 1.4 param set-default CA_ROTOR3_PZ 0 -param set-default EKF2_ABL_TAU 1 -param set-default EKF2_ABL_LIM 1 -param set-default COM_ARM_EKF_VEL 1 +param set-default EKF2_ABL_TAU 1 +param set-default EKF2_ABL_LIM 0.8 param set-default CP_DELAY 0.4 param set-default CP_DIST -1 param set-default CP_GO_NO_DATA 0 From cf28d940c0304b1bfe0fd6ba2555ee52b2398a47 Mon Sep 17 00:00:00 2001 From: Alireza Ghaderi Date: Thu, 29 Aug 2024 06:46:54 +0000 Subject: [PATCH 17/25] accel bias rating --- .../init.d-posix/airframes/5001_xplane_cessna172 | 4 ++++ ROMFS/px4fmu_common/init.d-posix/airframes/5002_xplane_tb2 | 4 ++++ .../px4fmu_common/init.d-posix/airframes/5020_xplane_alia250 | 4 ++++ 3 files changed, 12 insertions(+) diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/5001_xplane_cessna172 b/ROMFS/px4fmu_common/init.d-posix/airframes/5001_xplane_cessna172 index 45d3d976d8ec..69d4350c5027 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/5001_xplane_cessna172 +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/5001_xplane_cessna172 @@ -19,6 +19,10 @@ # Load default configuration for fixed-wing aircraft . ${R}etc/init.d/rc.fw_defaults +param set-default EKF2_ABL_TAU 1 +param set-default EKF2_ABL_LIM 0.8 + + # ---- Airframe Configuration Parameters ---- # These parameters define the physical configuration of the Cessna 172 Skyhawk airframe param set-default CA_AIRFRAME 1 diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/5002_xplane_tb2 b/ROMFS/px4fmu_common/init.d-posix/airframes/5002_xplane_tb2 index bf73056b07ab..2e9c59cb5002 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/5002_xplane_tb2 +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/5002_xplane_tb2 @@ -23,6 +23,10 @@ param set-default CA_AIRFRAME 1 param set-default CA_ROTOR_COUNT 1 param set-default CA_SV_CS_COUNT 7 + +param set-default EKF2_ABL_TAU 1 +param set-default EKF2_ABL_LIM 0.8 + # --- Control Surface Configuration --- param set-default CA_SV_CS0_TYPE 1 # Left aileron param set-default CA_SV_CS0_TRQ_R -0.5 diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/5020_xplane_alia250 b/ROMFS/px4fmu_common/init.d-posix/airframes/5020_xplane_alia250 index f793c3014251..1312d3de8ae0 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/5020_xplane_alia250 +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/5020_xplane_alia250 @@ -251,6 +251,10 @@ param set-default NAV_ACC_RAD 300.0000 param set-default NAV_FW_ALT_RAD 50.0000 param set-default NAV_MIN_LTR_ALT -1.0000 + +param set-default EKF2_ABL_TAU 1 +param set-default EKF2_ABL_LIM 0.8 + param set-default EKF2_MAG_TYPE 0param param set-default FW_LND_AIRSPD 0 param set-default FW_PR_D 0.3550 From 6ea0cf95aa4c5e0d1c2b6fbf14f4e4623bcb2cd1 Mon Sep 17 00:00:00 2001 From: Alireza Ghaderi Date: Sun, 1 Sep 2024 02:44:01 +0000 Subject: [PATCH 18/25] not using baro for ekf2 --- .../px4fmu_common/init.d-posix/airframes/5001_xplane_cessna172 | 2 ++ ROMFS/px4fmu_common/init.d-posix/airframes/5002_xplane_tb2 | 2 ++ .../px4fmu_common/init.d-posix/airframes/5010_xplane_ehang184 | 3 +++ ROMFS/px4fmu_common/init.d-posix/airframes/5020_xplane_alia250 | 2 ++ 4 files changed, 9 insertions(+) diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/5001_xplane_cessna172 b/ROMFS/px4fmu_common/init.d-posix/airframes/5001_xplane_cessna172 index 69d4350c5027..35eadc5cbc75 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/5001_xplane_cessna172 +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/5001_xplane_cessna172 @@ -21,6 +21,8 @@ param set-default EKF2_ABL_TAU 1 param set-default EKF2_ABL_LIM 0.8 +param set-default EKF2_BARO_CTRL 0 + # ---- Airframe Configuration Parameters ---- diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/5002_xplane_tb2 b/ROMFS/px4fmu_common/init.d-posix/airframes/5002_xplane_tb2 index 2e9c59cb5002..fa841847e7bf 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/5002_xplane_tb2 +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/5002_xplane_tb2 @@ -26,6 +26,8 @@ param set-default CA_SV_CS_COUNT 7 param set-default EKF2_ABL_TAU 1 param set-default EKF2_ABL_LIM 0.8 +param set-default EKF2_BARO_CTRL 0 + # --- Control Surface Configuration --- param set-default CA_SV_CS0_TYPE 1 # Left aileron diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/5010_xplane_ehang184 b/ROMFS/px4fmu_common/init.d-posix/airframes/5010_xplane_ehang184 index c0dff5ae7b03..1935c0a05b43 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/5010_xplane_ehang184 +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/5010_xplane_ehang184 @@ -61,6 +61,7 @@ param set-default CA_ROTOR3_PZ 0 param set-default EKF2_ABL_TAU 1 param set-default EKF2_ABL_LIM 0.8 +param set-default EKF2_BARO_CTRL 0 param set-default CP_DELAY 0.4 param set-default CP_DIST -1 param set-default CP_GO_NO_DATA 0 @@ -187,3 +188,5 @@ param set-default MPC_MAN_Y_MAX 30 param set-default MPC_XY_CRUISE 10 param set-default MPC_YAWRAUTO_ACC 20 param set-default MPC_YAWRAUTO_MAX 30 + +param set-default NAV_MC_ALT_RAD 2.0000 diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/5020_xplane_alia250 b/ROMFS/px4fmu_common/init.d-posix/airframes/5020_xplane_alia250 index 1312d3de8ae0..3c27fb922e5a 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/5020_xplane_alia250 +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/5020_xplane_alia250 @@ -250,6 +250,8 @@ param set-default MIS_YAW_ERR 15.0000 param set-default NAV_ACC_RAD 300.0000 param set-default NAV_FW_ALT_RAD 50.0000 param set-default NAV_MIN_LTR_ALT -1.0000 +param set-default EKF2_BARO_CTRL 0 +param set-default NAV_MC_ALT_RAD 2.0000 param set-default EKF2_ABL_TAU 1 From 0414755ca28e7c1f09726577c3a316087a63df27 Mon Sep 17 00:00:00 2001 From: Alireza Ghaderi Date: Mon, 2 Sep 2024 04:40:49 +0000 Subject: [PATCH 19/25] bias acceptance , ,.. --- .../init.d-posix/airframes/5001_xplane_cessna172 | 12 ++++++++---- .../init.d-posix/airframes/5002_xplane_tb2 | 6 +++--- .../init.d-posix/airframes/5010_xplane_ehang184 | 15 +++++++++------ .../init.d-posix/airframes/5020_xplane_alia250 | 10 ++++++---- 4 files changed, 26 insertions(+), 17 deletions(-) diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/5001_xplane_cessna172 b/ROMFS/px4fmu_common/init.d-posix/airframes/5001_xplane_cessna172 index 35eadc5cbc75..b1c21e5652c6 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/5001_xplane_cessna172 +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/5001_xplane_cessna172 @@ -19,9 +19,9 @@ # Load default configuration for fixed-wing aircraft . ${R}etc/init.d/rc.fw_defaults -param set-default EKF2_ABL_TAU 1 -param set-default EKF2_ABL_LIM 0.8 -param set-default EKF2_BARO_CTRL 0 +param set-default EKF2_ABL_TAU 0.3 +param set-default EKF2_ABL_LIM 2 +param set-default EKF2_BARO_CTRL 1 @@ -70,6 +70,7 @@ param set-default FW_R_LIM 30.0000 param set-default LNDFW_VEL_XY_MAX 15.0000 param set-default FW_LND_FLALT 5.0000 param set-default RTL_LOITER_RAD 1000.0000 +param set-default RTL_DESCEND_ALT 200.0000 param set-default FW_LND_FL_PMAX 35.0000 # ---- PWM Reversals ---- @@ -127,9 +128,12 @@ param set-default FW_T_RLL2THR 5.0000 param set-default FW_T_STE_R_TC 2.5000 param set-default FW_T_THR_DAMP 0.0000 param set-default LNDFW_AIRSPD_MAX 30.0000 -param set-default MIS_YAW_ERR 15.0000 +param set-default MIS_YAW_ERR 30.0000 +param set-default MIS_YAW_TMT 5.0000 + param set-default NAV_ACC_RAD 300.0000 param set-default NAV_FW_ALT_RAD 50.0000 +param set-default MPC_MAN_Y_MAX 20.0000 param set-default NAV_MIN_LTR_ALT -1.0000 param set-default EKF2_MAG_TYPE 0 diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/5002_xplane_tb2 b/ROMFS/px4fmu_common/init.d-posix/airframes/5002_xplane_tb2 index fa841847e7bf..b7b2610502c4 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/5002_xplane_tb2 +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/5002_xplane_tb2 @@ -24,9 +24,9 @@ param set-default CA_ROTOR_COUNT 1 param set-default CA_SV_CS_COUNT 7 -param set-default EKF2_ABL_TAU 1 -param set-default EKF2_ABL_LIM 0.8 -param set-default EKF2_BARO_CTRL 0 +param set-default EKF2_ABL_TAU 0.3 +param set-default EKF2_ABL_LIM 2 +param set-default EKF2_BARO_CTRL 1 # --- Control Surface Configuration --- diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/5010_xplane_ehang184 b/ROMFS/px4fmu_common/init.d-posix/airframes/5010_xplane_ehang184 index 1935c0a05b43..e233628b159e 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/5010_xplane_ehang184 +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/5010_xplane_ehang184 @@ -59,9 +59,9 @@ param set-default CA_ROTOR3_PX -1.4 param set-default CA_ROTOR3_PY 1.4 param set-default CA_ROTOR3_PZ 0 -param set-default EKF2_ABL_TAU 1 -param set-default EKF2_ABL_LIM 0.8 -param set-default EKF2_BARO_CTRL 0 +param set-default EKF2_ABL_TAU 0.3 +param set-default EKF2_ABL_LIM 2 +param set-default EKF2_BARO_CTRL 1 param set-default CP_DELAY 0.4 param set-default CP_DIST -1 param set-default CP_GO_NO_DATA 0 @@ -164,8 +164,8 @@ param set-default MPC_Z_VEL_I_ACC 2 param set-default MPC_Z_VEL_MAX_DN 1.5 param set-default MPC_Z_VEL_MAX_UP 3 param set-default MPC_Z_VEL_P_ACC 3 -param set-default NAV_ACC_RAD 2 -param set-default RTL_DESCEND_ALT 10 +param set-default NAV_ACC_RAD 20 +param set-default RTL_DESCEND_ALT 30 param set-default RTL_RETURN_ALT 30 param set-default SYS_VEHICLE_RESP -0.4 param set-default WV_EN 0 @@ -184,9 +184,12 @@ param set-default MPC_HOLD_DZ 0.3 param set-default MPC_JERK_AUTO 1 param set-default MPC_JERK_MAX 3 param set-default MPC_LAND_RC_HELP 1 -param set-default MPC_MAN_Y_MAX 30 +param set-default MPC_MAN_Y_MAX 20 param set-default MPC_XY_CRUISE 10 param set-default MPC_YAWRAUTO_ACC 20 param set-default MPC_YAWRAUTO_MAX 30 +param set-default MIS_YAW_ERR 20.0000 +param set-default MIS_YAW_TMT 5.0000 + param set-default NAV_MC_ALT_RAD 2.0000 diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/5020_xplane_alia250 b/ROMFS/px4fmu_common/init.d-posix/airframes/5020_xplane_alia250 index 3c27fb922e5a..9f63290c85e2 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/5020_xplane_alia250 +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/5020_xplane_alia250 @@ -250,14 +250,16 @@ param set-default MIS_YAW_ERR 15.0000 param set-default NAV_ACC_RAD 300.0000 param set-default NAV_FW_ALT_RAD 50.0000 param set-default NAV_MIN_LTR_ALT -1.0000 -param set-default EKF2_BARO_CTRL 0 +param set-default EKF2_BARO_CTRL 1 param set-default NAV_MC_ALT_RAD 2.0000 +param set-default MIS_YAW_TMT 5.0000 +param set-default MIS_YAW_ERR 20.0000 -param set-default EKF2_ABL_TAU 1 -param set-default EKF2_ABL_LIM 0.8 +param set-default EKF2_ABL_TAU 0.3 +param set-default EKF2_ABL_LIM 2 -param set-default EKF2_MAG_TYPE 0param +param set-default EKF2_MAG_TYPE 0 param set-default FW_LND_AIRSPD 0 param set-default FW_PR_D 0.3550 param set-default FW_RR_D 0.0850 From aa2087bc9d68d77d487f4cbce603866a4e7ee507 Mon Sep 17 00:00:00 2001 From: Alireza Ghaderi Date: Mon, 2 Sep 2024 06:33:36 +0000 Subject: [PATCH 20/25] increased loter radii --- .../init.d-posix/airframes/5020_xplane_alia250 | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/5020_xplane_alia250 b/ROMFS/px4fmu_common/init.d-posix/airframes/5020_xplane_alia250 index 9f63290c85e2..7b70b6eafbd7 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/5020_xplane_alia250 +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/5020_xplane_alia250 @@ -184,7 +184,7 @@ param set-default FW_RR_FF 1 param set-default FW_R_LIM 30.0000 param set-default LNDFW_VEL_XY_MAX 15.0000 param set-default FW_LND_FLALT 5.0000 -param set-default RTL_LOITER_RAD 1000.0000 +param set-default RTL_LOITER_RAD 1500.0000 param set-default FW_LND_FL_PMAX 35.0000 @@ -226,7 +226,7 @@ param set-default VT_ELEV_MC_LOCK 0 param set-default VT_FWD_THRUST_EN 0 param set-default VT_F_TRANS_DUR 30.0000 param set-default VT_QC_T_ALT_LOSS 100.0000 -param set-default VTO_LOITER_ALT 1000.0000 +param set-default VTO_LOITER_ALT 1500.0000 param set-default VT_TRANS_MIN_TM 8.0000 param set-default VT_TRANS_TIMEOUT 60.0000 param set-default VT_TYPE 2 @@ -271,7 +271,7 @@ param set-default FW_WING_SPAN 17.0000 param set-default MIS_DIST_1WP 5000.0000 param set-default MIS_TAKEOFF_ALT 100.0000 param set-default MIS_TKO_LAND_REQ 0 -param set-default NAV_LOITER_RAD 1000.0000 +param set-default NAV_LOITER_RAD 1500.0000 param set-default RTL_MIN_DIST 50.0000 param set-default WEIGHT_BASE 3100.0000 param set-default WEIGHT_GROSS 3500.0000 From d1528ff10513987c23c522dd4b0f4a0b4e12e749 Mon Sep 17 00:00:00 2001 From: Alireza Ghaderi Date: Wed, 2 Oct 2024 12:22:41 +0000 Subject: [PATCH 21/25] added new qtailsitter --- .../airframes/5021_xplane_qtailsitteer | 113 ++++++++++++++++++ .../init.d-posix/airframes/CMakeLists.txt | 1 + 2 files changed, 114 insertions(+) create mode 100644 ROMFS/px4fmu_common/init.d-posix/airframes/5021_xplane_qtailsitteer diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/5021_xplane_qtailsitteer b/ROMFS/px4fmu_common/init.d-posix/airframes/5021_xplane_qtailsitteer new file mode 100644 index 000000000000..dedf49336cf7 --- /dev/null +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/5021_xplane_qtailsitteer @@ -0,0 +1,113 @@ +#!/bin/sh +# +# +# +# @output MAIN1 Motor 1 +# @output MAIN2 Motor 2 +# @output MAIN3 Motor 3 +# @output MAIN4 Motor 4 +# +# @xplane_model qtailsitter +# +# Airframe: Quad Tailsitter +# Compatible Simulator: X-Plane +# @name Quad Tailsitter for X-Plane +# @class VTOL +# @type VTOL Quad Tailsitter +# @maintainer alireza787b +# Date: Sept 2024 +# @url https://github.com/alireza787b/px4xplane/ +# Description: +# This is the airframe definition for a 1-meter wingspan control surface-less quad tailsitter, +# equipped with four high KV motors. The aircraft has a stall speed of approximately 20 m/s +# and a maximum speed of around 40 m/s. It is designed to operate without any control surfaces, +# relying solely on differential thrust and torque for control in both multicopter and fixed-wing modes. +# + +. ${R}etc/init.d/rc.vtol_defaults + +# Set the MAV type to Quad Tailsitter +param set-default MAV_TYPE 20 + +# Airframe-specific parameters +param set-default CA_AIRFRAME 4 + +# Rotor configurations (positions and moments) +param set-default CA_ROTOR_COUNT 4 +param set-default CA_ROTOR0_PX 0.5 +param set-default CA_ROTOR0_PY 0.5 +param set-default CA_ROTOR0_KM 0.05 +param set-default CA_ROTOR1_PX -0.5 +param set-default CA_ROTOR1_PY -0.5 +param set-default CA_ROTOR1_KM 0.05 +param set-default CA_ROTOR2_PX 0.5 +param set-default CA_ROTOR2_PY -0.5 +param set-default CA_ROTOR2_KM -0.05 +param set-default CA_ROTOR3_PX -0.5 +param set-default CA_ROTOR3_PY 0.5 +param set-default CA_ROTOR3_KM -0.05 + +# Control surface count (set to zero since it's a control surface-less tailsitter) +param set-default CA_SV_CS_COUNT 0 + +# Mixer assignments +param set-default PWM_MAIN_FUNC1 101 # Motor 1 +param set-default PWM_MAIN_FUNC2 102 # Motor 2 +param set-default PWM_MAIN_FUNC3 103 # Motor 3 +param set-default PWM_MAIN_FUNC4 104 # Motor 4 + +# Flight control parameters +param set-default FD_FAIL_R 70 # Fail-safe return altitude +param set-default FW_P_TC 0.2 # Pitch time constant, lower for more responsive control +param set-default NPFG_PERIOD 8 # Path following period, adjusted for higher speeds + +# Fixed-wing attitude control gains (adjusted for control via differential thrust) +param set-default FW_R_P 3.0 # Roll angle P gain +param set-default FW_P_P 3.0 # Pitch angle P gain +param set-default FW_Y_P 1.5 # Yaw angle P gain + +# Fixed-wing rate control gains +param set-default FW_RR_P 0.1 # Roll rate P gain +param set-default FW_RR_I 0.02 # Roll rate I gain +param set-default FW_RR_D 0.001 # Roll rate D gain +param set-default FW_PR_P 0.1 # Pitch rate P gain +param set-default FW_PR_I 0.02 # Pitch rate I gain +param set-default FW_PR_D 0.001 # Pitch rate D gain +param set-default FW_YR_P 0.08 # Yaw rate P gain +param set-default FW_YR_I 0.01 # Yaw rate I gain +param set-default FW_YR_D 0.0 # Yaw rate D gain + +# Throttle settings +param set-default FW_THR_TRIM 0.6 # Trim throttle +param set-default FW_THR_MAX 0.9 # Max throttle +param set-default FW_THR_MIN 0.1 # Min throttle + +# Climb and sink rates +param set-default FW_T_CLMB_MAX 8 # Max climb rate (m/s) +param set-default FW_T_SINK_MAX 5 # Max sink rate (m/s) +param set-default FW_T_SINK_MIN 2 # Min sink rate (m/s) + +# Airspeed settings (updated for stall speed of 20 m/s, max speed of 40 m/s) +param set-default FW_AIRSPD_STALL 20 # Stall speed (m/s) +param set-default FW_AIRSPD_MIN 24 # Minimum airspeed (m/s) +param set-default FW_AIRSPD_TRIM 30 # Trim airspeed (m/s) +param set-default FW_AIRSPD_MAX 40 # Maximum airspeed (m/s) + +# Multicopter settings (tuned for high KV motors) +param set-default MC_AIRMODE 2 +param set-default MC_ROLL_P 6.0 +param set-default MC_PITCH_P 6.0 +param set-default MC_YAW_P 4.5 +param set-default MC_ROLLRATE_P 0.2 +param set-default MC_PITCHRATE_P 0.2 +param set-default MC_YAWRATE_P 0.15 + +# VTOL transition parameters +param set-default VT_ARSP_TRANS 26 # Transition airspeed (m/s) +param set-default VT_F_TRANS_DUR 2 # Front transition duration (s) +param set-default VT_B_TRANS_DUR 3 # Back transition duration (s) +param set-default VT_FW_DIFTHR_EN 7 # Enable differential thrust for roll, pitch, yaw +param set-default VT_FW_DIFTHR_S_R 1.0 # Differential thrust scaling for roll +param set-default VT_FW_DIFTHR_S_P 1.0 # Differential thrust scaling for pitch +param set-default VT_FW_DIFTHR_S_Y 1.0 # Differential thrust scaling for yaw +param set-default VT_TYPE 0 # Tailsitter type diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/CMakeLists.txt b/ROMFS/px4fmu_common/init.d-posix/airframes/CMakeLists.txt index 6742a1ef1068..757efb76a40e 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/CMakeLists.txt +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/CMakeLists.txt @@ -90,6 +90,7 @@ px4_add_romfs_files( 5002_xplane_tb2 5010_xplane_ehang184 5020_xplane_alia250 + 5021_xplane_qtailsitter 6011_gazebo-classic_typhoon_h480 6011_gazebo-classic_typhoon_h480.post From b356268772dbf7edc6d6f457c043bc77a5a0dfe9 Mon Sep 17 00:00:00 2001 From: Alireza Ghaderi Date: Wed, 2 Oct 2024 12:40:51 +0000 Subject: [PATCH 22/25] syntax --- .../{5021_xplane_qtailsitteer => 5021_xplane_qtailsitter} | 0 src/drivers/gps/devices | 2 +- 2 files changed, 1 insertion(+), 1 deletion(-) rename ROMFS/px4fmu_common/init.d-posix/airframes/{5021_xplane_qtailsitteer => 5021_xplane_qtailsitter} (100%) diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/5021_xplane_qtailsitteer b/ROMFS/px4fmu_common/init.d-posix/airframes/5021_xplane_qtailsitter similarity index 100% rename from ROMFS/px4fmu_common/init.d-posix/airframes/5021_xplane_qtailsitteer rename to ROMFS/px4fmu_common/init.d-posix/airframes/5021_xplane_qtailsitter diff --git a/src/drivers/gps/devices b/src/drivers/gps/devices index fb151bcaa269..a41210ede8c2 160000 --- a/src/drivers/gps/devices +++ b/src/drivers/gps/devices @@ -1 +1 @@ -Subproject commit fb151bcaa2690b56d4b16aa8de9fe2448f637c3b +Subproject commit a41210ede8c2d22dd8e9fdcf388fca927c1fc5e1 From a96a582a1c323220b6d640ba5baeaaed53bb6c77 Mon Sep 17 00:00:00 2001 From: Alireza Ghaderi Date: Wed, 2 Oct 2024 12:43:48 +0000 Subject: [PATCH 23/25] addedairframe --- .../simulation/simulator_mavlink/sitl_targets_xplane.cmake | 3 +++ 1 file changed, 3 insertions(+) diff --git a/src/modules/simulation/simulator_mavlink/sitl_targets_xplane.cmake b/src/modules/simulation/simulator_mavlink/sitl_targets_xplane.cmake index 8fd72558f647..e12ceb3929ff 100644 --- a/src/modules/simulation/simulator_mavlink/sitl_targets_xplane.cmake +++ b/src/modules/simulation/simulator_mavlink/sitl_targets_xplane.cmake @@ -39,6 +39,9 @@ add_xplane_target(xplane_ehang184 5010 5010_xplane_ehang184) # X-Plane eVTOL Air Taxi (Quad VTOL) - Alia-250 Configuration add_xplane_target(xplane_alia250 5020 5020_xplane_alia250) +# X-Plane QTailsitter (Tailsitter VTOL) - Quantix Style +add_xplane_target(xplane_qtailsitter 5021 5021_xplane_qtailsitter) + # Instructions for adding more X-Plane configurations: # To add additional airframe configurations for X-Plane, follow these steps: # 1. Ensure the airframe file is present in the PX4 ROMFS directory under init.d-posix/airframes. From 3cbb375737340b04cb16993c61b9c547245a1eff Mon Sep 17 00:00:00 2001 From: Alireza Ghaderi Date: Wed, 2 Oct 2024 12:45:44 +0000 Subject: [PATCH 24/25] wrong params --- .../init.d-posix/airframes/5021_xplane_qtailsitter | 4 ---- 1 file changed, 4 deletions(-) diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/5021_xplane_qtailsitter b/ROMFS/px4fmu_common/init.d-posix/airframes/5021_xplane_qtailsitter index dedf49336cf7..45fa182ffae2 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/5021_xplane_qtailsitter +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/5021_xplane_qtailsitter @@ -61,10 +61,6 @@ param set-default FD_FAIL_R 70 # Fail-safe return altitude param set-default FW_P_TC 0.2 # Pitch time constant, lower for more responsive control param set-default NPFG_PERIOD 8 # Path following period, adjusted for higher speeds -# Fixed-wing attitude control gains (adjusted for control via differential thrust) -param set-default FW_R_P 3.0 # Roll angle P gain -param set-default FW_P_P 3.0 # Pitch angle P gain -param set-default FW_Y_P 1.5 # Yaw angle P gain # Fixed-wing rate control gains param set-default FW_RR_P 0.1 # Roll rate P gain From 0d348345ddd224d3b91a2c39413d53829fb70a0f Mon Sep 17 00:00:00 2001 From: Alireza Ghaderi Date: Sat, 19 Oct 2024 07:32:07 +0000 Subject: [PATCH 25/25] added filter bias for tailsitter --- .../init.d-posix/airframes/5021_xplane_qtailsitter | 9 +++++++++ 1 file changed, 9 insertions(+) diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/5021_xplane_qtailsitter b/ROMFS/px4fmu_common/init.d-posix/airframes/5021_xplane_qtailsitter index 45fa182ffae2..d5a899e3bd64 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/5021_xplane_qtailsitter +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/5021_xplane_qtailsitter @@ -107,3 +107,12 @@ param set-default VT_FW_DIFTHR_S_R 1.0 # Differential thrust scaling for roll param set-default VT_FW_DIFTHR_S_P 1.0 # Differential thrust scaling for pitch param set-default VT_FW_DIFTHR_S_Y 1.0 # Differential thrust scaling for yaw param set-default VT_TYPE 0 # Tailsitter type + + +param set-default EKF2_TAS_GATE 3 +param set-default EKF2_WIND_NSD 0.01 + +param set-default EKF2_ABL_TAU 0.3 +param set-default EKF2_ABL_LIM 2 +param set-default EKF2_MAG_TYPE 0 +