diff --git a/ROMFS/px4fmu_common/init.d/airframes/1000_rc_fw_easystar.hil b/ROMFS/px4fmu_common/init.d/airframes/1000_rc_fw_easystar.hil index ada6610c0e..4658f352e5 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/1000_rc_fw_easystar.hil +++ b/ROMFS/px4fmu_common/init.d/airframes/1000_rc_fw_easystar.hil @@ -18,7 +18,6 @@ . ${R}etc/init.d/rc.fw_defaults - param set-default BAT1_N_CELLS 3 param set-default FW_AIRSPD_MAX 20 @@ -40,7 +39,6 @@ param set-default FW_RR_P 0.3 param set-default RWTO_TKOFF 1 - param set SYS_HITL 1 # disable some checks to allow to fly diff --git a/ROMFS/px4fmu_common/init.d/airframes/10015_tbs_discovery b/ROMFS/px4fmu_common/init.d/airframes/10015_tbs_discovery index 3f6118e7b7..0b01898f4c 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/10015_tbs_discovery +++ b/ROMFS/px4fmu_common/init.d/airframes/10015_tbs_discovery @@ -34,5 +34,3 @@ param set-default MC_PITCHRATE_D 0.0025 param set-default MC_YAWRATE_P 0.28 set MIXER quad_w - -set PWM_OUT 1234 diff --git a/ROMFS/px4fmu_common/init.d/airframes/10016_3dr_iris b/ROMFS/px4fmu_common/init.d/airframes/10016_3dr_iris index a2822828f4..e3e54c8da6 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/10016_3dr_iris +++ b/ROMFS/px4fmu_common/init.d/airframes/10016_3dr_iris @@ -23,7 +23,6 @@ . ${R}etc/init.d/rc.mc_defaults - # TODO tune roll/pitch separately param set-default MC_ROLL_P 7 param set-default MC_ROLLRATE_I 0.05 @@ -39,5 +38,3 @@ param set-default BAT1_V_DIV 12.27559 param set-default BAT1_A_PER_V 15.39103 set MIXER quad_w - -set PWM_OUT 1234 diff --git a/ROMFS/px4fmu_common/init.d/airframes/10017_steadidrone_qu4d b/ROMFS/px4fmu_common/init.d/airframes/10017_steadidrone_qu4d index 507265e804..dfaaa816d0 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/10017_steadidrone_qu4d +++ b/ROMFS/px4fmu_common/init.d/airframes/10017_steadidrone_qu4d @@ -25,7 +25,6 @@ . ${R}etc/init.d/rc.mc_defaults - param set-default BAT1_N_CELLS 4 param set-default MC_ROLL_P 7 @@ -38,5 +37,3 @@ param set-default MC_PITCHRATE_I 0.05 param set-default MC_PITCHRATE_D 0.004 param set-default MC_YAW_P 4 set MIXER quad_w - -set PWM_OUT 1234 diff --git a/ROMFS/px4fmu_common/init.d/airframes/10018_tbs_endurance b/ROMFS/px4fmu_common/init.d/airframes/10018_tbs_endurance index c60c5ff64d..bbf00f86bc 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/10018_tbs_endurance +++ b/ROMFS/px4fmu_common/init.d/airframes/10018_tbs_endurance @@ -25,7 +25,6 @@ . ${R}etc/init.d/rc.mc_defaults - param set-default BAT1_N_CELLS 6 param set-default BAT1_V_EMPTY 3.5 @@ -42,5 +41,3 @@ param set-default MPC_XY_VEL_MAX 2 param set-default PWM_MAIN_MIN 1080 set MIXER quad_w - -set PWM_OUT 1234 diff --git a/ROMFS/px4fmu_common/init.d/airframes/1001_rc_quad_x.hil b/ROMFS/px4fmu_common/init.d/airframes/1001_rc_quad_x.hil index cb343bbdf1..d8096364ed 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/1001_rc_quad_x.hil +++ b/ROMFS/px4fmu_common/init.d/airframes/1001_rc_quad_x.hil @@ -12,7 +12,6 @@ . ${R}etc/init.d/rc.mc_defaults set MIXER quad_x -set PWM_OUT 1234 param set SYS_HITL 1 diff --git a/ROMFS/px4fmu_common/init.d/airframes/13004_quad+_tailsitter b/ROMFS/px4fmu_common/init.d/airframes/13004_quad+_tailsitter index 2e2f6ac4be..c4fc1ad0a6 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/13004_quad+_tailsitter +++ b/ROMFS/px4fmu_common/init.d/airframes/13004_quad+_tailsitter @@ -22,11 +22,11 @@ . ${R}etc/init.d/rc.vtol_defaults - param set-default PWM_MAIN_MAX 2000 param set-default VT_IDLE_PWM_MC 1080 param set-default VT_TYPE 0 + set MAV_TYPE 20 set MIXER quad_+_vtol diff --git a/ROMFS/px4fmu_common/init.d/airframes/13005_vtol_AAERT_quad b/ROMFS/px4fmu_common/init.d/airframes/13005_vtol_AAERT_quad index 699d039b8b..6f6ed72235 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/13005_vtol_AAERT_quad +++ b/ROMFS/px4fmu_common/init.d/airframes/13005_vtol_AAERT_quad @@ -23,10 +23,8 @@ . ${R}etc/init.d/rc.vtol_defaults - param set-default PWM_AUX_DIS5 950 - param set-default MC_ROLL_P 6 param set-default MC_ROLLRATE_P 0.17 param set-default MC_ROLLRATE_I 0.002 diff --git a/ROMFS/px4fmu_common/init.d/airframes/13006_vtol_standard_delta b/ROMFS/px4fmu_common/init.d/airframes/13006_vtol_standard_delta index 9e640846db..de7ef8cad5 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/13006_vtol_standard_delta +++ b/ROMFS/px4fmu_common/init.d/airframes/13006_vtol_standard_delta @@ -26,7 +26,6 @@ param set-default MC_ROLLRATE_I 0.01 param set-default MC_PITCHRATE_I 0.01 param set-default MC_YAW_P 3.5 - param set-default MC_YAWRATE_MAX 50 param set-default MPC_XY_P 0.8 diff --git a/ROMFS/px4fmu_common/init.d/airframes/13009_vtol_spt_ranger b/ROMFS/px4fmu_common/init.d/airframes/13009_vtol_spt_ranger index 099ba08069..dd0b4e7ed9 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/13009_vtol_spt_ranger +++ b/ROMFS/px4fmu_common/init.d/airframes/13009_vtol_spt_ranger @@ -13,7 +13,6 @@ . ${R}etc/init.d/rc.vtol_defaults - param set-default FW_AIRSPD_MAX 22 param set-default FW_AIRSPD_MIN 14 param set-default FW_AIRSPD_TRIM 16 @@ -68,7 +67,6 @@ param set-default PWM_AUX_REV4 1 param set-default PWM_AUX_DIS5 950 - param set-default VT_ARSP_TRANS 15 param set-default VT_F_TRANS_THR 0.6 param set-default VT_IDLE_PWM_MC 1180 diff --git a/ROMFS/px4fmu_common/init.d/airframes/13010_claire b/ROMFS/px4fmu_common/init.d/airframes/13010_claire index 18ae63b1c0..5d4976d9b3 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/13010_claire +++ b/ROMFS/px4fmu_common/init.d/airframes/13010_claire @@ -13,7 +13,6 @@ . ${R}etc/init.d/rc.vtol_defaults - param set-default PWM_AUX_DISARM 1000 param set-default PWM_AUX_MAX 2000 param set-default PWM_AUX_MIN 1000 diff --git a/ROMFS/px4fmu_common/init.d/airframes/13012_convergence b/ROMFS/px4fmu_common/init.d/airframes/13012_convergence index 28a63dbcd8..f56f7e2177 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/13012_convergence +++ b/ROMFS/px4fmu_common/init.d/airframes/13012_convergence @@ -22,7 +22,6 @@ . ${R}etc/init.d/rc.vtol_defaults - param set-default CBRK_AIRSPD_CHK 162128 param set-default FW_ARSP_MODE 1 diff --git a/ROMFS/px4fmu_common/init.d/airframes/13013_deltaquad b/ROMFS/px4fmu_common/init.d/airframes/13013_deltaquad index 729a5f8665..e3143fdf7e 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/13013_deltaquad +++ b/ROMFS/px4fmu_common/init.d/airframes/13013_deltaquad @@ -22,7 +22,6 @@ . ${R}etc/init.d/rc.vtol_defaults - param set-default BAT1_CAPACITY 23000 param set-default BAT1_N_CELLS 4 param set-default BAT1_R_INTERNAL 0.0025 diff --git a/ROMFS/px4fmu_common/init.d/airframes/13014_vtol_babyshark b/ROMFS/px4fmu_common/init.d/airframes/13014_vtol_babyshark index fe6cd3bf87..f8974c0265 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/13014_vtol_babyshark +++ b/ROMFS/px4fmu_common/init.d/airframes/13014_vtol_babyshark @@ -22,7 +22,6 @@ . ${R}etc/init.d/rc.vtol_defaults - param set-default BAT1_N_CELLS 6 param set-default FW_AIRSPD_MAX 30 diff --git a/ROMFS/px4fmu_common/init.d/airframes/13030_generic_vtol_quad_tiltrotor b/ROMFS/px4fmu_common/init.d/airframes/13030_generic_vtol_quad_tiltrotor index 06865b0f85..14e883e286 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/13030_generic_vtol_quad_tiltrotor +++ b/ROMFS/px4fmu_common/init.d/airframes/13030_generic_vtol_quad_tiltrotor @@ -26,8 +26,6 @@ . ${R}etc/init.d/rc.vtol_defaults - - param set-default VT_IDLE_PWM_MC 1100 param set-default VT_TYPE 1 param set-default VT_MOT_ID 1234 diff --git a/ROMFS/px4fmu_common/init.d/airframes/13050_generic_vtol_octo b/ROMFS/px4fmu_common/init.d/airframes/13050_generic_vtol_octo index 37d92fe4e6..523416ae7d 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/13050_generic_vtol_octo +++ b/ROMFS/px4fmu_common/init.d/airframes/13050_generic_vtol_octo @@ -25,7 +25,6 @@ . ${R}etc/init.d/rc.vtol_defaults - param set-default PWM_AUX_DIS5 950 param set-default VT_TYPE 2 diff --git a/ROMFS/px4fmu_common/init.d/airframes/13200_generic_vtol_tailsitter b/ROMFS/px4fmu_common/init.d/airframes/13200_generic_vtol_tailsitter index 23ea7fb2c9..5686023604 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/13200_generic_vtol_tailsitter +++ b/ROMFS/px4fmu_common/init.d/airframes/13200_generic_vtol_tailsitter @@ -18,7 +18,6 @@ . ${R}etc/init.d/rc.vtol_defaults - param set-default VT_ELEV_MC_LOCK 0 param set-default VT_MOT_COUNT 2 param set-default VT_TYPE 0 diff --git a/ROMFS/px4fmu_common/init.d/airframes/14001_tri_y_yaw+ b/ROMFS/px4fmu_common/init.d/airframes/14001_tri_y_yaw+ index 647a794505..5607827708 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/14001_tri_y_yaw+ +++ b/ROMFS/px4fmu_common/init.d/airframes/14001_tri_y_yaw+ @@ -19,5 +19,3 @@ . ${R}etc/init.d/rc.mc_defaults set MIXER tri_y_yaw+ - -set PWM_OUT 1234 diff --git a/ROMFS/px4fmu_common/init.d/airframes/14002_tri_y_yaw- b/ROMFS/px4fmu_common/init.d/airframes/14002_tri_y_yaw- index 65b427ff94..8ac71f0471 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/14002_tri_y_yaw- +++ b/ROMFS/px4fmu_common/init.d/airframes/14002_tri_y_yaw- @@ -19,5 +19,3 @@ . ${R}etc/init.d/rc.mc_defaults set MIXER tri_y_yaw- - -set PWM_OUT 1234 diff --git a/ROMFS/px4fmu_common/init.d/airframes/15001_coax_heli b/ROMFS/px4fmu_common/init.d/airframes/15001_coax_heli index c1d8ed37c3..da685868e2 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/15001_coax_heli +++ b/ROMFS/px4fmu_common/init.d/airframes/15001_coax_heli @@ -19,7 +19,6 @@ . ${R}etc/init.d/rc.mc_defaults set MIXER coax - param set-default MC_ROLLRATE_P 0.17 param set-default MC_ROLLRATE_I 0.05 param set-default MC_ROLLRATE_D 0.005 @@ -41,5 +40,4 @@ param set-default RTL_DESCEND_ALT 10 set MIXER_AUX pass # use PWM parameters for throttle channel -set PWM_AUX_OUT 1234 set PWM_OUT 34 diff --git a/ROMFS/px4fmu_common/init.d/airframes/16001_helicopter b/ROMFS/px4fmu_common/init.d/airframes/16001_helicopter index db8a761429..b97347ad56 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/16001_helicopter +++ b/ROMFS/px4fmu_common/init.d/airframes/16001_helicopter @@ -24,8 +24,7 @@ set MAV_TYPE 4 set MIXER blade130 -#set PWM_OUT 1234 - +set PWM_OUT none param set-default ATT_BIAS_MAX 0 diff --git a/ROMFS/px4fmu_common/init.d/airframes/18001_TF-B1 b/ROMFS/px4fmu_common/init.d/airframes/18001_TF-B1 index 53989028fd..dfc006ee82 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/18001_TF-B1 +++ b/ROMFS/px4fmu_common/init.d/airframes/18001_TF-B1 @@ -15,7 +15,6 @@ . ${R}etc/init.d/rc.balloon_defaults - param set-default COM_PREARM_MODE 2 # always in prearm state param set-default CBRK_IO_SAFETY 22027 param set-default SDLOG_PROFILE 17 @@ -28,6 +27,5 @@ param set-default SER_TEL2_BAUD 9600 set MAV_TYPE 8 param set MAV_TYPE ${MAV_TYPE} - set MIXER IO_pass set MIXER_AUX pass diff --git a/ROMFS/px4fmu_common/init.d/airframes/24001_dodeca_cox b/ROMFS/px4fmu_common/init.d/airframes/24001_dodeca_cox index f2e9813e86..dc2a23a5ca 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/24001_dodeca_cox +++ b/ROMFS/px4fmu_common/init.d/airframes/24001_dodeca_cox @@ -28,7 +28,6 @@ set VEHICLE_TYPE mc - param set-default NAV_ACC_RAD 2 param set-default PWM_AUX_RATE 400 diff --git a/ROMFS/px4fmu_common/init.d/airframes/2507_cloudship b/ROMFS/px4fmu_common/init.d/airframes/2507_cloudship index a040702c07..3b15aeb948 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/2507_cloudship +++ b/ROMFS/px4fmu_common/init.d/airframes/2507_cloudship @@ -18,6 +18,5 @@ param set-default COM_PREARM_MODE 2 param set-default CBRK_IO_SAFETY 22027 - set MIXER cloudship set PWM_OUT 1234 diff --git a/ROMFS/px4fmu_common/init.d/airframes/3032_skywalker_x5 b/ROMFS/px4fmu_common/init.d/airframes/3032_skywalker_x5 index d88cb83e38..f09bba392b 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/3032_skywalker_x5 +++ b/ROMFS/px4fmu_common/init.d/airframes/3032_skywalker_x5 @@ -37,5 +37,4 @@ param set-default FW_PR_FF 0.35 param set-default FW_RR_FF 0.6 param set-default FW_RR_P 0.04 - set MIXER fw_generic_wing diff --git a/ROMFS/px4fmu_common/init.d/airframes/3033_wingwing b/ROMFS/px4fmu_common/init.d/airframes/3033_wingwing index 453d82346d..44c5ec9d26 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/3033_wingwing +++ b/ROMFS/px4fmu_common/init.d/airframes/3033_wingwing @@ -41,7 +41,6 @@ param set-default FW_RR_P 0.04 param set-default PWM_MAIN_DISARM 1000 - # Configure this as plane. set MAV_TYPE 1 diff --git a/ROMFS/px4fmu_common/init.d/airframes/3100_tbs_caipirinha b/ROMFS/px4fmu_common/init.d/airframes/3100_tbs_caipirinha index 3fc962c9ef..cc74225a12 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/3100_tbs_caipirinha +++ b/ROMFS/px4fmu_common/init.d/airframes/3100_tbs_caipirinha @@ -21,7 +21,6 @@ . ${R}etc/init.d/rc.fw_defaults - param set-default FW_AIRSPD_MAX 25 param set-default FW_AIRSPD_MIN 12.5 param set-default FW_AIRSPD_TRIM 16.5 diff --git a/ROMFS/px4fmu_common/init.d/airframes/4001_quad_x b/ROMFS/px4fmu_common/init.d/airframes/4001_quad_x index cfa2ab089b..aabc2b29ca 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4001_quad_x +++ b/ROMFS/px4fmu_common/init.d/airframes/4001_quad_x @@ -21,7 +21,3 @@ # . ${R}etc/init.d/rc.mc_defaults - -set MIXER quad_x - -set PWM_OUT 1234 diff --git a/ROMFS/px4fmu_common/init.d/airframes/4003_qavr5 b/ROMFS/px4fmu_common/init.d/airframes/4003_qavr5 index 4638e92a54..f1a3a33d3b 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4003_qavr5 +++ b/ROMFS/px4fmu_common/init.d/airframes/4003_qavr5 @@ -13,10 +13,6 @@ . ${R}etc/init.d/rc.mc_defaults -set MIXER quad_x -set PWM_OUT 1234 - - param set-default MC_ROLL_P 8 param set-default MC_ROLLRATE_P 0.08 param set-default MC_ROLLRATE_I 0.16 diff --git a/ROMFS/px4fmu_common/init.d/airframes/4009_qav250 b/ROMFS/px4fmu_common/init.d/airframes/4009_qav250 index c3ecf7207e..4efe6c7c5a 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4009_qav250 +++ b/ROMFS/px4fmu_common/init.d/airframes/4009_qav250 @@ -13,10 +13,6 @@ . ${R}etc/init.d/rc.mc_defaults -set MIXER quad_x -set PWM_OUT 1234 - - param set-default ATT_BIAS_MAX 0 param set-default CBRK_IO_SAFETY 22027 diff --git a/ROMFS/px4fmu_common/init.d/airframes/4010_dji_f330 b/ROMFS/px4fmu_common/init.d/airframes/4010_dji_f330 index 5036383320..f6eef63d7d 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4010_dji_f330 +++ b/ROMFS/px4fmu_common/init.d/airframes/4010_dji_f330 @@ -11,9 +11,6 @@ . ${R}etc/init.d/rc.mc_defaults -set MIXER quad_x -set PWM_OUT 1234 - param set-default MC_ROLL_P 7 param set-default MC_ROLLRATE_I 0.05 param set-default MC_PITCH_P 7 diff --git a/ROMFS/px4fmu_common/init.d/airframes/4011_dji_f450 b/ROMFS/px4fmu_common/init.d/airframes/4011_dji_f450 index 9697ba2038..1d10254353 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4011_dji_f450 +++ b/ROMFS/px4fmu_common/init.d/airframes/4011_dji_f450 @@ -10,9 +10,6 @@ . ${R}etc/init.d/rc.mc_defaults -set MIXER quad_x -set PWM_OUT 1234 - param set-default MC_ROLL_P 7 param set-default MC_ROLLRATE_I 0.05 param set-default MC_PITCH_P 7 diff --git a/ROMFS/px4fmu_common/init.d/airframes/4014_s500 b/ROMFS/px4fmu_common/init.d/airframes/4014_s500 index cbb1dcfbd6..2c75a46c25 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4014_s500 +++ b/ROMFS/px4fmu_common/init.d/airframes/4014_s500 @@ -13,10 +13,6 @@ . ${R}etc/init.d/rc.mc_defaults -set MIXER quad_x -set PWM_OUT 1234 - - param set-default MC_ROLLRATE_P 0.18 param set-default MC_PITCHRATE_P 0.18 param set-default MC_ROLLRATE_I 0.15 diff --git a/ROMFS/px4fmu_common/init.d/airframes/4015_holybro_s500 b/ROMFS/px4fmu_common/init.d/airframes/4015_holybro_s500 index f1b79db664..d16ec71d3f 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4015_holybro_s500 +++ b/ROMFS/px4fmu_common/init.d/airframes/4015_holybro_s500 @@ -13,10 +13,6 @@ . ${R}etc/init.d/rc.mc_defaults -set MIXER quad_x -set PWM_OUT 1234 - - param set-default IMU_GYRO_CUTOFF 30 param set-default MC_ROLLRATE_P 0.14 diff --git a/ROMFS/px4fmu_common/init.d/airframes/4016_holybro_px4vision b/ROMFS/px4fmu_common/init.d/airframes/4016_holybro_px4vision index 46e9074065..84beba4dfa 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4016_holybro_px4vision +++ b/ROMFS/px4fmu_common/init.d/airframes/4016_holybro_px4vision @@ -16,10 +16,6 @@ . ${R}etc/init.d/rc.mc_defaults -set MIXER quad_x -set PWM_OUT 1234 - - # System parameters # use FMU motor outputs for less delay in the rate control loop param set-default SYS_USE_IO 0 diff --git a/ROMFS/px4fmu_common/init.d/airframes/4017_nxp_hovergames b/ROMFS/px4fmu_common/init.d/airframes/4017_nxp_hovergames index efb3e0adc0..dcfe0f943b 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4017_nxp_hovergames +++ b/ROMFS/px4fmu_common/init.d/airframes/4017_nxp_hovergames @@ -18,9 +18,6 @@ . ${R}etc/init.d/rc.mc_defaults -set MIXER quad_x -set PWM_OUT 1234 - param set-default IMU_DGYRO_CUTOFF 20 param set-default MC_ROLLRATE_P 0.18 diff --git a/ROMFS/px4fmu_common/init.d/airframes/4018_s500_ctrlalloc b/ROMFS/px4fmu_common/init.d/airframes/4018_s500_ctrlalloc index 99dbec4609..d92aeafd8f 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4018_s500_ctrlalloc +++ b/ROMFS/px4fmu_common/init.d/airframes/4018_s500_ctrlalloc @@ -13,6 +13,7 @@ . ${R}etc/init.d/rc.mc_defaults . ${R}etc/init.d/rc.ctrlalloc +set MIXER none param set-default MPC_USE_HTE 0 @@ -50,7 +51,5 @@ param set-default CA_MC_R3_CT 6.5 param set-default CA_MC_R3_KM -0.05 set MIXER direct -set PWM_OUT 1234 set MIXER_AUX direct_aux -set PWM_AUX_OUT 1234 diff --git a/ROMFS/px4fmu_common/init.d/airframes/4030_3dr_solo b/ROMFS/px4fmu_common/init.d/airframes/4030_3dr_solo index f1e581dea0..f698daed99 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4030_3dr_solo +++ b/ROMFS/px4fmu_common/init.d/airframes/4030_3dr_solo @@ -18,7 +18,6 @@ . ${R}etc/init.d/rc.mc_defaults - # tuning param set-default MC_PITCHRATE_P 0.11 param set-default MC_ROLLRATE_P 0.11 @@ -83,7 +82,5 @@ param set-default RC5_TRIM 1500 param set-default MAV_0_RATE 80000 param set-default MAV_0_MODE 2 param set-default SER_TEL1_BAUD 921600 -set MIXER quad_x -set PWM_OUT 1234 set MIXER_AUX none diff --git a/ROMFS/px4fmu_common/init.d/airframes/4031_3dr_quad b/ROMFS/px4fmu_common/init.d/airframes/4031_3dr_quad index 1339f8824c..e29fbf8dd6 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4031_3dr_quad +++ b/ROMFS/px4fmu_common/init.d/airframes/4031_3dr_quad @@ -13,9 +13,6 @@ . ${R}etc/init.d/rc.mc_defaults -set MIXER quad_x -set PWM_OUT 1234 - param set-default MC_ROLLRATE_P 0.14 param set-default MC_ROLLRATE_I 0.1 param set-default MC_ROLLRATE_D 0.004 diff --git a/ROMFS/px4fmu_common/init.d/airframes/4040_reaper b/ROMFS/px4fmu_common/init.d/airframes/4040_reaper index 49f64f2d28..45ec3f081b 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4040_reaper +++ b/ROMFS/px4fmu_common/init.d/airframes/4040_reaper @@ -42,8 +42,4 @@ param set-default RTL_DESCEND_ALT 10 set MIXER quad_h -set PWM_OUT 1234 - set MIXER_AUX pass - -set PWM_AUX_OUT 1234 diff --git a/ROMFS/px4fmu_common/init.d/airframes/4041_beta75x b/ROMFS/px4fmu_common/init.d/airframes/4041_beta75x index 50acc38438..a04cc31f98 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4041_beta75x +++ b/ROMFS/px4fmu_common/init.d/airframes/4041_beta75x @@ -23,7 +23,6 @@ . ${R}etc/init.d/rc.mc_defaults - param set-default CBRK_SUPPLY_CHK 894281 param set-default CBRK_USB_CHK 197848 @@ -57,5 +56,3 @@ param set-default SYS_HAS_MAG 0 param set-default BAT1_N_CELLS 2 # The Whoop uses reversed props set MIXER quad_h -set PWM_OUT 1234 - diff --git a/ROMFS/px4fmu_common/init.d/airframes/4050_generic_250 b/ROMFS/px4fmu_common/init.d/airframes/4050_generic_250 index 9d82e9fa1e..dfd2bacd61 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4050_generic_250 +++ b/ROMFS/px4fmu_common/init.d/airframes/4050_generic_250 @@ -12,10 +12,6 @@ . ${R}etc/init.d/rc.mc_defaults -set MIXER quad_x -set PWM_OUT 1234 - - param set-default MC_ROLL_P 8 param set-default MC_ROLLRATE_P 0.08 param set-default MC_ROLLRATE_I 0.25 diff --git a/ROMFS/px4fmu_common/init.d/airframes/4051_s250aq b/ROMFS/px4fmu_common/init.d/airframes/4051_s250aq index fe7e3322bf..118cbeca21 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4051_s250aq +++ b/ROMFS/px4fmu_common/init.d/airframes/4051_s250aq @@ -23,11 +23,9 @@ . ${R}etc/init.d/rc.mc_defaults set MIXER quad_s250aq + set MAV_TYPE 2 -set PWM_OUT 1234 - - param set-default ATT_BIAS_MAX 0 param set-default CBRK_IO_SAFETY 22027 diff --git a/ROMFS/px4fmu_common/init.d/airframes/4052_holybro_qav250 b/ROMFS/px4fmu_common/init.d/airframes/4052_holybro_qav250 index d2c26f373c..aeb48c41d7 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4052_holybro_qav250 +++ b/ROMFS/px4fmu_common/init.d/airframes/4052_holybro_qav250 @@ -15,10 +15,6 @@ . ${R}etc/init.d/rc.mc_defaults -set MIXER quad_x -set PWM_OUT 1234 - - # The set does not include a battery, but most people will probably use 4S param set-default BAT1_N_CELLS 4 diff --git a/ROMFS/px4fmu_common/init.d/airframes/4053_holybro_kopis2 b/ROMFS/px4fmu_common/init.d/airframes/4053_holybro_kopis2 index fc5695e401..24a9fa9c46 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4053_holybro_kopis2 +++ b/ROMFS/px4fmu_common/init.d/airframes/4053_holybro_kopis2 @@ -13,10 +13,6 @@ . ${R}etc/init.d/rc.mc_defaults -set MIXER quad_x -set PWM_OUT 1234 - - param set-default BAT1_N_CELLS 4 param set-default GPS_1_CONFIG 0 diff --git a/ROMFS/px4fmu_common/init.d/airframes/4060_dji_matrice_100 b/ROMFS/px4fmu_common/init.d/airframes/4060_dji_matrice_100 index 837ede54c1..52d37bf9a4 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4060_dji_matrice_100 +++ b/ROMFS/px4fmu_common/init.d/airframes/4060_dji_matrice_100 @@ -13,10 +13,6 @@ . ${R}etc/init.d/rc.mc_defaults -set MIXER quad_x -set PWM_OUT 1234 - - param set-default BAT1_N_CELLS 6 param set-default MC_ROLLRATE_P 0.05 diff --git a/ROMFS/px4fmu_common/init.d/airframes/4061_atl_mantis_edu b/ROMFS/px4fmu_common/init.d/airframes/4061_atl_mantis_edu index df57c387c8..3b4e2203a6 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4061_atl_mantis_edu +++ b/ROMFS/px4fmu_common/init.d/airframes/4061_atl_mantis_edu @@ -19,7 +19,6 @@ set MIXER none set MIXER_AUX none - # Battery settings param set-default BAT_CRIT_THR 0.20 param set-default BAT_LOW_THR 0.25 diff --git a/ROMFS/px4fmu_common/init.d/airframes/4071_ifo b/ROMFS/px4fmu_common/init.d/airframes/4071_ifo index c2b2668a25..a3ec1dc227 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4071_ifo +++ b/ROMFS/px4fmu_common/init.d/airframes/4071_ifo @@ -28,10 +28,8 @@ set PWM_OUT 1234 # Attitude & rate gains param set-default MC_ROLLRATE_D 0.0013 - param set-default MC_PITCHRATE_D 0.0016 - param set-default MC_YAW_FF 0.5 param set-default MPC_MANTHR_MAX 0.9 diff --git a/ROMFS/px4fmu_common/init.d/airframes/4072_draco b/ROMFS/px4fmu_common/init.d/airframes/4072_draco index 030314cd36..525bc56514 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4072_draco +++ b/ROMFS/px4fmu_common/init.d/airframes/4072_draco @@ -22,10 +22,6 @@ . ${R}etc/init.d/rc.mc_defaults -set MIXER quad_x -set PWM_OUT 1234 - - # use the Q attitude estimator, it works w/o mag or GPS. param set-default SYS_MC_EST_GROUP 3 param set-default ATT_ACC_COMP 0 diff --git a/ROMFS/px4fmu_common/init.d/airframes/4090_nanomind b/ROMFS/px4fmu_common/init.d/airframes/4090_nanomind index e265159a6d..5215931a84 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4090_nanomind +++ b/ROMFS/px4fmu_common/init.d/airframes/4090_nanomind @@ -17,10 +17,6 @@ . ${R}etc/init.d/rc.mc_defaults -set MIXER quad_x -set PWM_OUT 1234 - - param set-default BAT1_N_CELLS 1 param set-default MC_ROLL_P 8 diff --git a/ROMFS/px4fmu_common/init.d/airframes/4100_tiltquadrotor b/ROMFS/px4fmu_common/init.d/airframes/4100_tiltquadrotor index 17eac55c92..54fd22a5dc 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4100_tiltquadrotor +++ b/ROMFS/px4fmu_common/init.d/airframes/4100_tiltquadrotor @@ -31,5 +31,3 @@ # Set mixer set MIXER tilt_quad set MIXER_AUX tilt_quad - -set PWM_OUT 1234 diff --git a/ROMFS/px4fmu_common/init.d/airframes/4250_teal b/ROMFS/px4fmu_common/init.d/airframes/4250_teal deleted file mode 100644 index 39b14e291c..0000000000 --- a/ROMFS/px4fmu_common/init.d/airframes/4250_teal +++ /dev/null @@ -1,190 +0,0 @@ -#!/bin/sh -# -# @name Teal One -# -# @type Quadrotor x -# @class Copter -# -# @output MAIN1 motor 1 -# @output MAIN2 motor 2 -# @output MAIN3 motor 3 -# @output MAIN4 motor 4 -# -# @maintainer Matt McFadden -# -# @board px4_fmu-v2 exclude -# @board px4_fmu-v3 exclude -# @board px4_fmu-v4pro exclude -# @board px4_fmu-v5 exclude -# @board px4_fmu-v5x exclude -# @board bitcraze_crazyflie exclude -# - -echo "Executing 4250_teal script." - -. ${R}etc/init.d/rc.mc_defaults - -set MIXER quad_x -set PWM_OUT 1234 - - -# First thing, reset all params to default... EXCEPT THIS LIST -param reset_all SYS_AUTOSTART SYS_AUTOCONFIG RC* COM_FLTMODE* LND_FLIGHT_T_* TC_* CAL_ACC* CAL_GYRO* CAL_MAG* SENS_BOARD* EKF2_MAGBIAS* - -# battery -param set-default BAT_CRIT_THR 0.15 -param set-default BAT_EMERGEN_THR 0.075 -param set-default BAT_LOW_THR 0.20 - -param set-default BAT1_CAPACITY 2750 -param set-default BAT1_N_CELLS 4 -param set-default BAT1_R_INTERNAL 0.06 -param set-default BAT1_SOURCE 1 -param set-default BAT1_V_CHARGED 4.15 -param set-default BAT1_V_DIV 11.1625 -param set-default BAT1_V_EMPTY 3.65 -param set-default BAT1_V_OFFS_CURR -0.0045 - -# sensor calibration -param set-default CAL_MAG_SIDES 63 - -# circuit breakers -param set-default CBRK_IO_SAFETY 22027 -param set-default CBRK_USB_CHK 197848 - -# commander -param set-default COM_DISARM_LAND 0.1 -# Return mode at critically low level, Land mode at current position if reaching dangerously low levels. -param set-default COM_LOW_BAT_ACT 3 - -# ekf2 -param set-default EKF2_MAG_TYPE 1 -param set-default EKF2_GPS_CHECK 511 -param set-default EKF2_GPS_POS_X -0.04 -param set-default EKF2_IMU_POS_X -0.06 -param set-default EKF2_PCOEF_XN 0.1 -param set-default EKF2_PCOEF_XP -0.5 -param set-default EKF2_RNG_A_VMAX 20 -param set-default EKF2_RNG_NOISE 0.2 -param set-default EKF2_MIN_RNG 0.07 - -# geofence -# Geofence violation action -- Warning. -param set-default GF_ACTION 1 - -# land detector -param set-default LNDMC_XY_VEL_MAX 1 -# This is set high because we have lots of vibrations while in contact with ground. -param set-default LNDMC_ROT_MAX 50 - -# serial comms -param set-default SER_TEL1_BAUD 921600 -param set-default SER_TEL2_BAUD 921600 - -# mavlink stream configuration -# TEL1 ttyS1 -- disabled. TX1 FTDI UART has issues. -param set-default MAV_0_CONFIG 0 -param set-default MAV_0_RATE 800000 - -# TEL2 ttyS2 -- Primary MAVLINK stream to companion computer. -param set-default MAV_1_CONFIG 102 -param set-default MAV_1_RATE 800000 - -# mc_att_control -param set-default MC_ACRO_P_MAX 360 -param set-default MC_ACRO_R_MAX 360 -param set-default MC_ACRO_Y_MAX 360 - -param set-default MC_ROLL_P 6 -param set-default MC_ROLLRATE_P 0.055 -param set-default MC_ROLLRATE_D 0.0012 -param set-default MC_ROLLRATE_MAX 180 - -param set-default MC_PITCHRATE_P 0.06 -param set-default MC_PITCHRATE_D 0.0012 -param set-default MC_PITCHRATE_MAX 180 - -param set-default MC_YAW_P 1 -param set-default MC_YAWRATE_P 0.08 -param set-default MC_YAWRATE_I 0.08 - -param set-default MC_YAWRATE_MAX 180 - -# Set to reduce voltage transients as seen by battery management system. -param set-default MOT_SLEW_MAX 0.15 - -#### CONTROLLER ### -param set-default MPC_LAND_ALT1 8 -param set-default MPC_LAND_ALT2 5 -param set-default MPC_TKO_RAMP_T 0.75 -param set-default MPC_TKO_SPEED 0.75 -param set-default MPC_TILTMAX_LND 18 -param set-default MPC_TILTMAX_AIR 45 -param set-default MPC_MAN_TILT_MAX 45 - -param set-default MPC_MANTHR_MAX 0.85 -param set-default MPC_MANTHR_MIN 0.15 -# Full throttle can trip over current protection on BMS. -param set-default MPC_THR_MAX 0.85 -param set-default MPC_THR_MIN 0.15 - -param set-default MPC_VEL_MANUAL 26.5 -# RTL speed, it was too fast and scaring people. -param set-default MPC_XY_CRUISE 15 - -param set-default MPC_MAN_Y_MAX 200 - -param set-default MPC_JERK_MAX 5 -param set-default MPC_ACC_UP_MAX 10 -param set-default MPC_ACC_DOWN_MAX 10 -param set-default MPC_ACC_HOR 10 -param set-default MPC_ACC_HOR_MAX 15 - -param set-default MPC_XY_P 1.15 -param set-default MPC_XY_VEL_P_ACC 2.8 -param set-default MPC_XY_VEL_I_ACC 0.28 -param set-default MPC_XY_VEL_D_ACC 0.28 -param set-default MPC_XY_VEL_MAX 26.5 - -param set-default MPC_Z_P 0.85 -param set-default MPC_Z_VEL_P_ACC 5 -param set-default MPC_Z_VEL_I_ACC 1.7 -param set-default MPC_Z_VEL_D_ACC 0.4 -# Documentation says limit is 8.0, but does not seem to be enforced in code. -param set-default MPC_Z_VEL_MAX_UP 20 -param set-default MPC_Z_VEL_MAX_DN 2.5 -#### CONTROLLER ### - -# navigator -param set-default NAV_ACC_RAD 2.5 -# RC loss failsafe behavior -- hold mode. -param set-default NAV_RCL_ACT 1 - -# pwm control -param set-default PWM_MAIN_DISARM 900 -param set-default PWM_MAIN_MAX 1850 -param set-default PWM_MAIN_MIN 1075 -# Oneshot125 -param set-default PWM_MAIN_RATE 0 - -# rtl -param set-default RTL_DESCEND_ALT 5 -param set-default RTL_LAND_DELAY 5 -param set-default RTL_MIN_DIST 7.5 -param set-default RTL_RETURN_ALT 25 - -# calibration -param set-default CAL_ACC0_PRIO 255 -param set-default CAL_ACC1_PRIO 0 - -param set-default CAL_GYRO0_PRIO 255 -param set-default CAL_GYRO1_PRIO 0 -# Logger mode. Default(1) + estimator replay(2) + thermal calibration(4) -param set-default SDLOG_PROFILE 6 - -# Do not start frsky_telemetry on port ttyS6 by default, PGA460 lives there. 500 is in arbitrary unused number. -param set TEL_FRSKY_CONFIG 500 -# We want to make sure these always start -param set SENS_EN_PGA460 1 -param set SENS_EN_THERMAL 1 -param set SENS_EN_BATT 1 diff --git a/ROMFS/px4fmu_common/init.d/airframes/4500_clover4 b/ROMFS/px4fmu_common/init.d/airframes/4500_clover4 index 91a5ef23f0..d8116882fe 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4500_clover4 +++ b/ROMFS/px4fmu_common/init.d/airframes/4500_clover4 @@ -13,10 +13,6 @@ . ${R}etc/init.d/rc.mc_defaults -set MIXER quad_x -set PWM_OUT 1234 - - param set-default MC_PITCHRATE_P 0.087 param set-default MC_PITCHRATE_I 0.037 param set-default MC_PITCHRATE_D 0.0044 diff --git a/ROMFS/px4fmu_common/init.d/airframes/4900_crazyflie b/ROMFS/px4fmu_common/init.d/airframes/4900_crazyflie index 7723f11a84..cd7a74134b 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4900_crazyflie +++ b/ROMFS/px4fmu_common/init.d/airframes/4900_crazyflie @@ -17,7 +17,6 @@ . ${R}etc/init.d/rc.mc_defaults set MIXER quad_x_cw -set PWM_OUT 1234 param set-default BAT1_N_CELLS 1 param set-default BAT1_CAPACITY 240 @@ -69,4 +68,3 @@ set PWM_MAIN_MIN none syslink start mavlink start -d /dev/bridge0 -b 57600 -m osd -r 40000 - diff --git a/ROMFS/px4fmu_common/init.d/airframes/4901_crazyflie21 b/ROMFS/px4fmu_common/init.d/airframes/4901_crazyflie21 index 690b27611a..878a281a67 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4901_crazyflie21 +++ b/ROMFS/px4fmu_common/init.d/airframes/4901_crazyflie21 @@ -17,7 +17,6 @@ . ${R}etc/init.d/rc.mc_defaults set MIXER quad_x_cw -set PWM_OUT 1234 param set-default SYS_MC_EST_GROUP 2 param set-default SYS_HAS_MAG 0 @@ -61,7 +60,6 @@ param set-default PWM_MAIN_RATE 3921 param set-default SENS_FLOW_MINRNG 0.05 - set PWM_MAIN_DISARM none set PWM_MAIN_MAX none set PWM_MAIN_MIN none diff --git a/ROMFS/px4fmu_common/init.d/airframes/50003_aion_robotics_r1_rover b/ROMFS/px4fmu_common/init.d/airframes/50003_aion_robotics_r1_rover index 1fa95631f6..7a18aa5b11 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/50003_aion_robotics_r1_rover +++ b/ROMFS/px4fmu_common/init.d/airframes/50003_aion_robotics_r1_rover @@ -18,7 +18,6 @@ . ${R}etc/init.d/rc.rover_defaults - param set-default BAT1_N_CELLS 4 param set-default EKF2_GBIAS_INIT 0.01 diff --git a/ROMFS/px4fmu_common/init.d/airframes/50004_nxpcup_car_dfrobot_gpx b/ROMFS/px4fmu_common/init.d/airframes/50004_nxpcup_car_dfrobot_gpx index 92ea1bea32..cb1dd1eaea 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/50004_nxpcup_car_dfrobot_gpx +++ b/ROMFS/px4fmu_common/init.d/airframes/50004_nxpcup_car_dfrobot_gpx @@ -20,7 +20,6 @@ . ${R}etc/init.d/rc.rover_defaults - param set-default BAT1_N_CELLS 2 param set-default EKF2_GBIAS_INIT 0.01 diff --git a/ROMFS/px4fmu_common/init.d/airframes/5001_quad_+ b/ROMFS/px4fmu_common/init.d/airframes/5001_quad_+ index 263e7caa6c..3d172387c8 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/5001_quad_+ +++ b/ROMFS/px4fmu_common/init.d/airframes/5001_quad_+ @@ -26,5 +26,3 @@ . ${R}etc/init.d/rc.mc_defaults set MIXER quad_+ - -set PWM_OUT 1234 diff --git a/ROMFS/px4fmu_common/init.d/airframes/60002_uuv_bluerov2_heavy b/ROMFS/px4fmu_common/init.d/airframes/60002_uuv_bluerov2_heavy index e49c74591e..341cd4aaa1 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/60002_uuv_bluerov2_heavy +++ b/ROMFS/px4fmu_common/init.d/airframes/60002_uuv_bluerov2_heavy @@ -22,7 +22,6 @@ . ${R}etc/init.d/rc.uuv_defaults - #Set data link loss failsafe mode (0: disabled) # disable circuit breaker for airspeed sensor @@ -43,4 +42,3 @@ param set-default BAT_V_OFFS_CURR 0.33 set PWM_OUT 12345678 # set MIXER IO_pass set MIXER vectored6dof - diff --git a/ROMFS/px4fmu_common/init.d/airframes/6002_draco_r b/ROMFS/px4fmu_common/init.d/airframes/6002_draco_r index 584c3b447c..bc8f575fd1 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/6002_draco_r +++ b/ROMFS/px4fmu_common/init.d/airframes/6002_draco_r @@ -26,6 +26,7 @@ # . ${R}etc/init.d/rc.mc_defaults + set MIXER hexa_x set PWM_OUT 12345678 diff --git a/ROMFS/px4fmu_common/init.d/airframes/6003_hexa_x_ctrlalloc b/ROMFS/px4fmu_common/init.d/airframes/6003_hexa_x_ctrlalloc index 00c31ab2ec..894c3caf0c 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/6003_hexa_x_ctrlalloc +++ b/ROMFS/px4fmu_common/init.d/airframes/6003_hexa_x_ctrlalloc @@ -13,7 +13,6 @@ . ${R}etc/init.d/rc.mc_defaults . ${R}etc/init.d/rc.ctrlalloc - param set-default MPC_USE_HTE 0 param set-default VM_MASS 1.5 diff --git a/ROMFS/px4fmu_common/init.d/rc.mc_defaults b/ROMFS/px4fmu_common/init.d/rc.mc_defaults index 7a9fc56414..2ce920f5c1 100644 --- a/ROMFS/px4fmu_common/init.d/rc.mc_defaults +++ b/ROMFS/px4fmu_common/init.d/rc.mc_defaults @@ -25,4 +25,8 @@ param set-default GPS_UBX_DYNMODEL 6 # set MIXER_AUX pass +set MIXER quad_x + +set PWM_OUT 1234 + set PWM_AUX_OUT 1234