diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/4006_gz_px4vision b/ROMFS/px4fmu_common/init.d-posix/airframes/4006_gz_px4vision
new file mode 100644
index 0000000000..0b836484db
--- /dev/null
+++ b/ROMFS/px4fmu_common/init.d-posix/airframes/4006_gz_px4vision
@@ -0,0 +1,154 @@
+#!/bin/sh
+#
+# @name PX4Vision SITL
+# Holybro px4vision. Gazebo Only.
+#
+# @type Quadrotor
+#
+
+. ${R}etc/init.d/rc.mc_defaults
+
+PX4_SIMULATOR=${PX4_SIMULATOR:=gz}
+PX4_GZ_WORLD=${PX4_GZ_WORLD:=default}
+PX4_SIM_MODEL=${PX4_SIM_MODEL:=px4vision}
+
+param set-default SIM_GZ_EN 1
+
+param set-default SENS_EN_GPSSIM 1
+param set-default SENS_EN_BAROSIM 0
+param set-default SENS_EN_MAGSIM 1
+
+# Commander Parameters
+param set-default COM_OBS_AVOID 0
+param set-default COM_DISARM_LAND 0.5
+
+# EKF2 parameters
+param set-default EKF2_AID_MASK 35
+param set-default EKF2_IMU_POS_X 0.02
+param set-default EKF2_GPS_POS_X 0.055
+param set-default EKF2_GPS_POS_Z -0.15
+param set-default EKF2_MIN_RNG 0.03
+param set-default EKF2_OF_POS_X 0.055
+param set-default EKF2_OF_POS_Y 0.02
+param set-default EKF2_OF_POS_Z 0.065
+param set-default EKF2_REQ_HDRIFT 0.3
+param set-default EKF2_REQ_SACC 1
+param set-default EKF2_REQ_VDRIFT 0.3
+param set-default EKF2_RNG_A_HMAX 8
+param set-default EKF2_RNG_A_VMAX 2
+param set-default EKF2_RNG_POS_X 0.055
+param set-default EKF2_RNG_POS_Y -0.01
+param set-default EKF2_RNG_POS_Z 0.065
+param set-default EKF2_PCOEF_XP -0.25
+param set-default EKF2_PCOEF_YN -0.55
+param set-default EKF2_PCOEF_YP -0.55
+
+# MAVLink parameters
+# param set-default MAV_0_CONFIG 101 Not found
+# param set-default MAV_1_CONFIG 102 Not found
+param set-default MAV_1_RATE 80000
+param set-default MAV_1_MODE 9
+# param set-default SER_TEL1_BAUD 921600 Not found
+
+# Vehicle attitude PID tuning
+param set-default MC_ACRO_EXPO 0
+param set-default MC_ACRO_EXPO_Y 0
+param set-default MC_ACRO_P_MAX 200
+param set-default MC_ACRO_R_MAX 200
+param set-default MC_ACRO_SUPEXPO 0
+param set-default MC_ACRO_SUPEXPOY 0
+param set-default MC_ACRO_Y_MAX 150
+param set-default MC_PITCHRATE_D 0.0015
+param set-default MC_ROLLRATE_D 0.0015
+param set-default MC_YAWRATE_P 0.3
+
+# Position Control Tuning
+param set-default CP_DIST 6
+param set-default MPC_ACC_DOWN_MAX 5
+param set-default MPC_ACC_HOR_MAX 10
+param set-default MPC_ACC_UP_MAX 4
+param set-default MPC_MANTHR_MIN 0
+param set-default MPC_MAN_Y_MAX 120
+param set-default MPC_TILTMAX_AIR 45
+param set-default MPC_THR_HOVER 0.3
+param set-default MPC_VEL_MANUAL 5
+param set-default MPC_XY_CRUISE 5
+param set-default MPC_XY_VEL_MAX 5
+param set-default MPC_XY_VEL_P_ACC 1.58
+param set-default MPC_XY_TRAJ_P 0.3
+# param set-default MPC_Z_TRAJ_P 0.3 Not found
+param set-default MPC_Z_VEL_P_ACC 5
+param set-default MPC_Z_VEL_I_ACC 3
+param set-default MPC_LAND_ALT1 3
+param set-default MPC_LAND_ALT2 1
+param set-default MPC_POS_MODE 3
+param set-default CP_GO_NO_DATA 1
+
+# Navigator Parameters
+param set-default NAV_ACC_RAD 2
+
+# RTL Parameters
+param set-default RTL_DESCEND_ALT 5
+param set-default RTL_RETURN_ALT 5
+
+# Logging Parameters
+param set-default SDLOG_PROFILE 131
+
+# Sensors Parameters
+# param set-default SENS_CM8JL65_CFG 202 Not found
+param set-default SENS_FLOW_MAXHGT 25
+param set-default SENS_FLOW_MINHGT 0.5
+param set-default IMU_GYRO_CUTOFF 100
+# param set-default SENS_TFLOW_CFG 103 Not found
+
+# Power Parameters
+param set-default BAT1_N_CELLS 4
+# param set-default BAT1_A_PER_V 36.364 Not found
+# param set-default BAT1_V_DIV 18.182 Not found
+
+# Circuit breakers
+param set-default CBRK_IO_SAFETY 22027
+
+param set-default THR_MDL_FAC 0.3
+
+param set-default CA_ROTOR_COUNT 4
+param set-default CA_ROTOR0_PX 0.15
+param set-default CA_ROTOR0_PY 0.15
+param set-default CA_ROTOR0_KM 0.05
+param set-default CA_ROTOR1_PX -0.15
+param set-default CA_ROTOR1_PY -0.15
+param set-default CA_ROTOR1_KM 0.05
+param set-default CA_ROTOR2_PX 0.15
+param set-default CA_ROTOR2_PY -0.15
+param set-default CA_ROTOR2_KM -0.05
+param set-default CA_ROTOR3_PX -0.15
+param set-default CA_ROTOR3_PY 0.15
+param set-default CA_ROTOR3_KM -0.05
+
+# Outputs
+# param set-default PWM_AUX_FUNC1 101
+# param set-default PWM_AUX_FUNC2 102
+# param set-default PWM_AUX_FUNC3 103
+# param set-default PWM_AUX_FUNC4 104
+
+# 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 SIM_GZ_EC_FUNC1 101
+param set-default SIM_GZ_EC_FUNC2 102
+param set-default SIM_GZ_EC_FUNC3 103
+param set-default SIM_GZ_EC_FUNC4 104
+
+param set-default SIM_GZ_EC_MIN1 150
+param set-default SIM_GZ_EC_MIN2 150
+param set-default SIM_GZ_EC_MIN3 150
+param set-default SIM_GZ_EC_MIN4 150
+
+param set-default SIM_GZ_EC_MAX1 1100
+param set-default SIM_GZ_EC_MAX2 1100
+param set-default SIM_GZ_EC_MAX3 1100
+param set-default SIM_GZ_EC_MAX4 1100
+
+
diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/CMakeLists.txt b/ROMFS/px4fmu_common/init.d-posix/airframes/CMakeLists.txt
index 8e1c82b42f..4c61e70643 100644
--- a/ROMFS/px4fmu_common/init.d-posix/airframes/CMakeLists.txt
+++ b/ROMFS/px4fmu_common/init.d-posix/airframes/CMakeLists.txt
@@ -75,6 +75,7 @@ px4_add_romfs_files(
4003_gz_rc_cessna
4004_gz_standard_vtol
4005_gz_x500_vision
+ 4006_gz_px4vision
6011_gazebo-classic_typhoon_h480
6011_gazebo-classic_typhoon_h480.post
diff --git a/Tools/simulation/gz/models/px4vision/model.config b/Tools/simulation/gz/models/px4vision/model.config
new file mode 100644
index 0000000000..82f9eac095
--- /dev/null
+++ b/Tools/simulation/gz/models/px4vision/model.config
@@ -0,0 +1,15 @@
+
+
+ PX4 Vision
+ 1.0
+ model.sdf
+
+
+ Jaeyoung Lim
+ jaeyoung@auterion.com
+
+
+
+ This is a model of the Holybro PX4 Vision
+
+
diff --git a/Tools/simulation/gz/models/px4vision/model.sdf b/Tools/simulation/gz/models/px4vision/model.sdf
new file mode 100644
index 0000000000..630e8d6c51
--- /dev/null
+++ b/Tools/simulation/gz/models/px4vision/model.sdf
@@ -0,0 +1,10 @@
+
+
+
+
+
+ https://fuel.gazebosim.org/1.0/PX4/models/PX4 Vision
+
+
+
+