Skip to content
New issue

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

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

Already on GitHub? Sign in to your account

Px4-xplane sitl airframe for Fixed Wing and Multicopter and VTOL #22493

Open
wants to merge 43 commits into
base: main
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from 6 commits
Commits
Show all changes
43 commits
Select commit Hold shift + click to select a range
dee3f52
added c172 and ehang4 SITL
alireza787b Dec 5, 2023
36741d8
setting params for ehang and cessna172
alireza787b Dec 6, 2023
3722882
Merge branch 'PX4:main' into px4xplane-sitl
alireza787b Dec 6, 2023
47f71a0
setting params name for ehang and cessna172
alireza787b Dec 6, 2023
8fa3224
Merge branch 'px4xplane-sitl' of https://github.com/alireza787b/PX4-A…
alireza787b Dec 6, 2023
f1c17aa
changes airspeed and roll perfomance params
alireza787b Dec 7, 2023
de5be47
Refactor X-Plane SITL targets into dedicated CMake file
alireza787b Dec 9, 2023
2d1332f
added jerk limitation to smooth the inputs in cessna 172
alireza787b Dec 10, 2023
68881fa
Merge branch 'PX4:main' into px4xplane-sitl
alireza787b Dec 15, 2023
58361eb
added Alia 250 and c172 and ehang4 name changed
alireza787b Dec 20, 2023
f27ee88
Merge branch 'PX4:main' into px4xplane-sitl
alireza787b Dec 20, 2023
8b4866d
Merge branch 'PX4:main' into px4xplane-sitl
alireza787b Dec 31, 2023
3625e75
updated performance specs for better flight
alireza787b Jan 7, 2024
971c5f7
Merge branch 'px4xplane-sitl' of https://github.com/alireza787b/PX4-A…
alireza787b Jan 7, 2024
997f530
improved Alia250 performance speeds
alireza787b Jan 9, 2024
28c5c83
Merge branch 'PX4:main' into px4xplane-sitl
alireza787b Jan 14, 2024
cb58fde
Merge branch 'PX4:main' into px4xplane-sitl
alireza787b Jan 21, 2024
2f9147f
Merge branch 'PX4:main' into px4xplane-sitl
alireza787b Feb 15, 2024
3bb67bd
Merge branch 'PX4:main' into px4xplane-sitl
alireza787b Mar 15, 2024
40f6fb7
Merge branch 'PX4:main' into px4xplane-sitl
alireza787b Apr 8, 2024
b84f974
added tb2
alireza787b Apr 14, 2024
8450e19
added 5002_xplane_tb2
alireza787b Apr 16, 2024
1addba8
Merge branch 'PX4:main' into px4xplane-sitl
alireza787b Apr 22, 2024
67b2151
Merge branch 'PX4:main' into px4xplane-sitl
alireza787b Jul 20, 2024
e109c12
fix duplicated empty line
alireza787b Jul 20, 2024
a0fd955
Merge branch 'main' into px4xplane-sitl
alireza787b Aug 11, 2024
281952d
Merge branch 'main' into px4xplane-sitl
alireza787b Aug 23, 2024
87dca6e
fixed missed params
alireza787b Aug 24, 2024
046be67
Merge branch 'px4xplane-sitl' of github.com:alireza787b/PX4-Autopilot…
alireza787b Aug 24, 2024
122b312
Update 5010_xplane_ehang184
alireza787b Aug 26, 2024
29998b9
Update 5010_xplane_ehang184
alireza787b Aug 26, 2024
c0da531
accel bias ekf2 and baro
alireza787b Aug 29, 2024
8b38dc6
merged
alireza787b Aug 29, 2024
cf28d94
accel bias rating
alireza787b Aug 29, 2024
6ea0cf9
not using baro for ekf2
alireza787b Sep 1, 2024
0414755
bias acceptance , ,..
alireza787b Sep 2, 2024
aa2087b
increased loter radii
alireza787b Sep 2, 2024
d1528ff
added new qtailsitter
alireza787b Oct 2, 2024
69172f1
Merge branch 'PX4:main' into px4xplane-sitl
alireza787b Oct 2, 2024
b356268
syntax
alireza787b Oct 2, 2024
a96a582
addedairframe
alireza787b Oct 2, 2024
3cbb375
wrong params
alireza787b Oct 2, 2024
0d34834
added filter bias for tailsitter
alireza787b Oct 19, 2024
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
132 changes: 132 additions & 0 deletions ROMFS/px4fmu_common/init.d-posix/airframes/5001_xplane_c172
Original file line number Diff line number Diff line change
@@ -0,0 +1,132 @@
#!/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'.
#
# @name: Cessna 172 Skyhawk
# Compatible Simulator: X-Plane
# @type Standard Plane
# @maintainer alireza787b <[email protected]>
# 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

# ---- 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 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 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 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
187 changes: 187 additions & 0 deletions ROMFS/px4fmu_common/init.d-posix/airframes/5010_xplane_ehang4
Original file line number Diff line number Diff line change
@@ -0,0 +1,187 @@
#!/bin/sh
#
# PX4 SITL Configuration Script for Ehang Airtaxi (QuadCopter) in X-Plane
#
# 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 <[email protected]>
# 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 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
3 changes: 3 additions & 0 deletions ROMFS/px4fmu_common/init.d-posix/airframes/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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

Expand Down
25 changes: 25 additions & 0 deletions src/modules/simulation/simulator_mavlink/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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
alireza787b marked this conversation as resolved.
Show resolved Hide resolved
COMMAND ${CMAKE_COMMAND} -E env PX4_SYS_AUTOSTART=5001 $<TARGET_FILE:px4>
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 $<TARGET_FILE:px4>
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)"
)

Loading