diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/5001_xplane_cessna172 b/ROMFS/px4fmu_common/init.d-posix/airframes/5001_xplane_cessna172 new file mode 100644 index 000000000000..b1c21e5652c6 --- /dev/null +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/5001_xplane_cessna172 @@ -0,0 +1,144 @@ +#!/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_cessna172'. +# +# @name: Cessna 172 Skyhawk +# Compatible Simulator: X-Plane +# @type Standard Plane +# @maintainer alireza787b +# Date: Nov 2023 +# @url https://github.com/alireza787b/px4xplane/ +# +# ---- Start of Configuration ---- + +# Load default configuration for fixed-wing aircraft +. ${R}etc/init.d/rc.fw_defaults + +param set-default EKF2_ABL_TAU 0.3 +param set-default EKF2_ABL_LIM 2 +param set-default EKF2_BARO_CTRL 1 + + + +# ---- 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 + +# ---- 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 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 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 RTL_DESCEND_ALT 200.0000 +param set-default FW_LND_FL_PMAX 35.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_LOITER_RAD 1000.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_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_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 LNDFW_AIRSPD_MAX 30.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 +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/5002_xplane_tb2 b/ROMFS/px4fmu_common/init.d-posix/airframes/5002_xplane_tb2 new file mode 100644 index 000000000000..b7b2610502c4 --- /dev/null +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/5002_xplane_tb2 @@ -0,0 +1,107 @@ +#!/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 +# + +. ${R}etc/init.d/rc.fw_defaults + +# --- Aircraft Configuration --- +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 0.3 +param set-default EKF2_ABL_LIM 2 +param set-default EKF2_BARO_CTRL 1 + + +# --- 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_CS1_TYPE 2 # Right aileron +param set-default CA_SV_CS1_TRQ_R 0.5 +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_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_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 +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 +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 --- diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/5010_xplane_ehang184 b/ROMFS/px4fmu_common/init.d-posix/airframes/5010_xplane_ehang184 new file mode 100644 index 000000000000..e233628b159e --- /dev/null +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/5010_xplane_ehang184 @@ -0,0 +1,195 @@ +#!/bin/sh +# +# PX4 SITL Configuration Script for Ehang Airtaxi (QuadCopter) in X-Plane +# +# 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_ehang184'. +# +# 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_ROTOR1_KM 0.05 +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_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 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 +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 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 +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 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 new file mode 100644 index 000000000000..7b70b6eafbd7 --- /dev/null +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/5020_xplane_alia250 @@ -0,0 +1,288 @@ +#!/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 +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.0044 +param set-default MC_ROLLRATE_FF 0 +param set-default MC_ROLLRATE_I 0 +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 +param set-default MC_YAWRATE_I 0 +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 +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 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 +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.3 +param set-default MC_YAWRATE_D 0 +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 +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 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 1500.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 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 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 +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 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 +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 FW_P_TC 0.4500 +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_RLL2THR 5.0000 +param set-default FW_T_STE_R_TC 2.5000 +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 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 0.3 +param set-default EKF2_ABL_LIM 2 + +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 +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 1500.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 FW_AIRSPD_MAX 75.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 + +param set-default FW_T_SINK_MAX 6.0000 +param set-default FW_T_SINK_MIN 3.0000 diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/5021_xplane_qtailsitter b/ROMFS/px4fmu_common/init.d-posix/airframes/5021_xplane_qtailsitter new file mode 100644 index 000000000000..d5a899e3bd64 --- /dev/null +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/5021_xplane_qtailsitter @@ -0,0 +1,118 @@ +#!/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 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 + + +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 + diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/CMakeLists.txt b/ROMFS/px4fmu_common/init.d-posix/airframes/CMakeLists.txt index 1ba611c2755a..0b0972fc1cf2 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/CMakeLists.txt +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/CMakeLists.txt @@ -88,6 +88,12 @@ px4_add_romfs_files( 4014_gz_x500_mono_cam_down 4015_gz_r1_rover_mecanum + 5001_xplane_cessna172 + 5002_xplane_tb2 + 5010_xplane_ehang184 + 5020_xplane_alia250 + 5021_xplane_qtailsitter + 6011_gazebo-classic_typhoon_h480 6011_gazebo-classic_typhoon_h480.post 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 diff --git a/src/modules/simulation/simulator_mavlink/CMakeLists.txt b/src/modules/simulation/simulator_mavlink/CMakeLists.txt index fc4fa94aa4b4..222d948f4003 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) 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..e12ceb3929ff --- /dev/null +++ b/src/modules/simulation/simulator_mavlink/sitl_targets_xplane.cmake @@ -0,0 +1,52 @@ +# 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_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) + +# 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. +# 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.