diff --git a/Makefile b/Makefile
index c14c2fc4119058d2ae562363ecd134ce0d4365f4..05426971a70053da45281706da0a38e1887c1223 100644
--- a/Makefile
+++ b/Makefile
@@ -320,7 +320,7 @@ distclean: submodulesclean
 cmake_targets = test upload package package_source debug debug_tui debug_ddd debug_io debug_io_tui debug_io_ddd check_weak \
 	run_cmake_config config gazebo gazebo_gdb gazebo_lldb jmavsim replay \
 	jmavsim_gdb jmavsim_lldb gazebo_gdb_iris gazebo_lldb_tailsitter gazebo_iris gazebo_iris_opt_flow gazebo_tailsitter \
-	gazebo_gdb_standard_vtol gazebo_lldb_standard_vtol gazebo_standard_vtol gazebo_plane gazebo_solo
+	gazebo_gdb_standard_vtol gazebo_lldb_standard_vtol gazebo_standard_vtol gazebo_plane gazebo_solo gazebo_typhoon_h480
 $(foreach targ,$(cmake_targets),$(eval $(call cmake-targ,$(targ))))
 
 .PHONY: clean
diff --git a/posix-configs/SITL/init/rcS_gazebo_typhoon_h480 b/posix-configs/SITL/init/rcS_gazebo_typhoon_h480
new file mode 100644
index 0000000000000000000000000000000000000000..6a47ce7ff5f261f4de1fc08f685831257a9638b2
--- /dev/null
+++ b/posix-configs/SITL/init/rcS_gazebo_typhoon_h480
@@ -0,0 +1,75 @@
+uorb start
+param load
+param set MAV_TYPE 13
+param set SYS_AUTOSTART 6001
+param set SYS_RESTART_TYPE 2
+dataman start
+param set CAL_GYRO0_ID 2293768
+param set CAL_ACC0_ID 1376264
+param set CAL_ACC1_ID 1310728
+param set CAL_MAG0_ID 196616
+param set CAL_GYRO0_XOFF 0.01
+param set CAL_ACC0_XOFF 0.01
+param set CAL_ACC0_YOFF -0.01
+param set CAL_ACC0_ZOFF 0.01
+param set CAL_ACC0_XSCALE 1.01
+param set CAL_ACC0_YSCALE 1.01
+param set CAL_ACC0_ZSCALE 1.01
+param set CAL_ACC1_XOFF 0.01
+param set CAL_MAG0_XOFF 0.01
+param set SENS_BOARD_ROT 8
+param set SENS_BOARD_X_OFF 0.000001
+param set COM_RC_IN_MODE 1
+param set NAV_DLL_ACT 2
+param set COM_DISARM_LAND 3
+param set NAV_ACC_RAD 2.0
+param set RTL_RETURN_ALT 30.0
+param set RTL_DESCEND_ALT 10.0
+param set RTL_LAND_DELAY 0
+param set MIS_TAKEOFF_ALT 2.5
+param set MC_ROLLRATE_P 0.25
+param set MC_PITCHRATE_P 0.25
+param set MC_PITCH_P 5
+param set MC_ROLL_P 5
+param set MC_ROLLRATE_I 0.1
+param set MC_PITCHRATE_I 0.1
+param set MPC_HOLD_MAX_Z 2.0
+param set MPC_HOLD_XY_DZ 0.1
+param set MPC_Z_VEL_P 0.8
+param set MPC_Z_VEL_I 0.15
+param set MPC_XY_VEL_P 0.15
+param set MPC_XY_VEL_I 0.2
+param set EKF2_GBIAS_INIT 0.01
+param set EKF2_ANGERR_INIT 0.01
+simulator start -s
+rgbledsim start
+tone_alarm start
+gyrosim start
+accelsim start
+barosim start
+adcsim start
+gpssim start
+pwm_out_sim mode_pwm
+sleep 1
+sensors start
+commander start
+land_detector start multicopter
+navigator start
+ekf2 start
+mc_pos_control start
+mc_att_control start
+mixer load /dev/pwm_output0 ../../../../ROMFS/px4fmu_common/mixers/hexa_x.main.mix
+mavlink start -u 14556 -r 4000000
+mavlink start -u 14557 -r 4000000 -m onboard -o 14540
+mavlink stream -r 50 -s POSITION_TARGET_LOCAL_NED -u 14556
+mavlink stream -r 50 -s LOCAL_POSITION_NED -u 14556
+mavlink stream -r 50 -s GLOBAL_POSITION_INT -u 14556
+mavlink stream -r 50 -s ATTITUDE -u 14556
+mavlink stream -r 50 -s ATTITUDE_QUATERNION -u 14556
+mavlink stream -r 50 -s ATTITUDE_TARGET -u 14556
+mavlink stream -r 50 -s SERVO_OUTPUT_RAW_0 -u 14556
+mavlink stream -r 20 -s RC_CHANNELS -u 14556
+mavlink stream -r 250 -s HIGHRES_IMU -u 14556
+mavlink stream -r 10 -s OPTICAL_FLOW_RAD -u 14556
+sdlog2 start -r 100 -e -t -a
+mavlink boot_complete
diff --git a/src/firmware/posix/CMakeLists.txt b/src/firmware/posix/CMakeLists.txt
index a1c5f1c3747470a90de3c23dd6828717289c8435..74d4025a7a2043f5c8420879cc60ccba6a3c2e94 100644
--- a/src/firmware/posix/CMakeLists.txt
+++ b/src/firmware/posix/CMakeLists.txt
@@ -128,7 +128,7 @@ add_dependencies(run_config mainapp)
 
 foreach(viewer none jmavsim gazebo replay)
 	foreach(debugger none gdb lldb ddd valgrind)
-		foreach(model none iris iris_opt_flow tailsitter standard_vtol plane solo)
+		foreach(model none iris iris_opt_flow tailsitter standard_vtol plane solo typhoon_h480)
 			if (debugger STREQUAL "none")
 				if (model STREQUAL "none")
 					set(_targ_name "${viewer}")