From 88bf18a2fe24497e91e0c277d51902ae1dbccbe6 Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Tue, 18 Apr 2023 11:35:16 +0200 Subject: [PATCH] airframe configs: remove custom tuning if close to param default and not required due to hardware Signed-off-by: Silvan Fuhrer --- .../1040_gazebo-classic_standard_vtol | 1 - .../airframes/1041_gazebo-classic_tailsitter | 2 -- .../1043_gazebo-classic_standard_vtol_drop | 1 - .../airframes/4004_gz_standard_vtol | 1 - .../init.d/airframes/13013_deltaquad | 19 ------------------- .../init.d/airframes/13014_vtol_babyshark | 10 ---------- ROMFS/px4fmu_common/init.d/rc.vtol_defaults | 1 - 7 files changed, 35 deletions(-) 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 37722572ab..4e25647e01 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 @@ -67,7 +67,6 @@ param set-default MC_YAW_P 1.6 param set-default MIS_TAKEOFF_ALT 10 -param set-default MPC_ACC_HOR_MAX 2 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 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 c47a8fb9dd..d5f86862fe 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 @@ -61,7 +61,6 @@ param set-default FW_THR_MAX 0.6 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_HRATE_FF 0.5 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 @@ -69,7 +68,6 @@ param set-default FW_T_TAS_TC 2 param set-default MC_AIRMODE 1 param set-default MC_ROLLRATE_P 0.3 -param set-default MPC_ACC_HOR_MAX 2 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 diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/1043_gazebo-classic_standard_vtol_drop b/ROMFS/px4fmu_common/init.d-posix/airframes/1043_gazebo-classic_standard_vtol_drop index e7f04eb90b..f029918529 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/1043_gazebo-classic_standard_vtol_drop +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/1043_gazebo-classic_standard_vtol_drop @@ -66,7 +66,6 @@ param set-default MC_YAW_P 1.6 param set-default MIS_TAKEOFF_ALT 10 -param set-default MPC_ACC_HOR_MAX 2 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 diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/4004_gz_standard_vtol b/ROMFS/px4fmu_common/init.d-posix/airframes/4004_gz_standard_vtol index ffe65bf2d8..39f5f8f3e2 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/4004_gz_standard_vtol +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/4004_gz_standard_vtol @@ -96,7 +96,6 @@ param set-default MC_YAW_P 1.6 param set-default MIS_TAKEOFF_ALT 10 -param set-default MPC_ACC_HOR_MAX 2 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 diff --git a/ROMFS/px4fmu_common/init.d/airframes/13013_deltaquad b/ROMFS/px4fmu_common/init.d/airframes/13013_deltaquad index 40cbcb0df8..a01024e754 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/13013_deltaquad +++ b/ROMFS/px4fmu_common/init.d/airframes/13013_deltaquad @@ -33,9 +33,6 @@ param set-default CBRK_IO_SAFETY 22027 param set-default EKF2_GPS_POS_X -0.12 param set-default EKF2_IMU_POS_X -0.12 -param set-default EKF2_TAU_VEL 0.5 -param set-default EKF2_GPS_P_GATE 10 -param set-default EKF2_GPS_V_GATE 10 param set-default FW_ARSP_MODE 1 param set-default NPFG_PERIOD 25 @@ -51,7 +48,6 @@ param set-default FW_RR_P 0.18 param set-default FW_T_CLMB_MAX 3 param set-default FW_T_SINK_MAX 3 param set-default FW_T_SINK_MIN 1 -param set-default FW_T_VERT_ACC 6 param set-default FW_THR_TRIM 0.70 param set-default FW_THR_SLEW_MAX 1 param set-default FW_P_LIM_MAX 15 @@ -61,18 +57,11 @@ param set-default FW_P_RMAX_POS 45 param set-default FW_R_RMAX 50 param set-default FW_THR_MIN 0.55 param set-default FW_BAT_SCALE_EN 1 -param set-default FW_THR_ALT_SCL 2.7 param set-default FW_T_RLL2THR 20 -param set-default LNDMC_XY_VEL_MAX 1 -param set-default LNDMC_Z_VEL_MAX 0.7 - param set-default MC_ROLLRATE_P 0.16 param set-default MC_ROLLRATE_I 0.01 -param set-default MC_ROLLRATE_MAX 80 param set-default MC_PITCHRATE_I 0.05 -param set-default MC_PITCHRATE_MAX 80 -param set-default MC_YAW_P 3.5 param set-default MC_YAWRATE_MAX 20 param set-default MC_AIRMODE 1 @@ -81,16 +70,11 @@ param set-default MIS_DIST_1WP 100 param set-default MIS_TAKEOFF_ALT 15 param set-default MPC_XY_P 0.8 -param set-default MPC_XY_VEL_P_ACC 2 param set-default MPC_XY_VEL_MAX 5 -param set-default MPC_ACC_HOR_MAX 2 param set-default MPC_LAND_SPEED 1.2 param set-default MPC_TILTMAX_LND 35 param set-default MPC_Z_VEL_MAX_UP 1.5 -param set-default MPC_HOLD_MAX_XY 0.5 -param set-default MPC_HOLD_MAX_Z 0.5 param set-default MPC_TKO_RAMP_T 0.8 -param set-default MPC_XY_CRUISE 5 param set-default MPC_TILTMAX_AIR 25 param set-default MPC_TILTMAX_LND 25 param set-default MPC_YAWRAUTO_MAX 20 @@ -112,16 +96,13 @@ param set-default MAV_1_FORWARD 1 param set-default SER_TEL2_BAUD 57600 param set-default VT_TYPE 2 -param set-default VT_F_TRANS_THR 1 param set-default VT_PITCH_MIN 8 param set-default VT_FW_QC_P 55 param set-default VT_FW_QC_R 55 param set-default VT_TRANS_MIN_TM 15 param set-default VT_FWD_THRUST_SC 4 -param set-default VT_F_TRANS_DUR 1 param set-default VT_B_TRANS_THR 0.7 param set-default VT_TRANS_TIMEOUT 22 -param set-default VT_F_TRANS_RAMP 4 param set-default COM_RC_OVERRIDE 0 diff --git a/ROMFS/px4fmu_common/init.d/airframes/13014_vtol_babyshark b/ROMFS/px4fmu_common/init.d/airframes/13014_vtol_babyshark index f8cc4dbd50..ac59310758 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/13014_vtol_babyshark +++ b/ROMFS/px4fmu_common/init.d/airframes/13014_vtol_babyshark @@ -52,21 +52,12 @@ param set-default MC_YAWRATE_I 0.15 param set-default MC_YAWRATE_MAX 40 param set-default MC_YAWRATE_P 0.3 -param set-default MPC_ACC_DOWN_MAX 2 -param set-default MPC_ACC_HOR_MAX 2 -param set-default MPC_ACC_UP_MAX 3 param set-default MC_AIRMODE 1 -param set-default MPC_JERK_AUTO 4 param set-default MPC_LAND_SPEED 1 param set-default MPC_MAN_TILT_MAX 25 param set-default MPC_MAN_Y_MAX 40 -param set-default COM_SPOOLUP_TIME 1.5 param set-default MPC_THR_HOVER 0.45 param set-default MPC_TILTMAX_AIR 25 -param set-default MPC_TKO_RAMP_T 1.8 -param set-default MPC_VEL_MANUAL 3 -param set-default MPC_XY_CRUISE 3 -param set-default MPC_XY_VEL_MAX 3.5 param set-default MPC_YAWRAUTO_MAX 40 param set-default MPC_Z_VEL_MAX_UP 2 @@ -83,7 +74,6 @@ param set-default VT_B_DEC_MSS 1.5 param set-default VT_ELEV_MC_LOCK 0 param set-default VT_FWD_THRUST_SC 1.2 param set-default VT_F_TR_OL_TM 8 -param set-default VT_PSHER_RMP_DT 2 param set-default VT_TRANS_MIN_TM 4 param set-default VT_TYPE 2 diff --git a/ROMFS/px4fmu_common/init.d/rc.vtol_defaults b/ROMFS/px4fmu_common/init.d/rc.vtol_defaults index 0f3c4d98c0..2c273e9109 100644 --- a/ROMFS/px4fmu_common/init.d/rc.vtol_defaults +++ b/ROMFS/px4fmu_common/init.d/rc.vtol_defaults @@ -27,7 +27,6 @@ param set-default MIS_TKO_LAND_REQ 2 param set-default MPC_ACC_HOR_MAX 2 param set-default MPC_VEL_MANUAL 5 -param set-default MPC_XY_CRUISE 5 param set-default MPC_XY_ERR_MAX 5 param set-default MPC_XY_VEL_MAX 8 param set-default MPC_JERK_MAX 4.5