diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/1090_gazebo-classic_monocopter b/ROMFS/px4fmu_common/init.d-posix/airframes/1090_gazebo-classic_monocopter new file mode 100644 index 0000000000..04ebafc885 --- /dev/null +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/1090_gazebo-classic_monocopter @@ -0,0 +1,70 @@ +#!/bin/sh +# +# @name Monocopter SITL +# + +. ${R}etc/init.d/rc.fw_defaults + +param set-default FW_LND_ANG 8 + +param set-default NPFG_PERIOD 12 + +param set-default FW_PR_P 0.9 +param set-default FW_PR_FF 0.5 +param set-default FW_PR_I 0.5 +param set-default TRIM_PITCH -0.15 + +param set-default FW_PSP_OFF 2 +param set-default FW_P_LIM_MIN -15 + +param set-default FW_RR_FF 0.5 +param set-default FW_RR_P 0.3 +param set-default FW_RR_I 0.5 + +param set-default FW_YR_FF 0.5 +param set-default FW_YR_P 0.6 +param set-default FW_YR_I 0.5 + +param set-default FW_SPOILERS_LND 0.4 + +param set-default FW_THR_MAX 0.6 +param set-default FW_THR_MIN 0.05 +param set-default FW_THR_TRIM 0.25 + +param set-default FW_T_CLMB_MAX 8 +param set-default FW_T_SINK_MAX 2.7 +param set-default FW_T_SINK_MIN 2.2 + +param set-default FW_W_EN 1 + +param set-default MIS_TAKEOFF_ALT 30 + +param set-default NAV_ACC_RAD 15 +param set-default NAV_DLL_ACT 2 + +param set-default RWTO_TKOFF 1 + +param set-default CA_AIRFRAME 1 + +param set-default CA_ROTOR_COUNT 1 +param set-default CA_ROTOR0_PX 0.3 + +param set-default CA_SV_CS_COUNT 6 +param set-default CA_SV_CS0_TRQ_R -0.5 +param set-default CA_SV_CS0_TYPE 1 +param set-default CA_SV_CS1_TRQ_R 0.5 +param set-default CA_SV_CS1_TYPE 2 +param set-default CA_SV_CS2_TRQ_P 1 +param set-default CA_SV_CS2_TYPE 3 +param set-default CA_SV_CS3_TRQ_Y 1 +param set-default CA_SV_CS3_TYPE 4 +param set-default CA_SV_CS4_TYPE 9 +param set-default CA_SV_CS5_TYPE 10 +param set-default PWM_MAIN_FUNC3 204 +param set-default PWM_MAIN_FUNC4 205 +param set-default PWM_MAIN_FUNC5 101 +param set-default PWM_MAIN_FUNC6 201 +param set-default PWM_MAIN_FUNC7 202 +param set-default PWM_MAIN_FUNC8 203 +param set-default PWM_MAIN_FUNC9 206 +param set-default PWM_MAIN_REV 256 diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/CMakeLists.txt b/ROMFS/px4fmu_common/init.d-posix/airframes/CMakeLists.txt index 9277ad3039..d450931552 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/CMakeLists.txt +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/CMakeLists.txt @@ -67,6 +67,7 @@ px4_add_romfs_files( 1061_gazebo-classic_r1_rover 1062_flightgear_tf-r1 1070_gazebo-classic_boat + 1090_gazebo-classic_monocopter 2507_gazebo-classic_cloudship diff --git a/src/modules/simulation/simulator_mavlink/sitl_targets_gazebo-classic.cmake b/src/modules/simulation/simulator_mavlink/sitl_targets_gazebo-classic.cmake index b67fe546cc..1db4ec24f3 100644 --- a/src/modules/simulation/simulator_mavlink/sitl_targets_gazebo-classic.cmake +++ b/src/modules/simulation/simulator_mavlink/sitl_targets_gazebo-classic.cmake @@ -87,6 +87,7 @@ if(gazebo_FOUND) iris_opt_flow_mockup iris_rplidar iris_vision + monocopter omnicopter plane plane_cam