diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/1041_gazebo-classic_tailsitter b/ROMFS/px4fmu_common/init.d-posix/airframes/1041_gazebo-classic_tailsitter index 2ab3d13e80..1fe1fdde6e 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/1041_gazebo-classic_tailsitter +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/1041_gazebo-classic_tailsitter @@ -48,35 +48,32 @@ param set-default PWM_MAIN_REV 96 # invert both elevons param set-default EKF2_MULTI_IMU 0 param set-default SENS_IMU_MODE 1 -param set-default NPFG_PERIOD 12 -param set-default FW_PR_I 0.2 -param set-default FW_PR_P 0.2 +param set-default FW_P_TC 0.6 + +param set-default FW_PR_FF 0.1 param set-default FW_PSP_OFF 2 -param set-default FW_P_LIM_MIN -15 -param set-default FW_RR_P 0.2 -param set-default FW_THR_TRIM 0.33 -param set-default FW_THR_MAX 0.6 +param set-default FW_RR_FF 0.1 +param set-default FW_RR_I 0.2 +param set-default FW_RR_P 0.3 +param set-default FW_THR_TRIM 0.35 +param set-default FW_THR_MAX 0.8 param set-default FW_THR_MIN 0.05 -param set-default FW_T_ALT_TC 2 -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_T_TAS_TC 2 +param set-default FW_T_CLMB_MAX 6 +param set-default FW_T_HRATE_FF 0.5 +param set-default FW_T_SINK_MAX 3 +param set-default FW_T_SINK_MIN 1.6 param set-default MC_AIRMODE 1 +param set-default MC_ROLL_P 3 +param set-default MC_PITCH_P 3 param set-default MC_ROLLRATE_P 0.3 +param set-default MC_PITCHRATE_P 0.3 -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_ARSP_TRANS 10 +param set-default VT_B_TRANS_DUR 5 param set-default VT_FW_DIFTHR_EN 1 -param set-default VT_FW_DIFTHR_S_Y 0.5 +param set-default VT_FW_DIFTHR_S_Y 1 param set-default VT_F_TRANS_DUR 1.5 -param set-default VT_F_TRANS_THR 0.7 param set-default VT_TYPE 0 param set-default WV_EN 0