diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/1040_gazebo-classic_standard_vtol b/ROMFS/px4fmu_common/init.d-posix/airframes/1040_gazebo-classic_standard_vtol index 4e25647e01..9ad99c1d83 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/1040_gazebo-classic_standard_vtol +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/1040_gazebo-classic_standard_vtol @@ -47,6 +47,8 @@ param set-default PWM_MAIN_FUNC6 201 param set-default PWM_MAIN_FUNC7 202 param set-default PWM_MAIN_FUNC8 203 +param set-default FW_AIRSPD_MAX 25 +param set-default FW_THR_ASPD_MAX 0.4 param set-default NPFG_PERIOD 12 param set-default FW_PR_FF 0.2 param set-default FW_PR_P 0.9 @@ -62,19 +64,18 @@ param set-default FW_T_SINK_MAX 2.7 param set-default FW_T_SINK_MIN 2.2 param set-default MC_AIRMODE 1 +param set-default MC_ROLL_P 4 param set-default MC_ROLLRATE_P 0.3 param set-default MC_YAW_P 1.6 +param set-default MC_YAWRATE_P 0.3 + param set-default MIS_TAKEOFF_ALT 10 -param set-default MPC_XY_P 0.8 -param set-default MPC_XY_VEL_P_ACC 3 -param set-default MPC_XY_VEL_I_ACC 4 -param set-default MPC_XY_VEL_D_ACC 0.1 - param set-default NAV_ACC_RAD 5 param set-default VT_FWD_THRUST_EN 4 +param set-default VT_FWD_THRUST_SC 1 param set-default VT_F_TRANS_THR 0.75 param set-default VT_TYPE 2