diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/1022_uuv_bluerov2_heavy b/ROMFS/px4fmu_common/init.d-posix/airframes/1022_uuv_bluerov2_heavy index e7814e3530..e7ee3540e5 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/1022_uuv_bluerov2_heavy +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/1022_uuv_bluerov2_heavy @@ -11,6 +11,5 @@ param set-default NAV_DLL_ACT 0 # disable circuit breaker for airspeed sensor param set-default CBRK_AIRSPD_CHK 162128 -set PWM_OUT 12345678 set MIXER_FILE etc/mixers-sitl/vectored6dof_sitl.main.mix set MIXER custom diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/2507_cloudship b/ROMFS/px4fmu_common/init.d-posix/airframes/2507_cloudship index 09bfb9b528..e6684dd3ce 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/2507_cloudship +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/2507_cloudship @@ -12,4 +12,3 @@ . ${R}etc/init.d/rc.airship_defaults set MIXER cloudship -set PWM_OUT 1234 diff --git a/ROMFS/px4fmu_common/init.d-posix/rcS b/ROMFS/px4fmu_common/init.d-posix/rcS index ff5b7abee5..d87937d41d 100644 --- a/ROMFS/px4fmu_common/init.d-posix/rcS +++ b/ROMFS/px4fmu_common/init.d-posix/rcS @@ -30,7 +30,6 @@ set MIXER_AUX none set MIXER_FILE none set OUTPUT_MODE sim set EXTRA_MIXER_MODE none -set PWM_OUT none set SDCARD_MIXERS_PATH etc/mixers set USE_IO no set VEHICLE_TYPE none diff --git a/ROMFS/px4fmu_common/init.d/airframes/10015_tbs_discovery b/ROMFS/px4fmu_common/init.d/airframes/10015_tbs_discovery index a33707b682..e3b264ba76 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/10015_tbs_discovery +++ b/ROMFS/px4fmu_common/init.d/airframes/10015_tbs_discovery @@ -23,8 +23,9 @@ # @board bitcraze_crazyflie exclude # -. ${R}etc/init.d/rc.mc_defaults +. ${R}etc/init.d/rc.mc_quad_defaults +set MIXER quad_w param set-default MC_ROLL_P 6.5 param set-default MC_ROLLRATE_P 0.1 @@ -38,6 +39,3 @@ param set-default MC_YAW_P 2.8 param set-default MC_YAWRATE_P 0.28 param set-default MC_YAWRATE_I 0.1 param set-default MC_YAWRATE_D 0 -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 ea593e825b..434f53e123 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/10016_3dr_iris +++ b/ROMFS/px4fmu_common/init.d/airframes/10016_3dr_iris @@ -21,8 +21,9 @@ # @board bitcraze_crazyflie exclude # -. ${R}etc/init.d/rc.mc_defaults +. ${R}etc/init.d/rc.mc_quad_defaults +set MIXER quad_w # TODO tune roll/pitch separately param set-default MC_ROLL_P 7 @@ -40,6 +41,3 @@ param set-default MC_YAWRATE_D 0 param set-default BAT_V_DIV 12.27559 param set-default BAT_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 1d7e3e268c..a367ed8e37 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/10017_steadidrone_qu4d +++ b/ROMFS/px4fmu_common/init.d/airframes/10017_steadidrone_qu4d @@ -23,8 +23,9 @@ # @board bitcraze_crazyflie exclude # -. ${R}etc/init.d/rc.mc_defaults +. ${R}etc/init.d/rc.mc_quad_defaults +set MIXER quad_w param set-default BAT_N_CELLS 4 @@ -40,6 +41,3 @@ param set-default MC_YAW_P 4 param set-default MC_YAWRATE_P 0.2 param set-default MC_YAWRATE_I 0.1 param set-default MC_YAWRATE_D 0 -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 05b39e571e..957b1713be 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/10018_tbs_endurance +++ b/ROMFS/px4fmu_common/init.d/airframes/10018_tbs_endurance @@ -23,8 +23,9 @@ # @board bitcraze_crazyflie exclude # -. ${R}etc/init.d/rc.mc_defaults +. ${R}etc/init.d/rc.mc_quad_defaults +set MIXER quad_w param set-default BAT_N_CELLS 6 param set-default BAT_V_EMPTY 3.5 @@ -43,8 +44,3 @@ param set-default MC_YAWRATE_I 0.1 param set-default MC_YAWRATE_D 0 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 3cf60a0f98..74931ea067 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 @@ -11,7 +11,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/1002_standard_vtol.hil b/ROMFS/px4fmu_common/init.d/airframes/1002_standard_vtol.hil index 0eb7b40ff2..0dd4e7028f 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/1002_standard_vtol.hil +++ b/ROMFS/px4fmu_common/init.d/airframes/1002_standard_vtol.hil @@ -13,7 +13,6 @@ . ${R}etc/init.d/rc.vtol_defaults - param set-default BAT_N_CELLS 3 param set-default COM_RC_IN_MODE 1 @@ -78,5 +77,3 @@ param set-default CBRK_IO_SAFETY 22027 set MAV_TYPE 22 set MIXER standard_vtol_hitl - -set PWM_OUT 1234 diff --git a/ROMFS/px4fmu_common/init.d/airframes/11001_hexa_cox b/ROMFS/px4fmu_common/init.d/airframes/11001_hexa_cox index b36f11ef34..f18cec33dc 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/11001_hexa_cox +++ b/ROMFS/px4fmu_common/init.d/airframes/11001_hexa_cox @@ -21,9 +21,6 @@ # @board bitcraze_crazyflie exclude # -. ${R}etc/init.d/rc.mc_defaults +. ${R}etc/init.d/rc.mc_hex_defaults set MIXER hexa_cox - -# Need to set all 8 channels -set PWM_OUT 12345678 diff --git a/ROMFS/px4fmu_common/init.d/airframes/1100_rc_quad_x_sih.hil b/ROMFS/px4fmu_common/init.d/airframes/1100_rc_quad_x_sih.hil index 9011987384..f8ac39a099 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/1100_rc_quad_x_sih.hil +++ b/ROMFS/px4fmu_common/init.d/airframes/1100_rc_quad_x_sih.hil @@ -13,7 +13,6 @@ . ${R}etc/init.d/rc.mc_defaults set MIXER quad_x -set PWM_OUT 1234 # set SYS_HITL to 2 to start the SIH and avoid sensors startup param set SYS_HITL 2 diff --git a/ROMFS/px4fmu_common/init.d/airframes/12001_octo_cox b/ROMFS/px4fmu_common/init.d/airframes/12001_octo_cox index 5fc70fdfd3..e71ad485b7 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/12001_octo_cox +++ b/ROMFS/px4fmu_common/init.d/airframes/12001_octo_cox @@ -19,8 +19,7 @@ # @board bitcraze_crazyflie exclude # -. ${R}etc/init.d/rc.mc_defaults +. ${R}etc/init.d/rc.mc_octo_defaults +# MAIN set by rc.mc_octo_defaults set MIXER octo_cox - -set PWM_OUT 12345678 diff --git a/ROMFS/px4fmu_common/init.d/airframes/12002_steadidrone_mavrik b/ROMFS/px4fmu_common/init.d/airframes/12002_steadidrone_mavrik index e91e70e8d6..85154fb057 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/12002_steadidrone_mavrik +++ b/ROMFS/px4fmu_common/init.d/airframes/12002_steadidrone_mavrik @@ -20,8 +20,9 @@ # @board bitcraze_crazyflie exclude # -. ${R}etc/init.d/rc.mc_defaults +. ${R}etc/init.d/rc.mc_octo_defaults +set MIXER octo_cox_w param set-default MC_PITCH_P 4 param set-default MC_PITCHRATE_P 0.24 @@ -45,6 +46,3 @@ param set-default MPC_THR_MIN 0.15 param set-default MPC_Z_VEL_MAX_DN 2 param set-default BAT_N_CELLS 4 -set MIXER octo_cox_w - -set PWM_OUT 12345678 diff --git a/ROMFS/px4fmu_common/init.d/airframes/13000_generic_vtol_standard b/ROMFS/px4fmu_common/init.d/airframes/13000_generic_vtol_standard index 6029d176ff..5e1fcf883f 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/13000_generic_vtol_standard +++ b/ROMFS/px4fmu_common/init.d/airframes/13000_generic_vtol_standard @@ -21,18 +21,21 @@ # @board bitcraze_crazyflie exclude # +. ${R}etc/init.d/rc.mc_quad_defaults . ${R}etc/init.d/rc.vtol_defaults - -param set-default PWM_AUX_DIS5 950 -param set-default PWM_MAIN_RATE 400 +set MAV_TYPE 22 param set-default VT_TYPE 2 param set-default VT_MOT_ID 1234 param set-default VT_FW_MOT_OFFID 1234 -set MAV_TYPE 22 -set MIXER quad_x +# MAIN set by rc.mc_quad_defaults + +# AUX set MIXER_AUX vtol_AAERT - -set PWM_OUT 1234 +param set-default PWM_AUX_DIS1 1500 +param set-default PWM_AUX_DIS2 1500 +param set-default PWM_AUX_DIS3 1500 +param set-default PWM_AUX_DIS4 1500 +param set-default PWM_AUX_DIS5 900 # throttle diff --git a/ROMFS/px4fmu_common/init.d/airframes/13001_caipirinha_vtol b/ROMFS/px4fmu_common/init.d/airframes/13001_caipirinha_vtol index 30b8c7111f..cf3b5cafa7 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/13001_caipirinha_vtol +++ b/ROMFS/px4fmu_common/init.d/airframes/13001_caipirinha_vtol @@ -18,8 +18,7 @@ . ${R}etc/init.d/rc.vtol_defaults - -param set-default MAV_TYPE 19 +set MAV_TYPE 19 param set-default MC_ROLL_P 6 param set-default MC_ROLLRATE_P 0.12 @@ -43,8 +42,20 @@ param set-default VT_IDLE_PWM_MC 1080 param set-default VT_ELEV_MC_LOCK 0 param set-default VT_MOT_ID 12 param set-default VT_TYPE 0 -set MAV_TYPE 19 + +# MAIN set MIXER vtol_tailsitter_duo +param set-default PWM_MAIN_MIN1 1100 +param set-default PWM_MAIN_MIN2 1100 -set PWM_OUT 123456 +param set-default PWM_MAIN_MAX1 1900 +param set-default PWM_MAIN_MAX2 1900 + +param set-default PWM_MAIN_RATE1 400 +param set-default PWM_MAIN_RATE2 400 + +param set-default PWM_MAIN_DIS1 900 +param set-default PWM_MAIN_DIS2 900 +param set-default PWM_MAIN_DIS3 1500 # right (starboard) elevon +param set-default PWM_MAIN_DIS4 1500 # left (port) elevon. diff --git a/ROMFS/px4fmu_common/init.d/airframes/13002_firefly6 b/ROMFS/px4fmu_common/init.d/airframes/13002_firefly6 index 8660126b12..4846322c1f 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/13002_firefly6 +++ b/ROMFS/px4fmu_common/init.d/airframes/13002_firefly6 @@ -23,6 +23,7 @@ . ${R}etc/init.d/rc.vtol_defaults +set MAV_TYPE 21 param set-default MC_ROLL_P 7 param set-default MC_ROLLRATE_P 0.19 @@ -40,8 +41,6 @@ param set-default MC_YAWRATE_I 0.02 param set-default MC_YAWRATE_D 0 param set-default MC_YAWRATE_FF 0 -param set-default PWM_MAIN_RATE 400 - param set-default VT_FW_MOT_OFFID 34 param set-default VT_IDLE_PWM_MC 1080 param set-default VT_MOT_ID 123456 @@ -51,9 +50,40 @@ param set-default VT_TILT_TRANS 0.5 param set-default VT_TILT_FW 0.9 param set-default VT_ELEV_MC_LOCK 0 param set-default VT_TYPE 1 -set MAV_TYPE 21 +# MAIN set MIXER firefly6 -set MIXER_AUX firefly6 +param set-default PWM_MAIN_MIN1 1100 +param set-default PWM_MAIN_MIN2 1100 +param set-default PWM_MAIN_MIN3 1100 +param set-default PWM_MAIN_MIN4 1100 +param set-default PWM_MAIN_MIN5 1100 +param set-default PWM_MAIN_MIN6 1100 -set PWM_OUT 12345678 +param set-default PWM_MAIN_MAX1 1900 +param set-default PWM_MAIN_MAX2 1900 +param set-default PWM_MAIN_MAX3 1900 +param set-default PWM_MAIN_MAX4 1900 +param set-default PWM_MAIN_MAX5 1900 +param set-default PWM_MAIN_MAX6 1900 + +param set-default PWM_MAIN_RATE1 400 +param set-default PWM_MAIN_RATE2 400 +param set-default PWM_MAIN_RATE3 400 +param set-default PWM_MAIN_RATE4 400 +param set-default PWM_MAIN_RATE5 400 +param set-default PWM_MAIN_RATE6 400 + +param set-default PWM_MAIN_DIS1 900 +param set-default PWM_MAIN_DIS2 900 +param set-default PWM_MAIN_DIS3 900 +param set-default PWM_MAIN_DIS4 900 +param set-default PWM_MAIN_DIS5 900 +param set-default PWM_MAIN_DIS6 900 + +# AUX +set MIXER_AUX firefly6 +param set-default PWM_MAIN_DIS1 1000 # Tilt mechanism servo mixer +param set-default PWM_MAIN_DIS2 1500 +param set-default PWM_MAIN_DIS3 1500 +param set-default PWM_MAIN_DIS4 2000 # Landing gear diff --git a/ROMFS/px4fmu_common/init.d/airframes/13003_quad_tailsitter b/ROMFS/px4fmu_common/init.d/airframes/13003_quad_tailsitter index ea700ce084..bd8c77656b 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/13003_quad_tailsitter +++ b/ROMFS/px4fmu_common/init.d/airframes/13003_quad_tailsitter @@ -11,18 +11,18 @@ # @board bitcraze_crazyflie exclude # +. ${R}etc/init.d/rc.mc_quad_defaults . ${R}etc/init.d/rc.vtol_defaults - -param set-default PWM_MAIN_MAX 2000 -param set-default PWM_MAIN_RATE 400 - -param set-default VT_MOT_ID 1234 -param set-default VT_IDLE_PWM_MC 1080 -param set-default VT_TYPE 0 -param set-default VT_ELEV_MC_LOCK 1 set MAV_TYPE 20 -set MIXER quad_x_vtol +param set-default VT_MOT_ID 1234 +param set-default VT_IDLE_PWM_MC 1080 +param set-default VT_TYPE 0 +param set-default VT_ELEV_MC_LOCK 1 -set PWM_OUT 1234 +# MAIN +set MIXER quad_x_vtol +# outputs 1-4 set by rc.mc_quad_defaults +param set-default PWM_MAIN_DIS5 1500 # left elevon +param set-default PWM_MAIN_DIS6 1500 # right elevon diff --git a/ROMFS/px4fmu_common/init.d/airframes/13004_quad+_tailsitter b/ROMFS/px4fmu_common/init.d/airframes/13004_quad+_tailsitter index fdf9a3daf8..fce2b3d9af 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/13004_quad+_tailsitter +++ b/ROMFS/px4fmu_common/init.d/airframes/13004_quad+_tailsitter @@ -20,17 +20,19 @@ # @board bitcraze_crazyflie exclude # +. ${R}etc/init.d/rc.mc_quad_defaults . ${R}etc/init.d/rc.vtol_defaults - -param set-default PWM_MAIN_MAX 2000 -param set-default PWM_MAIN_RATE 400 - -param set-default VT_IDLE_PWM_MC 1080 -param set-default VT_TYPE 0 -param set-default VT_ELEV_MC_LOCK 1 set MAV_TYPE 20 -set MIXER quad_+_vtol +param set-default VT_IDLE_PWM_MC 1080 +param set-default VT_TYPE 0 +param set-default VT_ELEV_MC_LOCK 1 -set PWM_OUT 1234 +# MAIN +set MIXER quad_+_vtol +# outputs 1-4 set by rc.mc_quad_defaults +param set-default PWM_MAIN_DIS5 1500 +param set-default PWM_MAIN_DIS6 1500 +param set-default PWM_MAIN_DIS7 1500 +param set-default PWM_MAIN_DIS8 1500 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 03151f1426..0fe584cdab 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/13005_vtol_AAERT_quad +++ b/ROMFS/px4fmu_common/init.d/airframes/13005_vtol_AAERT_quad @@ -21,12 +21,10 @@ # @board bitcraze_crazyflie exclude # +. ${R}etc/init.d/rc.mc_quad_defaults . ${R}etc/init.d/rc.vtol_defaults - -param set-default PWM_AUX_DIS5 950 - -param set-default PWM_MAIN_RATE 400 +set MAV_TYPE 22 param set-default MC_ROLL_P 6 param set-default MC_ROLLRATE_P 0.17 @@ -64,9 +62,14 @@ param set-default VT_MOT_ID 1234 param set-default VT_FW_MOT_OFFID 1234 param set-default VT_IDLE_PWM_MC 1080 param set-default VT_TYPE 2 -set MAV_TYPE 22 -set MIXER quad_x + +# MAIN set by rc.mc_quad_defaults + +# AUX set MIXER_AUX vtol_AAERT - -set PWM_OUT 1234 +param set-default PWM_AUX_DIS1 1500 +param set-default PWM_AUX_DIS2 1500 +param set-default PWM_AUX_DIS3 1500 +param set-default PWM_AUX_DIS4 1500 +param set-default PWM_AUX_DIS5 900 # throttle 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 b50ab35cbe..9d16078cf3 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/13006_vtol_standard_delta +++ b/ROMFS/px4fmu_common/init.d/airframes/13006_vtol_standard_delta @@ -19,8 +19,10 @@ # @board bitcraze_crazyflie exclude # +. ${R}etc/init.d/rc.mc_quad_defaults . ${R}etc/init.d/rc.vtol_defaults +set MAV_TYPE 22 param set-default MC_ROLL_P 6.5 param set-default MC_ROLLRATE_P 0.15 @@ -44,17 +46,17 @@ param set-default MPC_XY_VEL_P_ACC 2 param set-default MPC_ACC_HOR_MAX 2 param set-default MPC_YAWRAUTO_MAX 20 -param set-default PWM_AUX_DIS3 950 -param set-default PWM_MAIN_RATE 400 - param set-default VT_MOT_ID 1234 param set-default VT_FW_MOT_OFFID 1234 param set-default VT_F_TRANS_THR 0.75 param set-default VT_IDLE_PWM_MC 1080 param set-default VT_TYPE 2 -set MAV_TYPE 22 -set MIXER quad_x +# MAIN set by rc.mc_quad_defaults + +# AUX set MIXER_AUX vtol_delta - -set PWM_OUT 1234 +param set-default PWM_AUX_DIS1 1500 +param set-default PWM_AUX_DIS2 1500 +param set-default PWM_AUX_DIS3 900 # throttle +param set-default PWM_AUX_DIS4 900 # throttle reverse diff --git a/ROMFS/px4fmu_common/init.d/airframes/13007_vtol_AAVVT_quad b/ROMFS/px4fmu_common/init.d/airframes/13007_vtol_AAVVT_quad index 62ad1e71a3..825ee63777 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/13007_vtol_AAVVT_quad +++ b/ROMFS/px4fmu_common/init.d/airframes/13007_vtol_AAVVT_quad @@ -11,8 +11,10 @@ # @board bitcraze_crazyflie exclude # +. ${R}etc/init.d/rc.mc_quad_defaults . ${R}etc/init.d/rc.vtol_defaults +set MAV_TYPE 22 param set-default MC_ROLL_P 7 param set-default MC_ROLLRATE_P 0.15 @@ -30,20 +32,20 @@ param set-default MC_YAWRATE_I 0.02 param set-default MC_YAWRATE_D 0 param set-default MC_YAWRATE_FF 0 param set-default MC_YAWRATE_MAX 40 - param set-default MPC_YAWRAUTO_MAX 40 -param set-default PWM_AUX_DIS5 950 -param set-default PWM_MAIN_RATE 400 - param set-default VT_F_TRANS_THR 0.75 param set-default VT_MOT_ID 1234 param set-default VT_FW_MOT_OFFID 1234 param set-default VT_IDLE_PWM_MC 1080 param set-default VT_TYPE 2 -set MAV_TYPE 22 -set MIXER quad_x +# MAIN set by rc.mc_quad_defaults + +# AUX set MIXER_AUX vtol_AAVVT - -set PWM_OUT 1234 +param set-default PWM_AUX_DIS1 1500 +param set-default PWM_AUX_DIS2 1500 +param set-default PWM_AUX_DIS3 1500 +param set-default PWM_AUX_DIS4 1500 +param set-default PWM_AUX_DIS5 900 # throttle diff --git a/ROMFS/px4fmu_common/init.d/airframes/13008_QuadRanger b/ROMFS/px4fmu_common/init.d/airframes/13008_QuadRanger index a04b06f68a..b1976accf8 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/13008_QuadRanger +++ b/ROMFS/px4fmu_common/init.d/airframes/13008_QuadRanger @@ -11,8 +11,10 @@ # @board bitcraze_crazyflie exclude # +. ${R}etc/init.d/rc.mc_quad_defaults . ${R}etc/init.d/rc.vtol_defaults +set MAV_TYPE 22 param set-default FW_THR_CRUISE 65 param set-default FW_PR_P 0.08 @@ -45,11 +47,6 @@ param set-default MPC_TKO_SPEED 1.5 param set-default MPC_LAND_SPEED 0.8 param set-default MPC_YAWRAUTO_MAX 40 -param set-default PWM_AUX_DIS5 950 -param set-default PWM_AUX_REV1 1 -param set-default PWM_AUX_REV2 1 -param set-default PWM_MAIN_RATE 400 - param set-default VT_ARSP_TRANS 15 param set-default VT_ARSP_BLEND 8 param set-default VT_B_TRANS_DUR 4 @@ -58,9 +55,13 @@ param set-default VT_IDLE_PWM_MC 1080 param set-default VT_MOT_ID 1234 param set-default VT_FW_MOT_OFFID 1234 param set-default VT_TYPE 2 -set MAV_TYPE 22 -set MIXER quad_x +# MAIN set by rc.mc_quad_defaults + +# AUX set MIXER_AUX vtol_AAERT - -set PWM_OUT 1234 +param set-default PWM_AUX_DIS1 1500 +param set-default PWM_AUX_DIS2 1500 +param set-default PWM_AUX_DIS3 1500 +param set-default PWM_AUX_DIS4 1500 +param set-default PWM_AUX_DIS5 900 # throttle 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 47f0c98f41..19fc98c5c6 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/13009_vtol_spt_ranger +++ b/ROMFS/px4fmu_common/init.d/airframes/13009_vtol_spt_ranger @@ -11,8 +11,10 @@ # @board bitcraze_crazyflie exclude # +. ${R}etc/init.d/rc.mc_quad_defaults . ${R}etc/init.d/rc.vtol_defaults +set MAV_TYPE 22 param set-default FW_AIRSPD_MAX 22 param set-default FW_AIRSPD_MIN 14 @@ -61,15 +63,6 @@ param set-default MPC_YAWRAUTO_MAX 40 param set-default NAV_ACC_RAD 3 -param set-default PWM_AUX_REV1 1 -param set-default PWM_AUX_REV2 1 -param set-default PWM_AUX_REV3 1 -param set-default PWM_AUX_REV4 1 - -param set-default PWM_AUX_DIS5 950 - -param set-default PWM_MAIN_RATE 400 - param set-default VT_ARSP_TRANS 15 param set-default VT_B_TRANS_DUR 4 param set-default VT_F_TRANS_THR 0.6 @@ -80,9 +73,17 @@ param set-default VT_TRANS_MIN_TM 5 param set-default VT_TRANS_TIMEOUT 30 param set-default VT_TYPE 2 -set MAV_TYPE 22 +# MAIN set by rc.mc_quad_defaults -set MIXER quad_x +# AUX set MIXER_AUX vtol_AAERT +param set-default PWM_AUX_DIS1 1500 +param set-default PWM_AUX_DIS2 1500 +param set-default PWM_AUX_DIS3 1500 +param set-default PWM_AUX_DIS4 1500 +param set-default PWM_AUX_DIS5 900 # throttle -set PWM_OUT 1234 +param set-default PWM_AUX_REV1 1 +param set-default PWM_AUX_REV2 1 +param set-default PWM_AUX_REV3 1 +param set-default PWM_AUX_REV4 1 diff --git a/ROMFS/px4fmu_common/init.d/airframes/13010_claire b/ROMFS/px4fmu_common/init.d/airframes/13010_claire index 5890fd4a67..6ea474361f 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/13010_claire +++ b/ROMFS/px4fmu_common/init.d/airframes/13010_claire @@ -13,14 +13,7 @@ . ${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 -param set-default PWM_AUX_RATE 50 - -param set-default PWM_MAIN_MAX 2000 -param set-default PWM_MAIN_RATE 400 +set MAV_TYPE 21 param set-default VT_MOT_ID 1234 param set-default VT_FW_MOT_OFFID 13 @@ -30,9 +23,32 @@ param set-default VT_TILT_MC 0.08 param set-default VT_TILT_TRANS 0.5 param set-default VT_ELEV_MC_LOCK 0 param set-default VT_TYPE 1 -set MAV_TYPE 21 -set MIXER claire + +# MAIN +set MIXER quad_x +param set-default PWM_MAIN_MIN1 1100 +param set-default PWM_MAIN_MIN2 1100 +param set-default PWM_MAIN_MIN3 1100 +param set-default PWM_MAIN_MIN4 1100 + +param set-default PWM_MAIN_MAX1 1900 +param set-default PWM_MAIN_MAX2 1900 +param set-default PWM_MAIN_MAX3 1900 +param set-default PWM_MAIN_MAX4 1900 + +param set-default PWM_MAIN_RATE1 400 +param set-default PWM_MAIN_RATE2 400 +param set-default PWM_MAIN_RATE3 400 +param set-default PWM_MAIN_RATE4 400 + +param set-default PWM_MAIN_DIS1 900 +param set-default PWM_MAIN_DIS2 900 +param set-default PWM_MAIN_DIS3 900 +param set-default PWM_MAIN_DIS4 900 + +# AUX set MIXER_AUX claire - -set PWM_OUT 1234 +param set-default PWM_MAIN_DIS1 1000 # tilt +param set-default PWM_MAIN_DIS2 1500 # elevon +param set-default PWM_MAIN_DIS3 1500 # elevon diff --git a/ROMFS/px4fmu_common/init.d/airframes/13012_convergence b/ROMFS/px4fmu_common/init.d/airframes/13012_convergence index 8c833c0c28..7aa8881dc7 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/13012_convergence +++ b/ROMFS/px4fmu_common/init.d/airframes/13012_convergence @@ -22,6 +22,7 @@ . ${R}etc/init.d/rc.vtol_defaults +set MAV_TYPE 21 param set-default CBRK_AIRSPD_CHK 162128 @@ -59,8 +60,6 @@ param set-default MPC_LAND_SPEED 1.2 param set-default MPC_TKO_SPEED 2.5 param set-default MPC_Z_VEL_MAX_UP 3 -param set-default PWM_MAIN_RATE 400 - param set-default SENS_BOARD_ROT 8 param set-default VT_B_TRANS_DUR 1 @@ -79,8 +78,26 @@ param set-default VT_TRANS_MIN_TM 1.2 param set-default VT_TRANS_P2_DUR 1.3 param set-default VT_ELEV_MC_LOCK 0 param set-default VT_TYPE 1 -set MAV_TYPE 21 + +# MAIN set MIXER vtol_convergence +param set-default PWM_MAIN_MIN1 1100 +param set-default PWM_MAIN_MIN2 1100 +param set-default PWM_MAIN_MIN3 1100 -set PWM_OUT 1234 +param set-default PWM_MAIN_MAX1 1900 +param set-default PWM_MAIN_MAX2 1900 +param set-default PWM_MAIN_MAX3 1900 + +param set-default PWM_MAIN_RATE1 400 +param set-default PWM_MAIN_RATE2 400 +param set-default PWM_MAIN_RATE3 400 + +param set-default PWM_MAIN_DIS1 900 +param set-default PWM_MAIN_DIS2 900 +param set-default PWM_MAIN_DIS3 900 +param set-default PWM_MAIN_DIS5 2000 # tilt right servo (2000 up) +param set-default PWM_MAIN_DIS6 1000 # tilt left servo (1000 up) +param set-default PWM_MAIN_DIS7 1500 # elevon +param set-default PWM_MAIN_DIS8 1500 # elevon diff --git a/ROMFS/px4fmu_common/init.d/airframes/13013_deltaquad b/ROMFS/px4fmu_common/init.d/airframes/13013_deltaquad index 056a7681cb..edde2cc635 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/13013_deltaquad +++ b/ROMFS/px4fmu_common/init.d/airframes/13013_deltaquad @@ -22,6 +22,7 @@ . ${R}etc/init.d/rc.vtol_defaults +set MAV_TYPE 22 param set-default BAT_CAPACITY 23000 param set-default BAT_N_CELLS 4 @@ -112,15 +113,6 @@ param set-default MPC_YAWRAUTO_MAX 20 param set-default NAV_DLL_ACT 0 param set-default NAV_LOITER_RAD 100 -param set-default PWM_AUX_DISARM 950 - -param set-default PWM_MAIN_DIS5 1500 -param set-default PWM_MAIN_DIS6 1500 -param set-default PWM_MAIN_DIS7 900 -param set-default PWM_MAIN_DIS8 900 - -param set-default PWM_MAIN_RATE 400 - param set-default SENS_BOARD_ROT 18 # TELEM2 config @@ -150,10 +142,34 @@ param set-default VT_TRANS_TIMEOUT 22 param set-default VT_F_TRANS_RAMP 4 param set-default COM_RC_OVERRIDE 0 -set MAV_TYPE 22 + +# MAIN set MIXER deltaquad +param set-default PWM_MAIN_MIN1 1100 +param set-default PWM_MAIN_MIN2 1100 +param set-default PWM_MAIN_MIN3 1100 +param set-default PWM_MAIN_MIN4 1100 + +param set-default PWM_MAIN_MAX1 1900 +param set-default PWM_MAIN_MAX2 1900 +param set-default PWM_MAIN_MAX3 1900 +param set-default PWM_MAIN_MAX4 1900 + +param set-default PWM_MAIN_RATE1 400 +param set-default PWM_MAIN_RATE2 400 +param set-default PWM_MAIN_RATE3 400 +param set-default PWM_MAIN_RATE4 400 + +param set-default PWM_MAIN_DIS1 900 +param set-default PWM_MAIN_DIS2 900 +param set-default PWM_MAIN_DIS3 900 +param set-default PWM_MAIN_DIS4 900 +param set-default PWM_MAIN_DIS5 1500 # left elevon +param set-default PWM_MAIN_DIS6 1500 # right elevon +param set-default PWM_MAIN_DIS7 900 # pusher +param set-default PWM_MAIN_DIS8 900 # reverse thrust + +# AUX set MIXER_AUX pass -set PWM_OUT 1234 -set PWM_AUX_OUT 12345 diff --git a/ROMFS/px4fmu_common/init.d/airframes/13014_vtol_babyshark b/ROMFS/px4fmu_common/init.d/airframes/13014_vtol_babyshark index 3dce88f318..17824e15e7 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/13014_vtol_babyshark +++ b/ROMFS/px4fmu_common/init.d/airframes/13014_vtol_babyshark @@ -22,7 +22,7 @@ . ${R}etc/init.d/rc.vtol_defaults - +set MAV_TYPE 22 param set-default BAT_N_CELLS 6 @@ -105,11 +105,28 @@ param set-default VT_PSHER_RMP_DT 2 param set-default VT_TRANS_MIN_TM 4 param set-default VT_TYPE 2 -set MAV_TYPE 22 - +# MAIN set MIXER babyshark -set MIXER_AUX pass +param set-default PWM_MAIN_MIN5 1100 +param set-default PWM_MAIN_MIN6 1100 +param set-default PWM_MAIN_MIN7 1120 +param set-default PWM_MAIN_MIN8 1100 -# Mark outputs for the alternate rate -# or D-Shot -set PWM_OUT 5678 +param set-default PWM_MAIN_MAX5 1900 +param set-default PWM_MAIN_MAX6 1900 +param set-default PWM_MAIN_MAX7 1900 +param set-default PWM_MAIN_MAX8 1900 + +param set-default PWM_MAIN_RATE5 400 +param set-default PWM_MAIN_RATE6 400 +param set-default PWM_MAIN_RATE7 400 +param set-default PWM_MAIN_RATE8 400 + +param set-default PWM_MAIN_DIS1 1500 +param set-default PWM_MAIN_DIS2 1500 +param set-default PWM_MAIN_DIS3 900 # pusher +param set-default PWM_MAIN_DIS4 1500 +param set-default PWM_MAIN_DIS5 900 +param set-default PWM_MAIN_DIS6 900 +param set-default PWM_MAIN_DIS7 900 +param set-default PWM_MAIN_DIS8 900 diff --git a/ROMFS/px4fmu_common/init.d/airframes/13015_generic_vtol_standard b/ROMFS/px4fmu_common/init.d/airframes/13015_generic_vtol_standard new file mode 100644 index 0000000000..6c48a1ddd6 --- /dev/null +++ b/ROMFS/px4fmu_common/init.d/airframes/13015_generic_vtol_standard @@ -0,0 +1,53 @@ +#!/bin/sh +# +# @name Generic Quadplane VTOL (PWM14) +# +# @type Standard VTOL +# @class VTOL +# +# @maintainer +# +# @output MAIN1 motor 1 +# @output MAIN2 motor 2 +# @output MAIN3 motor 3 +# @output MAIN4 motor 4 +# @output MAIN5 Aileron 1 +# @output MAIN6 Aileron 2 +# @output MAIN7 Elevator +# @output MAIN8 Rudder +# @output MAIN9 Pusher motor +# +# @board px4_fmu-v2 exclude +# @board intel_aerofc-v1 exclude +# @board bitcraze_crazyflie exclude +# + +. ${R}etc/init.d/rc.vtol_defaults + +set MAV_TYPE 22 + +param set-default VT_TYPE 2 +param set-default VT_MOT_ID 1234 +param set-default VT_FW_MOT_OFFID 1234 + +# MAIN +set MIXER quad_x_vtol_AAERT +param set-default PWM_MAIN_MIN1 1100 +param set-default PWM_MAIN_MIN2 1100 +param set-default PWM_MAIN_MIN3 1100 +param set-default PWM_MAIN_MIN4 1100 + +param set-default PWM_MAIN_MAX1 1900 +param set-default PWM_MAIN_MAX2 1900 +param set-default PWM_MAIN_MAX3 1900 +param set-default PWM_MAIN_MAX4 1900 + +param set-default PWM_MAIN_DIS1 900 +param set-default PWM_MAIN_DIS2 900 +param set-default PWM_MAIN_DIS3 900 +param set-default PWM_MAIN_DIS4 900 +param set-default PWM_MAIN_DIS5 1500 +param set-default PWM_MAIN_DIS6 1500 +param set-default PWM_MAIN_DIS7 1500 +param set-default PWM_MAIN_DIS8 1500 +param set-default PWM_MAIN_DIS9 900 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 6daf766136..a1f0c20d98 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/13050_generic_vtol_octo +++ b/ROMFS/px4fmu_common/init.d/airframes/13050_generic_vtol_octo @@ -23,18 +23,21 @@ # @board bitcraze_crazyflie exclude # +. ${R}etc/init.d/rc.mc_octo_defaults . ${R}etc/init.d/rc.vtol_defaults - -param set-default PWM_AUX_DIS5 950 -param set-default PWM_MAIN_RATE 400 +set MAV_TYPE 22 param set-default VT_TYPE 2 param set-default VT_MOT_ID 12345678 param set-default VT_FW_MOT_OFFID 12345678 -set MAV_TYPE 22 -set MIXER octo_cox +# MAIN set by rc.mc_octo_defaults + +# AUX set MIXER_AUX vtol_AAERT - -set PWM_OUT 12345678 +param set-default PWM_AUX_DIS1 1500 +param set-default PWM_AUX_DIS2 1500 +param set-default PWM_AUX_DIS3 1500 +param set-default PWM_AUX_DIS4 1500 +param set-default PWM_AUX_DIS5 900 # throttle 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..5a4dca5ec3 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/13200_generic_vtol_tailsitter +++ b/ROMFS/px4fmu_common/init.d/airframes/13200_generic_vtol_tailsitter @@ -18,13 +18,26 @@ . ${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 param set-default MAV_TYPE 19 + +param set-default PWM_MAIN_MIN1 1100 +param set-default PWM_MAIN_MIN2 1100 + +param set-default PWM_MAIN_MAX1 1900 +param set-default PWM_MAIN_MAX2 1900 + +param set-default PWM_MAIN_RATE1 400 +param set-default PWM_MAIN_RATE2 400 + +param set-default PWM_MAIN_DIS1 900 +param set-default PWM_MAIN_DIS2 900 +param set-default PWM_MAIN_DIS5 1500 # right elevon +param set-default PWM_MAIN_DIS6 1500 # left elevon + + set MAV_TYPE 19 set MIXER vtol_tailsitter_duo - -set PWM_OUT 1234 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 eb02d83734..631a9695f2 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/14001_tri_y_yaw+ +++ b/ROMFS/px4fmu_common/init.d/airframes/14001_tri_y_yaw+ @@ -19,4 +19,22 @@ set MIXER tri_y_yaw+ -set PWM_OUT 1234 +param set-default PWM_MAIN_MIN1 1100 +param set-default PWM_MAIN_MIN2 1100 +param set-default PWM_MAIN_MIN3 1100 +param set-default PWM_MAIN_MIN4 1000 + +param set-default PWM_MAIN_MAX1 1900 +param set-default PWM_MAIN_MAX2 1900 +param set-default PWM_MAIN_MAX3 1900 +param set-default PWM_MAIN_MAX4 2000 + +param set-default PWM_MAIN_RATE1 400 +param set-default PWM_MAIN_RATE2 400 +param set-default PWM_MAIN_RATE3 400 +param set-default PWM_MAIN_RATE4 50 + +param set-default PWM_MAIN_DIS1 900 +param set-default PWM_MAIN_DIS2 900 +param set-default PWM_MAIN_DIS3 900 +param set-default PWM_MAIN_DIS4 1500 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 ad36ed08c0..135942fadb 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/14002_tri_y_yaw- +++ b/ROMFS/px4fmu_common/init.d/airframes/14002_tri_y_yaw- @@ -19,4 +19,22 @@ set MIXER tri_y_yaw- -set PWM_OUT 1234 +param set-default PWM_MAIN_MIN1 1100 +param set-default PWM_MAIN_MIN2 1100 +param set-default PWM_MAIN_MIN3 1100 +param set-default PWM_MAIN_MIN4 1000 + +param set-default PWM_MAIN_MAX1 1900 +param set-default PWM_MAIN_MAX2 1900 +param set-default PWM_MAIN_MAX3 1900 +param set-default PWM_MAIN_MAX4 2000 + +param set-default PWM_MAIN_RATE1 400 +param set-default PWM_MAIN_RATE2 400 +param set-default PWM_MAIN_RATE3 400 +param set-default PWM_MAIN_RATE4 50 + +param set-default PWM_MAIN_DIS1 900 +param set-default PWM_MAIN_DIS2 900 +param set-default PWM_MAIN_DIS3 900 +param set-default PWM_MAIN_DIS4 1500 diff --git a/ROMFS/px4fmu_common/init.d/airframes/15001_coax_heli b/ROMFS/px4fmu_common/init.d/airframes/15001_coax_heli index 3113c8cc41..c3dce2b27e 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/15001_coax_heli +++ b/ROMFS/px4fmu_common/init.d/airframes/15001_coax_heli @@ -17,8 +17,8 @@ # . ${R}etc/init.d/rc.mc_defaults -set MIXER coax +set MIXER coax param set-default MC_ROLL_P 6.5 param set-default MC_ROLLRATE_P 0.17 @@ -38,17 +38,5 @@ param set-default MC_YAWRATE_FF 0 param set-default NAV_ACC_RAD 2 -param set-default PWM_AUX_RATE 50 -param set-default PWM_MAIN_DISARM 900 -param set-default PWM_MAIN_MIN 1075 -param set-default PWM_MAIN_MAX 1950 -param set-default PWM_MAIN_RATE 400 - param set-default RTL_RETURN_ALT 30 param set-default RTL_DESCEND_ALT 10 -# This is the gimbal pass mixer -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 0367a747a8..84924e9262 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/16001_helicopter +++ b/ROMFS/px4fmu_common/init.d/airframes/16001_helicopter @@ -24,11 +24,6 @@ set MAV_TYPE 4 set MIXER blade130 -#set PWM_OUT 1234 - - -param set-default ATT_BIAS_MAX 0 - param set-default CBRK_IO_SAFETY 22027 param set-default MC_ROLL_P 5 @@ -53,5 +48,3 @@ param set-default MC_ACRO_P_MAX 360 param set-default MPC_THR_MIN 0.06 param set-default MPC_MANTHR_MIN 0.06 - -param set-default PWM_MAIN_MIN 1075 diff --git a/ROMFS/px4fmu_common/init.d/airframes/17002_TF-AutoG2 b/ROMFS/px4fmu_common/init.d/airframes/17002_TF-AutoG2 index 048f4bb1be..f72fdc29e6 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/17002_TF-AutoG2 +++ b/ROMFS/px4fmu_common/init.d/airframes/17002_TF-AutoG2 @@ -25,13 +25,9 @@ . ${R}etc/init.d/rc.fw_defaults - param set-default BAT_CAPACITY 2500 param set-default BAT_N_CELLS 3 -param set-default PWM_AUX_RATE 50 -param set-default PWM_MAIN_RATE 50 - param set-default SENS_BOARD_ROT 8 param set-default FW_AIRSPD_MAX 20 @@ -46,5 +42,6 @@ param set-default FW_R_LIM 40 param set-default FW_P_LIM_MAX 25 param set-default FW_P_LIM_MIN -5 param set-default FW_P_RMAX_NEG 20 + set MIXER TF-AutoG2 set MIXER_AUX pass diff --git a/ROMFS/px4fmu_common/init.d/airframes/17003_TF-G2 b/ROMFS/px4fmu_common/init.d/airframes/17003_TF-G2 index 975001bc1a..02f5b854f8 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/17003_TF-G2 +++ b/ROMFS/px4fmu_common/init.d/airframes/17003_TF-G2 @@ -20,13 +20,9 @@ . ${R}etc/init.d/rc.fw_defaults - param set-default BAT_CAPACITY 3300 param set-default BAT_N_CELLS 3 -param set-default PWM_AUX_RATE 50 -param set-default PWM_MAIN_RATE 50 - param set-default SENS_BOARD_ROT 4 param set-default FW_AIRSPD_MAX 20 @@ -41,5 +37,6 @@ param set-default FW_R_LIM 40 param set-default FW_P_LIM_MAX 25 param set-default FW_P_LIM_MIN -5 param set-default FW_P_RMAX_NEG 20 + set MIXER TF-G2 set MIXER_AUX pass diff --git a/ROMFS/px4fmu_common/init.d/airframes/18001_TF-B1 b/ROMFS/px4fmu_common/init.d/airframes/18001_TF-B1 index e2ad00c809..1420da34a1 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 @@ -26,8 +25,8 @@ param set-default GPS_UBX_DYNMODEL 8 param set-default SER_TEL2_BAUD 9600 param set-default SENS_BOARD_ROT 0 - param set MAV_TYPE 8 # MAV_TYPE_FREE_BALLOON +param set-default MAV_TYPE 8 # MAV_TYPE_FREE_BALLOON set MIXER IO_pass set MIXER_AUX pass diff --git a/ROMFS/px4fmu_common/init.d/airframes/2100_standard_plane b/ROMFS/px4fmu_common/init.d/airframes/2100_standard_plane index 8274472503..495b3c2ee8 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/2100_standard_plane +++ b/ROMFS/px4fmu_common/init.d/airframes/2100_standard_plane @@ -23,10 +23,6 @@ . ${R}etc/init.d/rc.fw_defaults -param set-default PWM_AUX_RATE 50 -param set-default PWM_MAIN_RATE 50 - set MIXER AETRFG -# Rate must be set by group (see pwm info). -# Throttle is in the same group as servos. +param set-default PWM_MAIN_DIS3 900 diff --git a/ROMFS/px4fmu_common/init.d/airframes/2105_maja b/ROMFS/px4fmu_common/init.d/airframes/2105_maja index eda8c12d64..76d82eed15 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/2105_maja +++ b/ROMFS/px4fmu_common/init.d/airframes/2105_maja @@ -39,11 +39,7 @@ param set-default FW_WR_IMAX 0.8 param set-default FW_WR_P 1 param set-default FW_W_RMAX 0 -# set disarmed value for the ESC -param set-default PWM_MAIN_DISARM 1000 - - set MIXER AAERTWF # use PWM parameters for throttle channel -set PWM_OUT 5 +param set-default PWM_MAIN_DIS5 1000 diff --git a/ROMFS/px4fmu_common/init.d/airframes/2106_albatross b/ROMFS/px4fmu_common/init.d/airframes/2106_albatross index 7639f0b2d2..44cfe2bf3f 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/2106_albatross +++ b/ROMFS/px4fmu_common/init.d/airframes/2106_albatross @@ -39,11 +39,7 @@ param set-default FW_WR_IMAX 0.8 param set-default FW_WR_P 1 param set-default FW_W_RMAX 0 -# set disarmed value for the ESC -param set-default PWM_MAIN_DISARM 1000 - - set MIXER AAVVTWFF # use PWM parameters for throttle channel -set PWM_OUT 5 +param set-default PWM_MAIN_DIS5 1000 diff --git a/ROMFS/px4fmu_common/init.d/airframes/2200_mini_talon b/ROMFS/px4fmu_common/init.d/airframes/2200_mini_talon index 1f4825048f..d8ac4dadb0 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/2200_mini_talon +++ b/ROMFS/px4fmu_common/init.d/airframes/2200_mini_talon @@ -40,13 +40,10 @@ param set-default FW_WR_IMAX 0.8 param set-default FW_WR_P 1 param set-default FW_W_RMAX 0 -# set disarmed value for the ESC -param set-default PWM_MAIN_DISARM 1000 - # The Mini Talon does not have a wheel and # no flaps. I leave them here because the mixer # computes also wheel and flap controls. set MIXER AAVVTWFF_vtail # use PWM parameters for throttle channel -set PWM_OUT 5 +param set-default PWM_MAIN_DIS5 1000 diff --git a/ROMFS/px4fmu_common/init.d/airframes/24001_dodeca_cox b/ROMFS/px4fmu_common/init.d/airframes/24001_dodeca_cox index 37eddc6d7d..dc8a9e88bd 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/24001_dodeca_cox +++ b/ROMFS/px4fmu_common/init.d/airframes/24001_dodeca_cox @@ -27,23 +27,68 @@ set VEHICLE_TYPE mc - param set-default NAV_ACC_RAD 2 -param set-default PWM_AUX_RATE 400 -param set-default PWM_AUX_DISARM 900 -param set-default PWM_AUX_MIN 1075 -param set-default PWM_AUX_MAX 1950 - -param set-default PWM_MAIN_MIN 1075 -param set-default PWM_MAIN_MAX 1950 -param set-default PWM_MAIN_RATE 400 - param set-default RTL_DESCEND_ALT 10 param set-default RTL_RETURN_ALT 30 + +# MAIN +param set-default PWM_MAIN_MIN1 1100 +param set-default PWM_MAIN_MIN2 1100 +param set-default PWM_MAIN_MIN3 1100 +param set-default PWM_MAIN_MIN4 1100 +param set-default PWM_MAIN_MIN5 1100 +param set-default PWM_MAIN_MIN6 1100 + +param set-default PWM_MAIN_MAX1 1900 +param set-default PWM_MAIN_MAX2 1900 +param set-default PWM_MAIN_MAX3 1900 +param set-default PWM_MAIN_MAX4 1900 +param set-default PWM_MAIN_MAX5 1900 +param set-default PWM_MAIN_MAX6 1900 + +param set-default PWM_MAIN_RATE1 400 +param set-default PWM_MAIN_RATE2 400 +param set-default PWM_MAIN_RATE3 400 +param set-default PWM_MAIN_RATE4 400 +param set-default PWM_MAIN_RATE5 400 +param set-default PWM_MAIN_RATE6 400 + +param set-default PWM_MAIN_DIS1 900 +param set-default PWM_MAIN_DIS2 900 +param set-default PWM_MAIN_DIS3 900 +param set-default PWM_MAIN_DIS4 900 +param set-default PWM_MAIN_DIS5 900 +param set-default PWM_MAIN_DIS6 900 + +# AUX +param set-default PWM_AUX_MIN1 1100 +param set-default PWM_AUX_MIN2 1100 +param set-default PWM_AUX_MIN3 1100 +param set-default PWM_AUX_MIN4 1100 +param set-default PWM_AUX_MIN5 1100 +param set-default PWM_AUX_MIN6 1100 + +param set-default PWM_AUX_MAX1 1900 +param set-default PWM_AUX_MAX2 1900 +param set-default PWM_AUX_MAX3 1900 +param set-default PWM_AUX_MAX4 1900 +param set-default PWM_AUX_MAX5 1900 +param set-default PWM_AUX_MAX6 1900 + +param set-default PWM_AUX_RATE1 400 +param set-default PWM_AUX_RATE2 400 +param set-default PWM_AUX_RATE3 400 +param set-default PWM_AUX_RATE4 400 +param set-default PWM_AUX_RATE5 400 +param set-default PWM_AUX_RATE6 400 + +param set-default PWM_AUX_DIS1 900 +param set-default PWM_AUX_DIS2 900 +param set-default PWM_AUX_DIS3 900 +param set-default PWM_AUX_DIS4 900 +param set-default PWM_AUX_DIS5 900 +param set-default PWM_AUX_DIS6 900 + set MIXER dodeca_top_cox set MIXER_AUX dodeca_bottom_cox - -# Need to set all 8 channels -set PWM_OUT 12345678 -set PWM_AUX_OUT 123456 diff --git a/ROMFS/px4fmu_common/init.d/airframes/2507_cloudship b/ROMFS/px4fmu_common/init.d/airframes/2507_cloudship index a040702c07..76df30eb8a 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/2507_cloudship +++ b/ROMFS/px4fmu_common/init.d/airframes/2507_cloudship @@ -18,6 +18,4 @@ 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/3000_generic_wing b/ROMFS/px4fmu_common/init.d/airframes/3000_generic_wing index 4b5ee877d6..4b2ecb16b4 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/3000_generic_wing +++ b/ROMFS/px4fmu_common/init.d/airframes/3000_generic_wing @@ -21,3 +21,5 @@ . ${R}etc/init.d/rc.fw_defaults set MIXER fw_generic_wing + +param set-default PWM_MAIN_DIS4 1000 diff --git a/ROMFS/px4fmu_common/init.d/airframes/3030_io_camflyer b/ROMFS/px4fmu_common/init.d/airframes/3030_io_camflyer index d902b960eb..78511599d2 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/3030_io_camflyer +++ b/ROMFS/px4fmu_common/init.d/airframes/3030_io_camflyer @@ -9,10 +9,6 @@ # @output MAIN2 right aileron # @output MAIN4 throttle # -# @output AUX1 feed-through of RC AUX1 channel -# @output AUX2 feed-through of RC AUX2 channel -# @output AUX3 feed-through of RC AUX3 channel -# # @maintainer Simon Wilks # # @board px4_fmu-v2 exclude @@ -41,10 +37,8 @@ param set-default FW_RR_FF 0.6 param set-default FW_RR_IMAX 0.2 param set-default FW_RR_P 0.04 -param set-default PWM_MAIN_DISARM 1000 - set MIXER fw_generic_wing # Provide ESC a constant 1000 us pulse while disarmed -set PWM_OUT 4 +param set-default PWM_MAIN_DIS4 1000 diff --git a/ROMFS/px4fmu_common/init.d/airframes/3031_phantom b/ROMFS/px4fmu_common/init.d/airframes/3031_phantom index 0b2a594768..8e04e54190 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/3031_phantom +++ b/ROMFS/px4fmu_common/init.d/airframes/3031_phantom @@ -11,10 +11,6 @@ # @output MAIN2 right aileron # @output MAIN4 throttle # -# @output AUX1 feed-through of RC AUX1 channel -# @output AUX2 feed-through of RC AUX2 channel -# @output AUX3 feed-through of RC AUX3 channel -# # @maintainer Simon Wilks # # @board px4_fmu-v2 exclude @@ -42,8 +38,6 @@ param set-default FW_RR_P 0.08 param set-default FW_R_LIM 50 param set-default FW_R_RMAX 50 -param set-default PWM_MAIN_DISARM 1000 - # Bottom of bay and nominal zero-pitch attitude differ # the payload bay is pitched up about 7 degrees param set-default SENS_BOARD_Y_OFF 7 @@ -51,5 +45,5 @@ param set-default SENS_BOARD_Y_OFF 7 set MIXER phantom -# Provide ESC a constant 1000 us pulse -set PWM_OUT 4 +# Provide ESC a constant 1000 us pulse while disarmed +param set-default PWM_MAIN_DIS4 1000 diff --git a/ROMFS/px4fmu_common/init.d/airframes/3033_wingwing b/ROMFS/px4fmu_common/init.d/airframes/3033_wingwing index ddb33dbfd5..7021f1d5e1 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/3033_wingwing +++ b/ROMFS/px4fmu_common/init.d/airframes/3033_wingwing @@ -41,8 +41,6 @@ param set-default FW_PR_FF 0.35 param set-default FW_RR_FF 0.6 param set-default FW_RR_P 0.04 -param set-default PWM_MAIN_DISARM 1000 - # Configure this as plane. set MAV_TYPE 1 @@ -50,5 +48,5 @@ set MAV_TYPE 1 # Set mixer. set MIXER wingwing -# Provide ESC a constant 1000 us pulse. -set PWM_OUT 4 +# Provide ESC a constant 1000 us pulse while disarmed +param set-default PWM_MAIN_DIS4 1000 diff --git a/ROMFS/px4fmu_common/init.d/airframes/3034_fx79 b/ROMFS/px4fmu_common/init.d/airframes/3034_fx79 index 192b53a6ca..756d80b460 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/3034_fx79 +++ b/ROMFS/px4fmu_common/init.d/airframes/3034_fx79 @@ -27,5 +27,6 @@ param set-default FW_AIRSPD_TRIM 15 param set-default NAV_LOITER_RAD 150 - set MIXER FX79 + +param set-default PWM_MAIN_DIS4 1000 diff --git a/ROMFS/px4fmu_common/init.d/airframes/3035_viper b/ROMFS/px4fmu_common/init.d/airframes/3035_viper index fc8998e1d8..1c8c0be359 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/3035_viper +++ b/ROMFS/px4fmu_common/init.d/airframes/3035_viper @@ -21,3 +21,5 @@ . ${R}etc/init.d/rc.fw_defaults set MIXER Viper + +param set-default PWM_MAIN_DIS4 1000 diff --git a/ROMFS/px4fmu_common/init.d/airframes/3036_pigeon b/ROMFS/px4fmu_common/init.d/airframes/3036_pigeon index 0c8f8fdd44..e51dc6d067 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/3036_pigeon +++ b/ROMFS/px4fmu_common/init.d/airframes/3036_pigeon @@ -43,14 +43,10 @@ param set-default FW_R_LIM 40 param set-default FW_R_RMAX 50 param set-default FW_R_TC 0.3 -param set-default PWM_MAIN_DISARM 1000 +param set-default PWM_MAIN_DIS4 1000 # Bottom of bay and nominal zero-pitch attitude differ # the payload bay is pitched up about 7 degrees param set-default SENS_BOARD_Y_OFF 11.9 - set MIXER phantom - -# Provide ESC a constant 1000 us pulse -set PWM_OUT 4 diff --git a/ROMFS/px4fmu_common/init.d/airframes/3037_parrot_disco_mod b/ROMFS/px4fmu_common/init.d/airframes/3037_parrot_disco_mod index 648b4db5ca..549e73f630 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/3037_parrot_disco_mod +++ b/ROMFS/px4fmu_common/init.d/airframes/3037_parrot_disco_mod @@ -80,10 +80,8 @@ param set-default FW_RR_P 0.05 # Roll Integrator Anti-Windup param set-default FW_RR_IMAX 0.2 -param set-default PWM_MAIN_DISARM 1000 - set MIXER fw_generic_wing.main.mix # Provide ESC a constant 1000 us pulse -set PWM_OUT 4 +param set-default PWM_MAIN_DIS4 1000 diff --git a/ROMFS/px4fmu_common/init.d/airframes/3100_tbs_caipirinha b/ROMFS/px4fmu_common/init.d/airframes/3100_tbs_caipirinha index d0cbc03682..a767296ee0 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 @@ -60,9 +59,7 @@ param set-default NAV_LOITER_RAD 30 param set-default PWM_MAIN_REV1 1 param set-default PWM_MAIN_REV2 1 -param set-default PWM_MAIN_MIN 900 -param set-default PWM_MAIN_MAX 2100 - +# Provide ESC a constant 1000 us pulse +param set-default PWM_MAIN_DIS4 1000 set MIXER caipi -set PWM_OUT 1234 diff --git a/ROMFS/px4fmu_common/init.d/airframes/4001_quad_x b/ROMFS/px4fmu_common/init.d/airframes/4001_quad_x index cfa2ab089b..3e5e493dea 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4001_quad_x +++ b/ROMFS/px4fmu_common/init.d/airframes/4001_quad_x @@ -20,8 +20,4 @@ # @maintainer Lorenz Meier # -. ${R}etc/init.d/rc.mc_defaults - -set MIXER quad_x - -set PWM_OUT 1234 +. ${R}etc/init.d/rc.mc_quad_defaults diff --git a/ROMFS/px4fmu_common/init.d/airframes/4003_qavr5 b/ROMFS/px4fmu_common/init.d/airframes/4003_qavr5 index ef87133ba2..0fed5afc85 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4003_qavr5 +++ b/ROMFS/px4fmu_common/init.d/airframes/4003_qavr5 @@ -11,11 +11,7 @@ # @board bitcraze_crazyflie exclude # -. ${R}etc/init.d/rc.mc_defaults - -set MIXER quad_x -set PWM_OUT 1234 - +. ${R}etc/init.d/rc.mc_quad_defaults param set-default MC_ROLL_P 8 param set-default MC_ROLLRATE_P 0.08 @@ -32,5 +28,3 @@ param set-default MC_YAWRATE_D 0 param set-default MPC_THR_MIN 0.06 param set-default MPC_MANTHR_MIN 0.06 - -param set-default PWM_MAIN_MIN 1075 diff --git a/ROMFS/px4fmu_common/init.d/airframes/4009_qav250 b/ROMFS/px4fmu_common/init.d/airframes/4009_qav250 index 588d735c36..9ce6552e65 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4009_qav250 +++ b/ROMFS/px4fmu_common/init.d/airframes/4009_qav250 @@ -11,11 +11,7 @@ # @board bitcraze_crazyflie exclude # -. ${R}etc/init.d/rc.mc_defaults - -set MIXER quad_x -set PWM_OUT 1234 - +. ${R}etc/init.d/rc.mc_quad_defaults param set-default ATT_BIAS_MAX 0 @@ -35,5 +31,3 @@ param set-default MC_YAWRATE_P 0.3 param set-default MC_YAWRATE_I 0.2 param set-default MC_YAWRATE_D 0 param set-default MPC_THR_MIN 0.06 - -param set-default PWM_MAIN_MIN 1075 diff --git a/ROMFS/px4fmu_common/init.d/airframes/4010_dji_f330 b/ROMFS/px4fmu_common/init.d/airframes/4010_dji_f330 index 2245ac8d19..9e61723c61 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4010_dji_f330 +++ b/ROMFS/px4fmu_common/init.d/airframes/4010_dji_f330 @@ -8,10 +8,7 @@ # @maintainer Lorenz Meier # -. ${R}etc/init.d/rc.mc_defaults - -set MIXER quad_x -set PWM_OUT 1234 +. ${R}etc/init.d/rc.mc_quad_defaults param set-default MC_ROLL_P 7 param set-default MC_ROLLRATE_P 0.15 @@ -25,6 +22,3 @@ param set-default MC_YAW_P 2.8 param set-default MC_YAWRATE_P 0.2 param set-default MC_YAWRATE_I 0.1 param set-default MC_YAWRATE_D 0 - -# DJI ESCs do not support calibration and need a higher min -param set-default PWM_MAIN_MIN 1230 diff --git a/ROMFS/px4fmu_common/init.d/airframes/4011_dji_f450 b/ROMFS/px4fmu_common/init.d/airframes/4011_dji_f450 index 9aa4c79eb2..9208032107 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4011_dji_f450 +++ b/ROMFS/px4fmu_common/init.d/airframes/4011_dji_f450 @@ -8,10 +8,7 @@ # @maintainer Lorenz Meier # -. ${R}etc/init.d/rc.mc_defaults - -set MIXER quad_x -set PWM_OUT 1234 +. ${R}etc/init.d/rc.mc_quad_defaults param set-default MC_ROLL_P 7 param set-default MC_ROLLRATE_P 0.15 @@ -25,6 +22,3 @@ param set-default MC_YAW_P 2.8 param set-default MC_YAWRATE_P 0.3 param set-default MC_YAWRATE_I 0.1 param set-default MC_YAWRATE_D 0 - -# DJI ESCs do not support calibration and need a higher min -param set-default PWM_MAIN_MIN 1230 diff --git a/ROMFS/px4fmu_common/init.d/airframes/4014_s500 b/ROMFS/px4fmu_common/init.d/airframes/4014_s500 index 72629b75e6..78513a7048 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4014_s500 +++ b/ROMFS/px4fmu_common/init.d/airframes/4014_s500 @@ -11,11 +11,7 @@ # @board bitcraze_crazyflie exclude # -. ${R}etc/init.d/rc.mc_defaults - -set MIXER quad_x -set PWM_OUT 1234 - +. ${R}etc/init.d/rc.mc_quad_defaults param set-default MC_ROLLRATE_P 0.18 param set-default MC_PITCHRATE_P 0.18 diff --git a/ROMFS/px4fmu_common/init.d/airframes/4015_holybro_s500 b/ROMFS/px4fmu_common/init.d/airframes/4015_holybro_s500 index 62d2fe9c98..744f35d4f7 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4015_holybro_s500 +++ b/ROMFS/px4fmu_common/init.d/airframes/4015_holybro_s500 @@ -11,14 +11,7 @@ # @board bitcraze_crazyflie exclude # -. ${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 IMU_DGYRO_CUTOFF 30 +. ${R}etc/init.d/rc.mc_quad_defaults param set-default MC_ROLLRATE_P 0.14 param set-default MC_PITCHRATE_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 da92a11043..e633374eaa 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4016_holybro_px4vision +++ b/ROMFS/px4fmu_common/init.d/airframes/4016_holybro_px4vision @@ -14,11 +14,7 @@ # @board bitcraze_crazyflie exclude # -. ${R}etc/init.d/rc.mc_defaults - -set MIXER quad_x -set PWM_OUT 1234 - +. ${R}etc/init.d/rc.mc_quad_defaults # System parameters # use FMU motor outputs for less delay in the rate control loop @@ -102,12 +98,11 @@ param set-default MPC_LAND_ALT2 1 # Navigator Parameters param set-default NAV_ACC_RAD 2 -# PWM and RC Parameters -param set-default PWM_MAIN_MAX 1950 -param set-default PWM_MAIN_MIN 1075 - # use oneshot motor output protocol -param set-default PWM_MAIN_RATE 0 +param set-default PWM_MAIN_RATE1 0 +param set-default PWM_MAIN_RATE2 0 +param set-default PWM_MAIN_RATE3 0 +param set-default PWM_MAIN_RATE4 0 # RTL Parameters param set-default RTL_DESCEND_ALT 5 diff --git a/ROMFS/px4fmu_common/init.d/airframes/4017_nxp_hovergames b/ROMFS/px4fmu_common/init.d/airframes/4017_nxp_hovergames index d28edc165e..62c873c77e 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4017_nxp_hovergames +++ b/ROMFS/px4fmu_common/init.d/airframes/4017_nxp_hovergames @@ -16,10 +16,7 @@ # @maintainer Iain Galloway # -. ${R}etc/init.d/rc.mc_defaults - -set MIXER quad_x -set PWM_OUT 1234 +. ${R}etc/init.d/rc.mc_quad_defaults param set-default IMU_GYRO_CUTOFF 40 param set-default IMU_DGYRO_CUTOFF 20 diff --git a/ROMFS/px4fmu_common/init.d/airframes/4018_s500_ctrlalloc b/ROMFS/px4fmu_common/init.d/airframes/4018_s500_ctrlalloc index 99dbec4609..925937315c 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4018_s500_ctrlalloc +++ b/ROMFS/px4fmu_common/init.d/airframes/4018_s500_ctrlalloc @@ -10,7 +10,7 @@ # @board px4_fmu-v2 exclude # -. ${R}etc/init.d/rc.mc_defaults +. ${R}etc/init.d/rc.mc_quad_defaults . ${R}etc/init.d/rc.ctrlalloc @@ -50,7 +50,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/4020_hk_micro_pcb b/ROMFS/px4fmu_common/init.d/airframes/4020_hk_micro_pcb index a708e32d4d..cfd8238542 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4020_hk_micro_pcb +++ b/ROMFS/px4fmu_common/init.d/airframes/4020_hk_micro_pcb @@ -16,11 +16,7 @@ # @board bitcraze_crazyflie exclude # -. ${R}etc/init.d/rc.mc_defaults - -set MIXER quad_x -set PWM_OUT 1234 - +. ${R}etc/init.d/rc.mc_quad_defaults param set-default MC_ROLL_P 7 param set-default MC_ROLLRATE_P 0.1 @@ -34,5 +30,3 @@ param set-default MC_YAW_P 2.8 param set-default MC_YAWRATE_P 0.2 param set-default MC_YAWRATE_I 0.1 param set-default MC_YAWRATE_D 0 - -param set-default PWM_MAIN_MIN 1200 diff --git a/ROMFS/px4fmu_common/init.d/airframes/4030_3dr_solo b/ROMFS/px4fmu_common/init.d/airframes/4030_3dr_solo index 96f78e8e1a..d5e7dcc2a9 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4030_3dr_solo +++ b/ROMFS/px4fmu_common/init.d/airframes/4030_3dr_solo @@ -16,15 +16,14 @@ # @board bitcraze_crazyflie exclude # -. ${R}etc/init.d/rc.mc_defaults - +. ${R}etc/init.d/rc.mc_quad_defaults # tuning param set-default MC_PITCHRATE_P 0.11 param set-default MC_ROLLRATE_P 0.11 param set-default MPC_MANTHR_MIN 0.08 param set-default MPC_XY_VEL_MAX 3 -param set-default MPC_Z_VEL_MAX_DN 2 +param set-default MPC_Z_VEL_MAX_DN 2 # takeoff, land and RTL settings param set-default MIS_TAKEOFF_ALT 4 @@ -84,7 +83,3 @@ 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 405627f40a..e8953d6684 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4031_3dr_quad +++ b/ROMFS/px4fmu_common/init.d/airframes/4031_3dr_quad @@ -11,11 +11,7 @@ # @board bitcraze_crazyflie exclude # -. ${R}etc/init.d/rc.mc_defaults - -set MIXER quad_x -set PWM_OUT 1234 - +. ${R}etc/init.d/rc.mc_quad_defaults param set-default MC_ROLL_P 6.5 param set-default MC_ROLLRATE_P 0.14 diff --git a/ROMFS/px4fmu_common/init.d/airframes/4040_reaper b/ROMFS/px4fmu_common/init.d/airframes/4040_reaper index 9d3229bd07..baa2fac5cc 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4040_reaper +++ b/ROMFS/px4fmu_common/init.d/airframes/4040_reaper @@ -18,8 +18,9 @@ # @board bitcraze_crazyflie exclude # -. ${R}etc/init.d/rc.mc_defaults +. ${R}etc/init.d/rc.mc_quad_defaults +set MIXER quad_h param set-default MC_ROLL_P 6.5 param set-default MC_ROLLRATE_P 0.14 @@ -33,19 +34,5 @@ param set-default MC_YAW_P 4 param set-default NAV_ACC_RAD 2 -param set-default PWM_AUX_DISARM 950 -param set-default PWM_AUX_RATE 50 -param set-default PWM_MAIN_MIN 1100 -param set-default PWM_MAIN_MAX 1900 -param set-default PWM_MAIN_RATE 50 - param set-default RTL_RETURN_ALT 30 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 beb21c2937..655c37d850 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4041_beta75x +++ b/ROMFS/px4fmu_common/init.d/airframes/4041_beta75x @@ -23,6 +23,8 @@ . ${R}etc/init.d/rc.mc_defaults +# The Whoop uses reversed props +set MIXER quad_h param set-default CBRK_SUPPLY_CHK 894281 param set-default CBRK_USB_CHK 197848 @@ -55,7 +57,3 @@ param set-default SYS_HAS_BARO 0 param set-default SYS_HAS_MAG 0 param set-default BAT_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 0837d6f783..d6e6f32e8b 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4050_generic_250 +++ b/ROMFS/px4fmu_common/init.d/airframes/4050_generic_250 @@ -10,11 +10,7 @@ # @board bitcraze_crazyflie exclude # -. ${R}etc/init.d/rc.mc_defaults - -set MIXER quad_x -set PWM_OUT 1234 - +. ${R}etc/init.d/rc.mc_quad_defaults param set-default MC_ROLL_P 8 param set-default MC_ROLLRATE_P 0.08 @@ -39,10 +35,6 @@ param set-default MPC_MAN_TILT_MAX 60 # use thrust curve factor (instead of TPA) param set-default THR_MDL_FAC 0.3 -param set-default PWM_MAIN_MIN 1075 -# enable one-shot -param set-default PWM_MAIN_RATE 0 - # enable high-rate logging profile (helps with tuning) param set-default SDLOG_PROFILE 19 diff --git a/ROMFS/px4fmu_common/init.d/airframes/4051_s250aq b/ROMFS/px4fmu_common/init.d/airframes/4051_s250aq index 40230bb59b..387c3d14b4 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4051_s250aq +++ b/ROMFS/px4fmu_common/init.d/airframes/4051_s250aq @@ -20,14 +20,11 @@ # @board bitcraze_crazyflie exclude # -. ${R}etc/init.d/rc.mc_defaults +. ${R}etc/init.d/rc.mc_quad_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 @@ -52,5 +49,3 @@ param set-default MC_ACRO_P_MAX 360 param set-default MPC_THR_MIN 0.06 param set-default MPC_MANTHR_MIN 0.06 - -param set-default PWM_MAIN_MIN 1075 diff --git a/ROMFS/px4fmu_common/init.d/airframes/4052_holybro_qav250 b/ROMFS/px4fmu_common/init.d/airframes/4052_holybro_qav250 index df5fa21481..32fe94cd1f 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4052_holybro_qav250 +++ b/ROMFS/px4fmu_common/init.d/airframes/4052_holybro_qav250 @@ -13,11 +13,7 @@ # @board bitcraze_crazyflie exclude # -. ${R}etc/init.d/rc.mc_defaults - -set MIXER quad_x -set PWM_OUT 1234 - +. ${R}etc/init.d/rc.mc_quad_defaults # The set does not include a battery, but most people will probably use 4S param set-default BAT_N_CELLS 4 @@ -48,8 +44,4 @@ param set-default MPC_THR_HOVER 0.25 param set-default MPC_THR_MIN 0.05 param set-default MPC_Z_VEL_I_ACC 1.7 -param set-default PWM_MAIN_MAX 1950 -param set-default PWM_MAIN_MIN 1050 - -param set-default PWM_MAIN_RATE 0 param set-default THR_MDL_FAC 0.3 diff --git a/ROMFS/px4fmu_common/init.d/airframes/4053_holybro_kopis2 b/ROMFS/px4fmu_common/init.d/airframes/4053_holybro_kopis2 index 41a287c4c3..729fb5285d 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4053_holybro_kopis2 +++ b/ROMFS/px4fmu_common/init.d/airframes/4053_holybro_kopis2 @@ -11,11 +11,7 @@ # @board bitcraze_crazyflie exclude # -. ${R}etc/init.d/rc.mc_defaults - -set MIXER quad_x -set PWM_OUT 1234 - +. ${R}etc/init.d/rc.mc_quad_defaults param set-default BAT_N_CELLS 4 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 7ea158a44a..b61d2bbb3f 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4060_dji_matrice_100 +++ b/ROMFS/px4fmu_common/init.d/airframes/4060_dji_matrice_100 @@ -11,11 +11,7 @@ # @board bitcraze_crazyflie exclude # -. ${R}etc/init.d/rc.mc_defaults - -set MIXER quad_x -set PWM_OUT 1234 - +. ${R}etc/init.d/rc.mc_quad_defaults param set-default BAT_N_CELLS 6 @@ -30,5 +26,3 @@ param set-default MC_PITCHRATE_D 0.001 param set-default MC_YAWRATE_P 0.2 param set-default MC_YAWRATE_I 0 param set-default MC_YAWRATE_D 0 - -param set-default PWM_MAIN_MIN 1200 diff --git a/ROMFS/px4fmu_common/init.d/airframes/4071_ifo b/ROMFS/px4fmu_common/init.d/airframes/4071_ifo index eb3e0a680f..4792b8c24a 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4071_ifo +++ b/ROMFS/px4fmu_common/init.d/airframes/4071_ifo @@ -21,10 +21,7 @@ # @board cuav_x7pro exclude # -set VEHICLE_TYPE mc -set MIXER quad_x -set PWM_OUT 1234 - +. ${R}etc/init.d/rc.mc_quad_defaults # Attitude & rate gains #param set MC_ROLL_P 7 @@ -64,11 +61,11 @@ param set-default IMU_GYRO_CUTOFF 100 #param set THR_MDL_FAC 0.25 # System -param set-default PWM_MAIN_MAX 1950 -param set-default PWM_MAIN_MIN 1100 -param set-default PWM_MAIN_RATE 0 +param set-default PWM_MAIN_RATE1 0 +param set-default PWM_MAIN_RATE2 0 +param set-default PWM_MAIN_RATE3 0 +param set-default PWM_MAIN_RATE4 0 -#param set SYS_FMU_TASK 1 param set-default SENS_BOARD_ROT 10 # EKF2 diff --git a/ROMFS/px4fmu_common/init.d/airframes/4072_draco b/ROMFS/px4fmu_common/init.d/airframes/4072_draco index 18afd3735f..692027828f 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4072_draco +++ b/ROMFS/px4fmu_common/init.d/airframes/4072_draco @@ -20,11 +20,7 @@ # @board bitcraze_crazyflie exclude # -. ${R}etc/init.d/rc.mc_defaults - -set MIXER quad_x -set PWM_OUT 1234 - +. ${R}etc/init.d/rc.mc_quad_defaults # use the Q attitude estimator, it works w/o mag or GPS. param set-default SYS_MC_EST_GROUP 3 @@ -65,11 +61,16 @@ param set-default MPC_THR_HOVER 0.25 param set-default THR_MDL_FAC 0.3 # System -param set-default PWM_MAIN_MAX 1950 -param set-default PWM_MAIN_MIN 1180 +param set-default PWM_MAIN_MIN1 1180 +param set-default PWM_MAIN_MIN2 1180 +param set-default PWM_MAIN_MIN3 1180 +param set-default PWM_MAIN_MIN4 1180 # enable one-shot -param set-default PWM_MAIN_RATE 0 +param set-default PWM_MAIN_RATE1 0 +param set-default PWM_MAIN_RATE2 0 +param set-default PWM_MAIN_RATE3 0 +param set-default PWM_MAIN_RATE4 0 param set-default SENS_BOARD_ROT 2 diff --git a/ROMFS/px4fmu_common/init.d/airframes/4073_ifo-s b/ROMFS/px4fmu_common/init.d/airframes/4073_ifo-s index 3d9a7c34d4..477557013b 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4073_ifo-s +++ b/ROMFS/px4fmu_common/init.d/airframes/4073_ifo-s @@ -21,10 +21,7 @@ # @maintainer Hyon Lim # -set VEHICLE_TYPE mc -set MIXER quad_x -set PWM_OUT 1234 - +. ${R}etc/init.d/rc.mc_quad_defaults # Attitude & rate gains #param set MC_ROLL_P 7 @@ -60,11 +57,6 @@ param set-default IMU_GYRO_CUTOFF 100 # Thrust curve (avoids the need for TPA) #param set THR_MDL_FAC 0.25 -# Obsolete -#param set PWM_MAIN_MAX 1950 -#param set PWM_MAIN_MIN 1100 -#param set PWM_MAIN_RATE 0 - # Sensors param set-default SENS_BOARD_ROT 10 # Yaw 180 diff --git a/ROMFS/px4fmu_common/init.d/airframes/4080_zmr250 b/ROMFS/px4fmu_common/init.d/airframes/4080_zmr250 index 9576fd24be..9f3555c827 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4080_zmr250 +++ b/ROMFS/px4fmu_common/init.d/airframes/4080_zmr250 @@ -11,11 +11,7 @@ # @board bitcraze_crazyflie exclude # -. ${R}etc/init.d/rc.mc_defaults - -set MIXER quad_x -set PWM_OUT 1234 - +. ${R}etc/init.d/rc.mc_quad_defaults param set-default CBRK_IO_SAFETY 22027 @@ -37,9 +33,3 @@ param set-default MC_YAWRATE_D 0 param set-default MC_ACRO_R_MAX 1000 param set-default MC_ACRO_P_MAX 1000 param set-default MC_ACRO_Y_MAX 1000 - -# param set NAV_RCL_ACT 6 # Lockdown - -param set-default PWM_MAIN_MIN 1075 -param set-default PWM_MAIN_RATE 400 -param set-default PWM_MAIN_DISARM 900 diff --git a/ROMFS/px4fmu_common/init.d/airframes/4090_nanomind b/ROMFS/px4fmu_common/init.d/airframes/4090_nanomind index a51335b8fa..f5f559f608 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4090_nanomind +++ b/ROMFS/px4fmu_common/init.d/airframes/4090_nanomind @@ -18,8 +18,6 @@ . ${R}etc/init.d/rc.mc_defaults set MIXER quad_x -set PWM_OUT 1234 - param set-default BAT_N_CELLS 1 @@ -36,6 +34,17 @@ param set-default MC_YAWRATE_P 0.2 param set-default MC_YAWRATE_I 0.1 param set-default MC_YAWRATE_D 0 -param set-default PWM_MAIN_DISARM 0 -param set-default PWM_MAIN_MIN 500 -param set-default PWM_MAIN_MAX 2200 +param set-default PWM_MAIN_DIS1 0 +param set-default PWM_MAIN_DIS2 0 +param set-default PWM_MAIN_DIS3 0 +param set-default PWM_MAIN_DIS4 0 + +param set-default PWM_MAIN_MIN1 500 +param set-default PWM_MAIN_MIN2 500 +param set-default PWM_MAIN_MIN3 500 +param set-default PWM_MAIN_MIN4 500 + +param set-default PWM_MAIN_MAX1 2200 +param set-default PWM_MAIN_MAX2 2200 +param set-default PWM_MAIN_MAX3 2200 +param set-default PWM_MAIN_MAX4 2200 diff --git a/ROMFS/px4fmu_common/init.d/airframes/4100_tiltquadrotor b/ROMFS/px4fmu_common/init.d/airframes/4100_tiltquadrotor index 3fd3f11d74..60c3ea7e28 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4100_tiltquadrotor +++ b/ROMFS/px4fmu_common/init.d/airframes/4100_tiltquadrotor @@ -27,12 +27,9 @@ #Parameters here: param set LED_RGB_MAXBRT 8 - # Configure this as Quadrotor # set MAV_TYPE 14 # 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 index 117d4037aa..1b1b217eb3 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4250_teal +++ b/ROMFS/px4fmu_common/init.d/airframes/4250_teal @@ -20,16 +20,7 @@ # @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* +. ${R}etc/init.d/rc.mc_quad_defaults # battery param set-default BAT_CAPACITY 2750 @@ -44,10 +35,6 @@ param set-default BAT_V_DIV 11.1625 param set-default BAT_V_EMPTY 3.65 param set-default BAT_V_OFFS_CURR -0.0045 -# sensor calibration -param set-default CAL_MAG_SIDES 63 -param set-default SENS_BOARD_ROT 0 - # circuit breakers param set-default CBRK_IO_SAFETY 22027 param set-default CBRK_USB_CHK 197848 @@ -169,11 +156,21 @@ param set-default NAV_ACC_RAD 2.5 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 +param set-default PWM_MAIN_MIN1 1075 +param set-default PWM_MAIN_MIN2 1075 +param set-default PWM_MAIN_MIN3 1075 +param set-default PWM_MAIN_MIN4 1075 + +param set-default PWM_MAIN_MAX1 1850 +param set-default PWM_MAIN_MAX2 1850 +param set-default PWM_MAIN_MAX3 1850 +param set-default PWM_MAIN_MAX4 1850 + # Oneshot125 -param set-default PWM_MAIN_RATE 0 +param set-default PWM_MAIN_RATE1 0 +param set-default PWM_MAIN_RATE2 0 +param set-default PWM_MAIN_RATE3 0 +param set-default PWM_MAIN_RATE4 0 # rtl param set-default RTL_DESCEND_ALT 5 diff --git a/ROMFS/px4fmu_common/init.d/airframes/4500_clover4 b/ROMFS/px4fmu_common/init.d/airframes/4500_clover4 index 91a5ef23f0..c8d6b25e9d 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4500_clover4 +++ b/ROMFS/px4fmu_common/init.d/airframes/4500_clover4 @@ -11,11 +11,7 @@ # @board bitcraze_crazyflie exclude # -. ${R}etc/init.d/rc.mc_defaults - -set MIXER quad_x -set PWM_OUT 1234 - +. ${R}etc/init.d/rc.mc_quad_defaults param set-default MC_PITCHRATE_P 0.087 param set-default MC_PITCHRATE_I 0.037 @@ -25,6 +21,7 @@ param set-default MC_ROLLRATE_P 0.087 param set-default MC_ROLLRATE_I 0.037 param set-default MC_ROLLRATE_D 0.0044 param set-default MC_ROLL_P 8.5 + param set-default MPC_XY_VEL_P_ACC 2.2 param set-default MPC_XY_VEL_D_ACC 0.26 param set-default MPC_XY_P 1.1 diff --git a/ROMFS/px4fmu_common/init.d/airframes/4900_crazyflie b/ROMFS/px4fmu_common/init.d/airframes/4900_crazyflie index da3c4bfac0..42c565b49c 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 BAT_N_CELLS 1 param set-default BAT_CAPACITY 240 @@ -58,21 +57,31 @@ param set-default MPC_MAX_FLOW_HGT 3 param set-default NAV_RCL_ACT 3 -param set-default PWM_MAIN_DISARM 0 -param set-default PWM_MAIN_MIN 0 -param set-default PWM_MAIN_MAX 255 +param set-default PWM_MAIN_MIN1 0 +param set-default PWM_MAIN_MIN2 0 +param set-default PWM_MAIN_MIN3 0 +param set-default PWM_MAIN_MIN4 0 + +param set-default PWM_MAIN_MAX1 255 +param set-default PWM_MAIN_MAX2 255 +param set-default PWM_MAIN_MAX3 255 +param set-default PWM_MAIN_MAX4 255 # Run the motors at 328.125 kHz (recommended) -param set-default PWM_MAIN_RATE 3921 +param set-default PWM_MAIN_RATE1 3921 +param set-default PWM_MAIN_RATE2 3921 +param set-default PWM_MAIN_RATE3 3921 +param set-default PWM_MAIN_RATE4 3921 + +param set-default PWM_MAIN_DIS1 0 +param set-default PWM_MAIN_DIS2 0 +param set-default PWM_MAIN_DIS3 0 +param set-default PWM_MAIN_DIS4 0 param set-default SDLOG_PROFILE 1 param set-default SENS_FLOW_MINRNG 0.05 -set PWM_MAIN_DISARM none -set PWM_MAIN_MAX none -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 67fb4406ce..23893dcc5b 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 @@ -59,21 +58,30 @@ param set-default MPC_MAX_FLOW_HGT 3 param set-default NAV_RCL_ACT 3 -param set-default PWM_MAIN_DISARM 0 -param set-default PWM_MAIN_MIN 20 -param set-default PWM_MAIN_MAX 255 +param set-default PWM_MAIN_MIN1 0 +param set-default PWM_MAIN_MIN2 0 +param set-default PWM_MAIN_MIN3 0 +param set-default PWM_MAIN_MIN4 0 + +param set-default PWM_MAIN_MAX1 255 +param set-default PWM_MAIN_MAX2 255 +param set-default PWM_MAIN_MAX3 255 +param set-default PWM_MAIN_MAX4 255 # Run the motors at 328.125 kHz (recommended) -param set-default PWM_MAIN_RATE 3921 +param set-default PWM_MAIN_RATE1 3921 +param set-default PWM_MAIN_RATE2 3921 +param set-default PWM_MAIN_RATE3 3921 +param set-default PWM_MAIN_RATE4 3921 + +param set-default PWM_MAIN_DIS1 0 +param set-default PWM_MAIN_DIS2 0 +param set-default PWM_MAIN_DIS3 0 +param set-default PWM_MAIN_DIS4 0 param set-default SDLOG_PROFILE 1 param set-default SENS_FLOW_MINRNG 0.05 - -set PWM_MAIN_DISARM none -set PWM_MAIN_MAX none -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/50000_generic_ground_vehicle b/ROMFS/px4fmu_common/init.d/airframes/50000_generic_ground_vehicle index 41242a98c5..cf06e4ca48 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/50000_generic_ground_vehicle +++ b/ROMFS/px4fmu_common/init.d/airframes/50000_generic_ground_vehicle @@ -15,7 +15,6 @@ . ${R}etc/init.d/rc.rover_defaults - param set-default BAT_N_CELLS 2 param set-default EKF2_ANGERR_INIT 0.01 @@ -45,13 +44,10 @@ param set-default MIS_TAKEOFF_ALT 0.01 param set-default NAV_ACC_RAD 0.5 # Provide ESC a constant 1500 us pulse -param set-default PWM_MAIN_DISARM 1500 -param set-default PWM_MAIN_MAX 2000 -param set-default PWM_MAIN_MIN 1000 +param set-default PWM_MAIN_DIS3 1500 + # Configure this as rover set MAV_TYPE 10 # Set mixer set MIXER rover_generic - -set PWM_MAIN_REV2 1 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 5652765a67..76ae3a087d 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 BAT_N_CELLS 4 param set-default EKF2_GBIAS_INIT 0.01 @@ -57,11 +56,8 @@ param set-default NAV_ACC_RAD 0.5 # Provide ESC a constant 1500 us pulse, which corresponds to # idle on the Roboclaw motor controller on the Aion R1 -param set-default PWM_MAIN_DISARM 1500 param set-default PWM_MAIN_DIS0 1500 param set-default PWM_MAIN_DIS1 1500 -param set-default PWM_MAIN_MAX 2000 -param set-default PWM_MAIN_MIN 1000 # Enable Airspeed check circuit breaker because Rovers will have no airspeed sensor param set-default CBRK_AIRSPD_CHK 162128 @@ -83,5 +79,3 @@ set MAV_TYPE 10 # Set mixer set MIXER generic_diff_rover - -set PWM_MAIN_REV2 1 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 fd6f195605..bdc34f3bed 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 BAT_N_CELLS 2 param set-default EKF2_GBIAS_INIT 0.01 @@ -53,13 +52,12 @@ param set-default MIS_TAKEOFF_ALT 0.01 param set-default NAV_ACC_RAD 0.5 # Provide ESC a constant 1500 us pulse to idle -param set-default PWM_MAIN_DISARM 1500 param set-default PWM_MAIN_DIS3 1485 param set-default PWM_MAIN_DIS4 1485 + param set-default PWM_MAIN_FAIL3 1485 param set-default PWM_MAIN_FAIL4 1485 -param set-default PWM_MAIN_MAX 2000 -param set-default PWM_MAIN_MIN 1000 + param set-default PWM_MAIN_MIN3 970 param set-default PWM_MAIN_MIN4 970 @@ -71,5 +69,3 @@ set MAV_TYPE 10 # Set mixer set MIXER rover_diff_and_servo - -set PWM_MAIN_REV2 1 diff --git a/ROMFS/px4fmu_common/init.d/airframes/5001_quad_+ b/ROMFS/px4fmu_common/init.d/airframes/5001_quad_+ index 5e5df33a4c..240ab49fd6 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/5001_quad_+ +++ b/ROMFS/px4fmu_common/init.d/airframes/5001_quad_+ @@ -22,8 +22,6 @@ # @board bitcraze_crazyflie exclude # -. ${R}etc/init.d/rc.mc_defaults +. ${R}etc/init.d/rc.mc_quad_defaults set MIXER quad_+ - -set PWM_OUT 1234 diff --git a/ROMFS/px4fmu_common/init.d/airframes/60000_uuv_generic b/ROMFS/px4fmu_common/init.d/airframes/60000_uuv_generic index 705d185a6a..9d7141d068 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/60000_uuv_generic +++ b/ROMFS/px4fmu_common/init.d/airframes/60000_uuv_generic @@ -13,7 +13,6 @@ . ${R}etc/init.d/rc.uuv_defaults - #Set data link loss failsafe mode (0: disabled) param set-default NAV_DLL_ACT 0 @@ -22,6 +21,5 @@ param set-default CBRK_AIRSPD_CHK 162128 #param set CBRK_GPSFAIL 240024 set MAV_TYPE 12 -param set MAV_TYPE ${MAV_TYPE} set MIXER uuv_x diff --git a/ROMFS/px4fmu_common/init.d/airframes/60001_uuv_hippocampus b/ROMFS/px4fmu_common/init.d/airframes/60001_uuv_hippocampus index 360d700fd6..aaf1e5134a 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/60001_uuv_hippocampus +++ b/ROMFS/px4fmu_common/init.d/airframes/60001_uuv_hippocampus @@ -13,7 +13,6 @@ . ${R}etc/init.d/rc.uuv_defaults - #Set data link loss failsafe mode (0: disabled) param set-default NAV_DLL_ACT 0 @@ -22,6 +21,5 @@ param set-default CBRK_AIRSPD_CHK 162128 #param set CBRK_GPSFAIL 240024 set MAV_TYPE 12 -param set MAV_TYPE ${MAV_TYPE} set MIXER uuv_x 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 69384284be..e26a289fd7 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) param set-default NAV_DLL_ACT 0 @@ -41,7 +40,5 @@ param set-default BAT1_CAPACITY 18000 param set-default BAT1_V_DIV 11.0 param set-default BAT1_N_CELLS 4 param set-default BAT_V_OFFS_CURR 0.33 -set PWM_OUT 12345678 -# set MIXER IO_pass -set MIXER vectored6dof +set MIXER vectored6dof diff --git a/ROMFS/px4fmu_common/init.d/airframes/6001_hexa_x b/ROMFS/px4fmu_common/init.d/airframes/6001_hexa_x index 893bb991c9..daa92c75fd 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/6001_hexa_x +++ b/ROMFS/px4fmu_common/init.d/airframes/6001_hexa_x @@ -21,9 +21,6 @@ # @board bitcraze_crazyflie exclude # -. ${R}etc/init.d/rc.mc_defaults +. ${R}etc/init.d/rc.mc_hex_defaults -set MIXER hexa_x - -# Need to set all 8 channels -set PWM_OUT 12345678 +# MAIN set by rc.mc_hex_defaults diff --git a/ROMFS/px4fmu_common/init.d/airframes/6002_draco_r b/ROMFS/px4fmu_common/init.d/airframes/6002_draco_r index 1eefccbfb1..534cee7dff 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/6002_draco_r +++ b/ROMFS/px4fmu_common/init.d/airframes/6002_draco_r @@ -25,10 +25,7 @@ # @board bitcraze_crazyflie exclude # -. ${R}etc/init.d/rc.mc_defaults -set MIXER hexa_x -set PWM_OUT 12345678 - +. ${R}etc/init.d/rc.mc_hex_defaults ############################################### # Attitude & rate gains @@ -80,12 +77,6 @@ param set-default IMU_GYRO_CUTOFF 100 # Thrust curve (avoids the need for TPA) param set-default THR_MDL_FAC 0.25 -# System -param set-default PWM_MAIN_MAX 1950 -param set-default PWM_MAIN_MIN 1100 -param set-default PWM_MAIN_DIS5 980 -param set-default PWM_MAIN_DIS6 980 - # DSHOT param set-default DSHOT_CONFIG 600 @@ -112,9 +103,6 @@ param set-default SENS_FLOW_ROT 2 param set-default CBRK_IO_SAFETY 22027 param set-default COM_DISARM_LAND 3 -# PWM ONESHOT -param set-default PWM_MAIN_RATE 0 - # Battery param set-default BAT_SOURCE 0 param set-default BAT_N_CELLS 4 @@ -132,3 +120,6 @@ param set-default MAV_1_MODE 2 param set-default MAV_1_FORWARD 1 param set-default MAV_1_RATE 800000 param set-default SER_TEL2_BAUD 921600 + + +# MAIN set by rc.mc_hex_defaults 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..c479efcf9f 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/6003_hexa_x_ctrlalloc +++ b/ROMFS/px4fmu_common/init.d/airframes/6003_hexa_x_ctrlalloc @@ -10,7 +10,7 @@ # @board px4_fmu-v2 exclude # -. ${R}etc/init.d/rc.mc_defaults +. ${R}etc/init.d/rc.mc_hex_defaults . ${R}etc/init.d/rc.ctrlalloc @@ -67,8 +67,8 @@ param set-default CA_MC_R5_PY -0.1375 param set-default CA_MC_R5_CT 6.5 param set-default CA_MC_R5_KM -0.05 +# MAIN set MIXER direct -set PWM_OUT 123456 +# AUX set MIXER_AUX direct_aux -set PWM_AUX_OUT 123456 diff --git a/ROMFS/px4fmu_common/init.d/airframes/7001_hexa_+ b/ROMFS/px4fmu_common/init.d/airframes/7001_hexa_+ index 8f9e6f7cf9..e2794ab389 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/7001_hexa_+ +++ b/ROMFS/px4fmu_common/init.d/airframes/7001_hexa_+ @@ -21,9 +21,6 @@ # @board bitcraze_crazyflie exclude # -. ${R}etc/init.d/rc.mc_defaults +. ${R}etc/init.d/rc.mc_hex_defaults set MIXER hexa_+ - -# Need to set all 8 channels -set PWM_OUT 12345678 diff --git a/ROMFS/px4fmu_common/init.d/airframes/8001_octo_x b/ROMFS/px4fmu_common/init.d/airframes/8001_octo_x index e69776f314..96e1de1c79 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/8001_octo_x +++ b/ROMFS/px4fmu_common/init.d/airframes/8001_octo_x @@ -23,8 +23,6 @@ # @board bitcraze_crazyflie exclude # -. ${R}etc/init.d/rc.mc_defaults +. ${R}etc/init.d/rc.mc_octo_defaults -set MIXER octo_x - -set PWM_OUT 12345678 +# MAIN set by rc.mc_octo_defaults diff --git a/ROMFS/px4fmu_common/init.d/airframes/9001_octo_+ b/ROMFS/px4fmu_common/init.d/airframes/9001_octo_+ index b61a1f95b0..4909f10482 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/9001_octo_+ +++ b/ROMFS/px4fmu_common/init.d/airframes/9001_octo_+ @@ -23,8 +23,7 @@ # @board bitcraze_crazyflie exclude # -. ${R}etc/init.d/rc.mc_defaults +. ${R}etc/init.d/rc.mc_octo_defaults +# MAIN set by rc.mc_octo_defaults set MIXER octo_+ - -set PWM_OUT 12345678 diff --git a/ROMFS/px4fmu_common/init.d/rc.airship_defaults b/ROMFS/px4fmu_common/init.d/rc.airship_defaults index 25ac61e212..f626d46461 100644 --- a/ROMFS/px4fmu_common/init.d/rc.airship_defaults +++ b/ROMFS/px4fmu_common/init.d/rc.airship_defaults @@ -11,4 +11,3 @@ set VEHICLE_TYPE airship # This is the gimbal pass mixer. # set MIXER_AUX pass -set PWM_AUX_OUT 1234 diff --git a/ROMFS/px4fmu_common/init.d/rc.boat_defaults b/ROMFS/px4fmu_common/init.d/rc.boat_defaults index 54bb4d0ccd..2e61f987fa 100644 --- a/ROMFS/px4fmu_common/init.d/rc.boat_defaults +++ b/ROMFS/px4fmu_common/init.d/rc.boat_defaults @@ -19,21 +19,7 @@ param set-default NAV_ACC_RAD 2 # Temporary. param set-default NAV_FW_ALT_RAD 1000 -# -# Enable servo output on pins 3 and 4 (steering and thrust) -# but also include 1+2 as they form together one output group -# and need to be set together. -# -set PWM_OUT 1234 - -# -# PWM Hz - 50 Hz is the normal rate in RC cars, higher rates -# may damage analog servos. -# -set PWM_MAIN_RATE 50 - # # This is the gimbal pass mixer. # set MIXER_AUX pass -set PWM_AUX_OUT 1234 diff --git a/ROMFS/px4fmu_common/init.d/rc.fw_defaults b/ROMFS/px4fmu_common/init.d/rc.fw_defaults index 94828ac47c..32740222a8 100644 --- a/ROMFS/px4fmu_common/init.d/rc.fw_defaults +++ b/ROMFS/px4fmu_common/init.d/rc.fw_defaults @@ -45,8 +45,6 @@ param set-default MIS_DIST_WPS 5000 param set-default MIS_LTRMIN_ALT 25 param set-default MIS_TAKEOFF_ALT 25 -param set-default PWM_MAIN_RATE 50 - # # FW takeoff acceleration can easily exceed ublox GPS 2G default. # @@ -56,6 +54,3 @@ param set-default GPS_UBX_DYNMODEL 8 # This is the gimbal pass mixer. # set MIXER_AUX pass - -set PWM_AUX_RATE 50 -set PWM_AUX_OUT 1234 diff --git a/ROMFS/px4fmu_common/init.d/rc.mc_defaults b/ROMFS/px4fmu_common/init.d/rc.mc_defaults index 7a9fc56414..00ba980918 100644 --- a/ROMFS/px4fmu_common/init.d/rc.mc_defaults +++ b/ROMFS/px4fmu_common/init.d/rc.mc_defaults @@ -14,15 +14,4 @@ param set-default NAV_ACC_RAD 2 param set-default RTL_RETURN_ALT 30 param set-default RTL_DESCEND_ALT 10 -param set-default PWM_MAIN_MAX 1950 -param set-default PWM_MAIN_MIN 1075 -param set-default PWM_MAIN_RATE 400 - param set-default GPS_UBX_DYNMODEL 6 - -# -# This is the gimbal pass mixer. -# -set MIXER_AUX pass - -set PWM_AUX_OUT 1234 diff --git a/ROMFS/px4fmu_common/init.d/rc.mc_hex_defaults b/ROMFS/px4fmu_common/init.d/rc.mc_hex_defaults new file mode 100644 index 0000000000..a93bb226cb --- /dev/null +++ b/ROMFS/px4fmu_common/init.d/rc.mc_hex_defaults @@ -0,0 +1,38 @@ +#!/bin/sh +# +# Multicopter default parameters. +# +# NOTE: Script variables are declared/initialized/unset in the rcS script. +# + +. ${R}etc/init.d/rc.mc_defaults + +# MAIN +set MIXER hexa_x +param set-default PWM_MAIN_MIN1 1100 +param set-default PWM_MAIN_MIN2 1100 +param set-default PWM_MAIN_MIN3 1100 +param set-default PWM_MAIN_MIN4 1100 +param set-default PWM_MAIN_MIN5 1100 +param set-default PWM_MAIN_MIN6 1100 + +param set-default PWM_MAIN_MAX1 1900 +param set-default PWM_MAIN_MAX2 1900 +param set-default PWM_MAIN_MAX3 1900 +param set-default PWM_MAIN_MAX4 1900 +param set-default PWM_MAIN_MAX5 1900 +param set-default PWM_MAIN_MAX6 1900 + +param set-default PWM_MAIN_RATE1 400 +param set-default PWM_MAIN_RATE2 400 +param set-default PWM_MAIN_RATE3 400 +param set-default PWM_MAIN_RATE4 400 +param set-default PWM_MAIN_RATE5 400 +param set-default PWM_MAIN_RATE6 400 + +param set-default PWM_MAIN_DIS1 900 +param set-default PWM_MAIN_DIS2 900 +param set-default PWM_MAIN_DIS3 900 +param set-default PWM_MAIN_DIS4 900 +param set-default PWM_MAIN_DIS5 900 +param set-default PWM_MAIN_DIS6 900 diff --git a/ROMFS/px4fmu_common/init.d/rc.mc_octo_defaults b/ROMFS/px4fmu_common/init.d/rc.mc_octo_defaults new file mode 100644 index 0000000000..487bd750b5 --- /dev/null +++ b/ROMFS/px4fmu_common/init.d/rc.mc_octo_defaults @@ -0,0 +1,46 @@ +#!/bin/sh +# +# Multicopter default parameters. +# +# NOTE: Script variables are declared/initialized/unset in the rcS script. +# + +. ${R}etc/init.d/rc.mc_defaults + +# MAIN +set MIXER octo_x +param set-default PWM_MAIN_MIN1 1100 +param set-default PWM_MAIN_MIN2 1100 +param set-default PWM_MAIN_MIN3 1100 +param set-default PWM_MAIN_MIN4 1100 +param set-default PWM_MAIN_MIN5 1100 +param set-default PWM_MAIN_MIN6 1100 +param set-default PWM_MAIN_MIN7 1100 +param set-default PWM_MAIN_MIN8 1100 + +param set-default PWM_MAIN_MAX1 1900 +param set-default PWM_MAIN_MAX2 1900 +param set-default PWM_MAIN_MAX3 1900 +param set-default PWM_MAIN_MAX4 1900 +param set-default PWM_MAIN_MAX5 1900 +param set-default PWM_MAIN_MAX6 1900 +param set-default PWM_MAIN_MAX7 1900 +param set-default PWM_MAIN_MAX8 1900 + +param set-default PWM_MAIN_RATE1 400 +param set-default PWM_MAIN_RATE2 400 +param set-default PWM_MAIN_RATE3 400 +param set-default PWM_MAIN_RATE4 400 +param set-default PWM_MAIN_RATE5 400 +param set-default PWM_MAIN_RATE6 400 +param set-default PWM_MAIN_RATE7 400 +param set-default PWM_MAIN_RATE8 400 + +param set-default PWM_MAIN_DIS1 900 +param set-default PWM_MAIN_DIS2 900 +param set-default PWM_MAIN_DIS3 900 +param set-default PWM_MAIN_DIS4 900 +param set-default PWM_MAIN_DIS5 900 +param set-default PWM_MAIN_DIS6 900 +param set-default PWM_MAIN_DIS7 900 +param set-default PWM_MAIN_DIS8 900 diff --git a/ROMFS/px4fmu_common/init.d/rc.mc_quad_defaults b/ROMFS/px4fmu_common/init.d/rc.mc_quad_defaults new file mode 100644 index 0000000000..c7e8247df5 --- /dev/null +++ b/ROMFS/px4fmu_common/init.d/rc.mc_quad_defaults @@ -0,0 +1,30 @@ +#!/bin/sh +# +# Multicopter default parameters. +# +# NOTE: Script variables are declared/initialized/unset in the rcS script. +# + +. ${R}etc/init.d/rc.mc_defaults + +# MAIN +set MIXER quad_x +param set-default PWM_MAIN_MIN1 1100 +param set-default PWM_MAIN_MIN2 1100 +param set-default PWM_MAIN_MIN3 1100 +param set-default PWM_MAIN_MIN4 1100 + +param set-default PWM_MAIN_MAX1 1900 +param set-default PWM_MAIN_MAX2 1900 +param set-default PWM_MAIN_MAX3 1900 +param set-default PWM_MAIN_MAX4 1900 + +param set-default PWM_MAIN_RATE1 400 +param set-default PWM_MAIN_RATE2 400 +param set-default PWM_MAIN_RATE3 400 +param set-default PWM_MAIN_RATE4 400 + +param set-default PWM_MAIN_DIS1 900 +param set-default PWM_MAIN_DIS2 900 +param set-default PWM_MAIN_DIS3 900 +param set-default PWM_MAIN_DIS4 900 diff --git a/ROMFS/px4fmu_common/init.d/rc.rover_defaults b/ROMFS/px4fmu_common/init.d/rc.rover_defaults index 26db6d098c..baf52f4f93 100644 --- a/ROMFS/px4fmu_common/init.d/rc.rover_defaults +++ b/ROMFS/px4fmu_common/init.d/rc.rover_defaults @@ -20,21 +20,7 @@ param set-default NAV_LOITER_RAD 2 # Temporary. param set-default NAV_FW_ALT_RAD 1000 -# -# Enable servo output on pins 3 and 4 (steering and thrust) -# but also include 1+2 as they form together one output group -# and need to be set together. -# -set PWM_OUT 1234 - -# -# PWM Hz - 50 Hz is the normal rate in RC cars, higher rates -# may damage analog servos. -# -set PWM_MAIN_RATE 50 - # # This is the gimbal pass mixer. # set MIXER_AUX pass -set PWM_AUX_OUT 1234 diff --git a/ROMFS/px4fmu_common/init.d/rc.uuv_defaults b/ROMFS/px4fmu_common/init.d/rc.uuv_defaults index 6d525fd0e1..a6359c0909 100644 --- a/ROMFS/px4fmu_common/init.d/rc.uuv_defaults +++ b/ROMFS/px4fmu_common/init.d/rc.uuv_defaults @@ -7,23 +7,22 @@ set VEHICLE_TYPE uuv -param set-default PWM_MAIN_MAX 1950 -param set-default PWM_MAIN_MIN 1050 -param set-default PWM_MAIN_DISARM 1500 +param set-default PWM_MAIN_MIN1 1100 +param set-default PWM_MAIN_MIN2 1100 +param set-default PWM_MAIN_MIN3 1100 +param set-default PWM_MAIN_MIN4 1100 -# -# PWM Hz - 50 Hz is the normal rate in RC cars, boats etc, -# higher rates may damage analog servos. -# -set PWM_MAIN_RATE 50 +param set-default PWM_MAIN_MAX1 1900 +param set-default PWM_MAIN_MAX2 1900 +param set-default PWM_MAIN_MAX3 1900 +param set-default PWM_MAIN_MAX4 1900 -# -# Enable servo output on pins 1-4 -set PWM_OUT 1234 +param set-default PWM_MAIN_DIS1 1500 +param set-default PWM_MAIN_DIS2 1500 +param set-default PWM_MAIN_DIS3 1500 +param set-default PWM_MAIN_DIS4 1500 # # This is the gimbal pass mixer. # set MIXER_AUX pass -set PWM_AUX_OUT 1234 -set PWM_AUX_RATE 50 diff --git a/ROMFS/px4fmu_common/init.d/rc.vtol_defaults b/ROMFS/px4fmu_common/init.d/rc.vtol_defaults index 2d229fddb3..10cd5f7fd6 100644 --- a/ROMFS/px4fmu_common/init.d/rc.vtol_defaults +++ b/ROMFS/px4fmu_common/init.d/rc.vtol_defaults @@ -27,9 +27,6 @@ param set-default MPC_YAW_MODE 4 param set-default NAV_ACC_RAD 3 -param set-default PWM_AUX_RATE 50 -param set-default PWM_MAIN_RATE 400 - param set-default RTL_TYPE 1 param set-default WV_EN 1 diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS index 0832c4f6d8..f2097847e0 100644 --- a/ROMFS/px4fmu_common/init.d/rcS +++ b/ROMFS/px4fmu_common/init.d/rcS @@ -38,12 +38,6 @@ set MIXER_FILE none set MIXER_EXTRA none set OUTPUT_MODE none set PARAM_FILE /fs/microsd/params -set PWM_OUT none -set PWM_MAIN_RATE p:PWM_MAIN_RATE -set PWM_AUX_OUT none -set PWM_AUX_RATE p:PWM_AUX_RATE -set PWM_EXTRA_OUT none -set PWM_EXTRA_RATE p:PWM_EXTRA_RATE set EXTRA_MIXER_MODE none set RC_INPUT_ARGS "" set SDCARD_MIXERS_PATH /fs/microsd/etc/mixers @@ -561,12 +555,6 @@ unset MIXER_AUX unset MIXER_FILE unset OUTPUT_MODE unset PARAM_FILE -unset PWM_AUX_OUT -unset PWM_AUX_RATE -unset PWM_MAIN_RATE -unset PWM_OUT -unset PWM_EXTRA_OUT -unset PWM_EXTRA_RATE unset RC_INPUT_ARGS unset SDCARD_MIXERS_PATH unset STARTUP_TUNE diff --git a/ROMFS/px4fmu_common/mixers/CMakeLists.txt b/ROMFS/px4fmu_common/mixers/CMakeLists.txt index df861065a2..6f87881c84 100644 --- a/ROMFS/px4fmu_common/mixers/CMakeLists.txt +++ b/ROMFS/px4fmu_common/mixers/CMakeLists.txt @@ -42,7 +42,6 @@ px4_add_romfs_files( caipi.main.mix CCPM.main.mix claire.aux.mix - claire.main.mix cloudship.main.mix coax.main.mix delta.main.mix diff --git a/ROMFS/px4fmu_common/mixers/TF-AutoG2.main.mix b/ROMFS/px4fmu_common/mixers/TF-AutoG2.main.mix index bed0fedee2..ffa5214d78 100644 --- a/ROMFS/px4fmu_common/mixers/TF-AutoG2.main.mix +++ b/ROMFS/px4fmu_common/mixers/TF-AutoG2.main.mix @@ -11,13 +11,13 @@ Two scalers total (output, roll). M: 2 O: 10000 10000 0 -10000 10000 S: 0 0 -10000 -10000 0 -10000 10000 -S: 0 1 10000 10000 0 -10000 10000 +S: 0 1 10000 10000 0 -10000 10000 M: 2 O: 10000 10000 0 -10000 10000 S: 0 0 -10000 -10000 0 -10000 10000 -S: 0 1 -10000 -10000 0 -10000 10000 +S: 0 1 -10000 -10000 0 -10000 10000 CH3: Elevator, prerotator mixer diff --git a/ROMFS/px4fmu_common/mixers/claire.aux.mix b/ROMFS/px4fmu_common/mixers/claire.aux.mix index 7213daf2a2..9333fa8cc6 100644 --- a/ROMFS/px4fmu_common/mixers/claire.aux.mix +++ b/ROMFS/px4fmu_common/mixers/claire.aux.mix @@ -1,23 +1,13 @@ # mixer for the CruiseAder Claire tilt mechansim servo and elevons - ======================================================================= - Tilt mechanism servo mixer - --------------------------- - M: 1 - - S: 1 4 10000 10000 0 -10000 10000 - - Elevon mixers - ------------- - M: 2 S: 1 0 7500 7500 0 -10000 10000 diff --git a/ROMFS/px4fmu_common/mixers/claire.main.mix b/ROMFS/px4fmu_common/mixers/claire.main.mix deleted file mode 100644 index af84d3d8a1..0000000000 --- a/ROMFS/px4fmu_common/mixers/claire.main.mix +++ /dev/null @@ -1,7 +0,0 @@ -# CruiseAder Claire Main Multirotor mixer for PX4FMU - -# - -#=========================== - -R: 4x diff --git a/posix-configs/bbblue/px4.config b/posix-configs/bbblue/px4.config index afe9f4bc57..1217df4f87 100644 --- a/posix-configs/bbblue/px4.config +++ b/posix-configs/bbblue/px4.config @@ -21,8 +21,6 @@ param set SYS_AUTOSTART 4011 # http://www.dji.com/e2000/info indicates E2000 Operating Pulse Width: 1120 to 1920 μs # It seems that all latest DJI ESC have the same range. # Note that the setting here applies to all PWM channels. -# param set PWM_MAIN_MIN 1120 -# param set PWM_MAIN_MAX 1920 # Not using DJI 430 LITE ESC anymore due to its hiccups: # each random motor stop would cause a scary flip in the fly # Replacing with 4 BLHeli32 (Wraith32 V2) ESCs solved the main problem in BBBlue porting diff --git a/posix-configs/bbblue/px4_fw.config b/posix-configs/bbblue/px4_fw.config index 15d506d48a..7610404bc4 100644 --- a/posix-configs/bbblue/px4_fw.config +++ b/posix-configs/bbblue/px4_fw.config @@ -21,8 +21,6 @@ param set SYS_AUTOSTART 4011 # http://www.dji.com/e2000/info indicates E2000 Operating Pulse Width: 1120 to 1920 μs # It seems that all latest DJI ESC have the same range. # Note that the setting here applies to all PWM channels. -# param set PWM_MAIN_MIN 1120 -# param set PWM_MAIN_MAX 1920 # Not using DJI 430 LITE ESC anymore due to its hiccups: # each random motor stop would cause a scary flip in the fly # Replacing with 4 BLHeli32 (Wraith32 V2) ESCs solved the main problem in BBBlue porting diff --git a/src/drivers/pwm_out/PWMOut.cpp b/src/drivers/pwm_out/PWMOut.cpp index 6ea6a6a052..e5cab04ec4 100644 --- a/src/drivers/pwm_out/PWMOut.cpp +++ b/src/drivers/pwm_out/PWMOut.cpp @@ -659,37 +659,17 @@ void PWMOut::update_params() { updateParams(); - int32_t pwm_min_default = PWM_DEFAULT_MIN; - int32_t pwm_max_default = PWM_DEFAULT_MAX; - int32_t pwm_disarmed_default = 0; - int32_t pwm_rate_default = 50; - const char *prefix; if (_class_instance == CLASS_DEVICE_PRIMARY) { prefix = "PWM_MAIN"; - param_get(param_find("PWM_MAIN_MIN"), &pwm_min_default); - param_get(param_find("PWM_MAIN_MAX"), &pwm_max_default); - param_get(param_find("PWM_MAIN_DISARM"), &pwm_disarmed_default); - param_get(param_find("PWM_MAIN_RATE"), &pwm_rate_default); - } else if (_class_instance == CLASS_DEVICE_SECONDARY) { prefix = "PWM_AUX"; - param_get(param_find("PWM_AUX_MIN"), &pwm_min_default); - param_get(param_find("PWM_AUX_MAX"), &pwm_max_default); - param_get(param_find("PWM_AUX_DISARM"), &pwm_disarmed_default); - param_get(param_find("PWM_AUX_RATE"), &pwm_rate_default); - } else if (_class_instance == CLASS_DEVICE_TERTIARY) { prefix = "PWM_EXTRA"; - param_get(param_find("PWM_EXTRA_MIN"), &pwm_min_default); - param_get(param_find("PWM_EXTRA_MAX"), &pwm_max_default); - param_get(param_find("PWM_EXTRA_DISARM"), &pwm_disarmed_default); - param_get(param_find("PWM_EXTRA_RATE"), &pwm_rate_default); - } else { PX4_ERR("invalid class instance %d", _class_instance); return; @@ -705,19 +685,14 @@ void PWMOut::update_params() // PWM_MAIN_MINx { sprintf(str, "%s_MIN%u", prefix, i + 1); - int32_t pwm_min = -1; + int32_t pwm_min = PWM_DEFAULT_MIN; if (param_get(param_find(str), &pwm_min) == PX4_OK) { - if (pwm_min >= 0) { - _mixing_output.minValue(i) = math::constrain(pwm_min, (int32_t) PWM_LOWEST_MIN, (int32_t) PWM_HIGHEST_MIN); + _mixing_output.minValue(i) = math::constrain(pwm_min, PWM_LOWEST_MIN, PWM_HIGHEST_MIN); - if (pwm_min != _mixing_output.minValue(i)) { - int32_t pwm_min_new = _mixing_output.minValue(i); - param_set(param_find(str), &pwm_min_new); - } - - } else { - _mixing_output.minValue(i) = pwm_min_default; + if (pwm_min != _mixing_output.minValue(i)) { + int32_t pwm_min_new = _mixing_output.minValue(i); + param_set(param_find(str), &pwm_min_new); } } } @@ -725,19 +700,14 @@ void PWMOut::update_params() // PWM_MAIN_MAXx { sprintf(str, "%s_MAX%u", prefix, i + 1); - int32_t pwm_max = -1; + int32_t pwm_max = PWM_DEFAULT_MAX; if (param_get(param_find(str), &pwm_max) == PX4_OK) { - if (pwm_max >= 0) { - _mixing_output.maxValue(i) = math::constrain(pwm_max, (int32_t) PWM_LOWEST_MAX, (int32_t) PWM_HIGHEST_MAX); + _mixing_output.maxValue(i) = math::constrain(pwm_max, PWM_LOWEST_MAX, PWM_HIGHEST_MAX); - if (pwm_max != _mixing_output.maxValue(i)) { - int32_t pwm_max_new = _mixing_output.maxValue(i); - param_set(param_find(str), &pwm_max_new); - } - - } else { - _mixing_output.maxValue(i) = pwm_max_default; + if (pwm_max != _mixing_output.maxValue(i)) { + int32_t pwm_max_new = _mixing_output.maxValue(i); + param_set(param_find(str), &pwm_max_new); } } } @@ -745,16 +715,14 @@ void PWMOut::update_params() // PWM_MAIN_FAILx { sprintf(str, "%s_FAIL%u", prefix, i + 1); - int32_t pwm_failsafe = -1; + int32_t pwm_failsafe = 0; if (param_get(param_find(str), &pwm_failsafe) == PX4_OK) { - if (pwm_failsafe >= 0) { - _mixing_output.failsafeValue(i) = math::constrain(pwm_failsafe, (int32_t) 0, (int32_t) PWM_HIGHEST_MAX); + _mixing_output.failsafeValue(i) = math::constrain(pwm_failsafe, 0, PWM_HIGHEST_MAX); - if (pwm_failsafe != _mixing_output.failsafeValue(i)) { - int32_t pwm_fail_new = _mixing_output.failsafeValue(i); - param_set(param_find(str), &pwm_fail_new); - } + if (pwm_failsafe != _mixing_output.failsafeValue(i)) { + int32_t pwm_fail_new = _mixing_output.failsafeValue(i); + param_set(param_find(str), &pwm_fail_new); } } } @@ -762,19 +730,14 @@ void PWMOut::update_params() // PWM_MAIN_DISx { sprintf(str, "%s_DIS%u", prefix, i + 1); - int32_t pwm_dis = -1; + int32_t pwm_dis = 0; if (param_get(param_find(str), &pwm_dis) == PX4_OK) { - if (pwm_dis >= 0) { - _mixing_output.disarmedValue(i) = math::constrain(pwm_dis, (int32_t) 0, (int32_t) PWM_HIGHEST_MAX); + _mixing_output.disarmedValue(i) = math::constrain(pwm_dis, 0, PWM_HIGHEST_MAX); - if (pwm_dis != _mixing_output.disarmedValue(i)) { - int32_t pwm_dis_new = _mixing_output.disarmedValue(i); - param_set(param_find(str), &pwm_dis_new); - } - - } else { - _mixing_output.disarmedValue(i) = pwm_disarmed_default; + if (pwm_dis != _mixing_output.disarmedValue(i)) { + int32_t pwm_dis_new = _mixing_output.disarmedValue(i); + param_set(param_find(str), &pwm_dis_new); } } @@ -801,6 +764,24 @@ void PWMOut::update_params() } } + + // PWM_MAIN_RATEx + { + //uint32_t rate_map = 0; + + for (unsigned i = 0; i < _num_outputs; i++) { + sprintf(str, "%s_RATE%u", prefix, i + 1); + int32_t pwm_rate = 50; + + if (param_get(param_find(str), &pwm_rate) == PX4_OK) { + //rate_map |= + } + } + + + // set_pwm_rate(uint32_t rate_map, unsigned default_rate, unsigned alt_rate) + } + if (_mixing_output.mixers()) { int16_t values[FMU_MAX_ACTUATORS] {}; diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp index 87f9fff4c3..d5b29e7852 100644 --- a/src/drivers/px4io/px4io.cpp +++ b/src/drivers/px4io/px4io.cpp @@ -1205,21 +1205,10 @@ void PX4IO::update_params() return; } - int32_t pwm_min_default = PWM_DEFAULT_MIN; - int32_t pwm_max_default = PWM_DEFAULT_MAX; - int32_t pwm_disarmed_default = 0; - int32_t pwm_rate_default = 50; - const char *prefix = "PWM_MAIN"; - param_get(param_find("PWM_MAIN_MIN"), &pwm_min_default); - param_get(param_find("PWM_MAIN_MAX"), &pwm_max_default); - param_get(param_find("PWM_MAIN_DISARM"), &pwm_disarmed_default); - param_get(param_find("PWM_MAIN_RATE"), &pwm_rate_default); - char str[17]; - // PWM_MAIN_MINx if (!_pwm_min_configured) { pwm_output_values pwm{}; @@ -1227,19 +1216,14 @@ void PX4IO::update_params() for (unsigned i = 0; i < _max_actuators; i++) { sprintf(str, "%s_MIN%u", prefix, i + 1); - int32_t pwm_min = -1; + int32_t pwm_min = PWM_DEFAULT_MIN; if (param_get(param_find(str), &pwm_min) == PX4_OK) { - if (pwm_min >= 0) { - pwm.values[i] = math::constrain(pwm_min, static_cast(PWM_LOWEST_MIN), static_cast(PWM_HIGHEST_MIN)); + pwm.values[i] = math::constrain(pwm_min, PWM_LOWEST_MIN, PWM_HIGHEST_MIN); - if (pwm_min != pwm.values[i]) { - int32_t pwm_min_new = pwm.values[i]; - param_set(param_find(str), &pwm_min_new); - } - - } else { - pwm.values[i] = pwm_min_default; + if (pwm_min != pwm.values[i]) { + int32_t pwm_min_new = pwm.values[i]; + param_set(param_find(str), &pwm_min_new); } } } @@ -1256,19 +1240,14 @@ void PX4IO::update_params() for (unsigned i = 0; i < _max_actuators; i++) { sprintf(str, "%s_MAX%u", prefix, i + 1); - int32_t pwm_max = -1; + int32_t pwm_max = PWM_DEFAULT_MAX; if (param_get(param_find(str), &pwm_max) == PX4_OK) { - if (pwm_max >= 0) { - pwm.values[i] = math::constrain(pwm_max, static_cast(PWM_LOWEST_MAX), static_cast(PWM_HIGHEST_MAX)); + pwm.values[i] = math::constrain(pwm_max, PWM_LOWEST_MAX, PWM_HIGHEST_MAX); - if (pwm_max != pwm.values[i]) { - int32_t pwm_max_new = pwm.values[i]; - param_set(param_find(str), &pwm_max_new); - } - - } else { - pwm.values[i] = pwm_max_default; + if (pwm_max != pwm.values[i]) { + int32_t pwm_max_new = pwm.values[i]; + param_set(param_find(str), &pwm_max_new); } } } @@ -1285,16 +1264,14 @@ void PX4IO::update_params() for (unsigned i = 0; i < _max_actuators; i++) { sprintf(str, "%s_FAIL%u", prefix, i + 1); - int32_t pwm_fail = -1; + int32_t pwm_fail = 0; if (param_get(param_find(str), &pwm_fail) == PX4_OK) { - if (pwm_fail >= 0) { - pwm.values[i] = math::constrain(pwm_fail, static_cast(0), static_cast(PWM_HIGHEST_MAX)); + pwm.values[i] = math::constrain(pwm_fail, 0, PWM_HIGHEST_MAX); - if (pwm_fail != pwm.values[i]) { - int32_t pwm_fail_new = pwm.values[i]; - param_set(param_find(str), &pwm_fail_new); - } + if (pwm_fail != pwm.values[i]) { + int32_t pwm_fail_new = pwm.values[i]; + param_set(param_find(str), &pwm_fail_new); } } } @@ -1311,19 +1288,14 @@ void PX4IO::update_params() for (unsigned i = 0; i < _max_actuators; i++) { sprintf(str, "%s_DIS%u", prefix, i + 1); - int32_t pwm_dis = -1; + int32_t pwm_dis = 0; if (param_get(param_find(str), &pwm_dis) == PX4_OK) { - if (pwm_dis >= 0) { - pwm.values[i] = math::constrain(pwm_dis, static_cast(0), static_cast(PWM_HIGHEST_MAX)); + pwm.values[i] = math::constrain(pwm_dis, 0, PWM_HIGHEST_MAX); - if (pwm_dis != pwm.values[i]) { - int32_t pwm_dis_new = pwm.values[i]; - param_set(param_find(str), &pwm_dis_new); - } - - } else { - pwm.values[i] = pwm_disarmed_default; + if (pwm_dis != pwm.values[i]) { + int32_t pwm_dis_new = pwm.values[i]; + param_set(param_find(str), &pwm_dis_new); } } } diff --git a/src/lib/parameters/param_translation.cpp b/src/lib/parameters/param_translation.cpp index 96ebbd0a80..6041cd21bc 100644 --- a/src/lib/parameters/param_translation.cpp +++ b/src/lib/parameters/param_translation.cpp @@ -142,29 +142,6 @@ bool param_modify_on_import(bson_node_t node) } } - // 2021-01-31 (v1.12 alpha): translate PWM_MIN/PWM_MAX/PWM_DISARMED to PWM_MAIN - { - if (strcmp("PWM_MIN", node->name) == 0) { - strcpy(node->name, "PWM_MAIN_MIN"); - PX4_INFO("copying %s -> %s", "PWM_MIN", "PWM_MAIN_MIN"); - } - - if (strcmp("PWM_MAX", node->name) == 0) { - strcpy(node->name, "PWM_MAIN_MAX"); - PX4_INFO("copying %s -> %s", "PWM_MAX", "PWM_MAIN_MAX"); - } - - if (strcmp("PWM_RATE", node->name) == 0) { - strcpy(node->name, "PWM_MAIN_RATE"); - PX4_INFO("copying %s -> %s", "PWM_RATE", "PWM_MAIN_RATE"); - } - - if (strcmp("PWM_DISARMED", node->name) == 0) { - strcpy(node->name, "PWM_MAIN_DISARM"); - PX4_INFO("copying %s -> %s", "PWM_DISARMED", "PWM_MAIN_DISARM"); - } - } - // 2021-04-30: translate ASPD_STALL to FW_AIRSPD_STALL { if (strcmp("ASPD_STALL", node->name) == 0) { diff --git a/src/lib/pwm/pwm_aux_params.yaml b/src/lib/pwm/pwm_aux_params.yaml index 002a9d125e..3c209d04df 100644 --- a/src/lib/pwm/pwm_aux_params.yaml +++ b/src/lib/pwm/pwm_aux_params.yaml @@ -6,108 +6,57 @@ parameters: - group: PWM Outputs definitions: - PWM_AUX_RATE: - description: - short: PWM aux output frequency - long: | - Set to 400 for industry default or 1000 for high frequency ESCs. - Set to 0 for Oneshot125. - type: int32 - unit: Hz - min: -1 - max: 2000 - default: 50 - - PWM_AUX_MIN: - description: - short: PWM aux minimum value - long: | - Set to 1000 for industry default or 900 to increase servo travel. - type: int32 - unit: us - min: 800 - max: 1400 - default: 1000 - - PWM_AUX_MAX: - description: - short: PWM aux maximum value - long: | - Set to 2000 for industry default or 2100 to increase servo travel. - type: int32 - unit: us - min: 1600 - max: 2200 - default: 2000 - - PWM_AUX_DISARM: - description: - short: PWM aux disarmed value - long: | - This is the PWM pulse the autopilot is outputting if not armed. - The main use of this parameter is to silence ESCs when they are disarmed. - type: int32 - unit: us - min: 0 - max: 2200 - default: 1500 - PWM_AUX_MIN${i}: description: short: PWM aux ${i} minimum value long: | This is the minimum PWM pulse the autopilot is allowed to output. - When set to -1 the value for PWM_AUX_MIN will be used type: int32 unit: us - min: -1 + min: 800 max: 1600 num_instances: *max_num_config_instances instance_start: 1 - default: -1 + default: 1000 PWM_AUX_MAX${i}: description: short: PWM aux ${i} maximum value long: | This is the maximum PWM pulse the autopilot is allowed to output. - When set to -1 the value for PWM_AUX_MAX will be used type: int32 unit: us - min: -1 + min: 1400 max: 2150 num_instances: *max_num_config_instances instance_start: 1 - default: -1 + default: 2000 PWM_AUX_FAIL${i}: description: short: PWM aux ${i} failsafe value long: | This is the PWM pulse the autopilot is outputting if in failsafe mode. - When set to -1 the value is set automatically depending if the actuator - is a motor (900us) or a servo (1500us) type: int32 unit: us - min: -1 + min: 0 max: 2150 num_instances: *max_num_config_instances instance_start: 1 - default: -1 + default: 0 PWM_AUX_DIS${i}: description: short: PWM aux ${i} disarmed value long: | This is the PWM pulse the autopilot is outputting if not armed. - When set to -1 the value for PWM_AUX_DISARM will be used type: int32 unit: us - min: -1 + min: 0 max: 2150 num_instances: *max_num_config_instances instance_start: 1 - default: -1 + default: 0 PWM_AUX_TRIM${i}: description: @@ -128,7 +77,6 @@ parameters: long: | Enable to invert the channel. Warning: Use this parameter when connected to a servo only. - For a brushless motor, invert manually two phases to reverse the direction. type: boolean num_instances: *max_num_config_instances instance_start: 1 diff --git a/src/lib/pwm/pwm_extra_params.yaml b/src/lib/pwm/pwm_extra_params.yaml index fcacc754ce..0ddc53dde9 100644 --- a/src/lib/pwm/pwm_extra_params.yaml +++ b/src/lib/pwm/pwm_extra_params.yaml @@ -6,87 +6,37 @@ parameters: - group: PWM Outputs definitions: - PWM_EXTRA_RATE: - description: - short: PWM extra output frequency - long: | - Set to 400 for industry default or 1000 for high frequency ESCs. - Set to 0 for Oneshot125. - type: int32 - unit: Hz - min: -1 - max: 2000 - default: 50 - - PWM_EXTRA_MIN: - description: - short: PWM extra minimum value - long: | - Set to 1000 for industry default or 900 to increase servo travel. - type: int32 - unit: us - min: 800 - max: 1400 - default: 1000 - - PWM_EXTRA_MAX: - description: - short: PWM extra maximum value - long: | - Set to 2000 for industry default or 2100 to increase servo travel. - type: int32 - unit: us - min: 1600 - max: 2200 - default: 2000 - - PWM_EXTRA_DISARM: - description: - short: PWM extra disarmed value - long: | - This is the PWM pulse the autopilot is outputting if not armed. - The main use of this parameter is to silence ESCs when they are disarmed. - type: int32 - unit: us - min: 0 - max: 2200 - default: 1500 - PWM_EXTRA_MIN${i}: description: short: PWM extra ${i} minimum value long: | This is the minimum PWM pulse the autopilot is allowed to output. - When set to -1 the value for PWM_EXTRA_MIN will be used type: int32 unit: us - min: -1 + min: 800 max: 1600 num_instances: *max_num_config_instances instance_start: 1 - default: -1 + default: 1000 PWM_EXTRA_MAX${i}: description: short: PWM extra ${i} maximum value long: | This is the maximum PWM pulse the autopilot is allowed to output. - When set to -1 the value for PWM_EXTRA_MAX will be used type: int32 unit: us - min: -1 + min: 1400 max: 2150 num_instances: *max_num_config_instances instance_start: 1 - default: -1 + default: 2000 PWM_EXTRA_FAIL${i}: description: short: PWM extra ${i} failsafe value long: | This is the PWM pulse the autopilot is outputting if in failsafe mode. - When set to -1 the value is set automatically depending if the actuator - is a motor (900us) or a servo (1500us) type: int32 unit: us min: 0 @@ -100,14 +50,13 @@ parameters: short: PWM extra ${i} disarmed value long: | This is the PWM pulse the autopilot is outputting if not armed. - When set to -1 the value for PWM_EXTRA_DISARM will be used type: int32 unit: us - min: -1 + min: 0 max: 2150 num_instances: *max_num_config_instances instance_start: 1 - default: -1 + default: 0 PWM_EXTRA_TRIM${i}: description: @@ -128,7 +77,6 @@ parameters: long: | Enable to invert the channel. Warning: Use this parameter when connected to a servo only. - For a brushless motor, invert manually two phases to reverse the direction. type: boolean num_instances: *max_num_config_instances instance_start: 1 @@ -138,7 +86,7 @@ parameters: description: short: PWM extra ${i} rate long: | - Set the default PWM output frequency for the main outputs + Set the default PWM output frequency for the extra outputs type: int32 unit: Hz min: 0 diff --git a/src/lib/pwm/pwm_main_params.yaml b/src/lib/pwm/pwm_main_params.yaml index 8808215a55..7a22de04ff 100644 --- a/src/lib/pwm/pwm_main_params.yaml +++ b/src/lib/pwm/pwm_main_params.yaml @@ -6,108 +6,57 @@ parameters: - group: PWM Outputs definitions: - PWM_MAIN_RATE: - description: - short: PWM main output frequency - long: | - Set to 400 for industry default or 1000 for high frequency ESCs. - Set to 0 for Oneshot125. - type: int32 - unit: Hz - min: -1 - max: 2000 - default: 400 - - PWM_MAIN_MIN: - description: - short: PWM main minimum value - long: | - Set to 1000 for industry default or 900 to increase servo travel. - type: int32 - unit: us - min: 800 - max: 1400 - default: 1000 - - PWM_MAIN_MAX: - description: - short: PWM main maximum value - long: | - Set to 2000 for industry default or 2100 to increase servo travel. - type: int32 - unit: us - min: 1600 - max: 2200 - default: 2000 - - PWM_MAIN_DISARM: - description: - short: PWM main disarmed value - long: | - This is the PWM pulse the autopilot is outputting if not armed. - The main use of this parameter is to silence ESCs when they are disarmed. - type: int32 - unit: us - min: 0 - max: 2200 - default: 900 - PWM_MAIN_MIN${i}: description: short: PWM main ${i} minimum value long: | This is the minimum PWM pulse the autopilot is allowed to output. - When set to -1 the value for PWM_MAIN_MIN will be used type: int32 unit: us - min: -1 + min: 800 max: 1600 num_instances: *max_num_config_instances instance_start: 1 - default: -1 + default: 1000 PWM_MAIN_MAX${i}: description: short: PWM main ${i} maximum value long: | This is the maximum PWM pulse the autopilot is allowed to output. - When set to -1 the value for PWM_MAIN_MAX will be used type: int32 unit: us - min: -1 - max: 2150 + min: 1400 + max: 2500 num_instances: *max_num_config_instances instance_start: 1 - default: -1 + default: 2000 PWM_MAIN_FAIL${i}: description: short: PWM main ${i} failsafe value long: | This is the PWM pulse the autopilot is outputting if in failsafe mode. - When set to -1 the value is set automatically depending if the actuator - is a motor (900us) or a servo (1500us) type: int32 unit: us - min: -1 + min: 0 max: 2150 num_instances: *max_num_config_instances instance_start: 1 - default: -1 + default: 0 PWM_MAIN_DIS${i}: description: short: PWM main ${i} disarmed value long: | This is the PWM pulse the autopilot is outputting if not armed. - When set to -1 the value for PWM_MAIN_DISARM will be used type: int32 unit: us - min: -1 - max: 2150 + min: 0 + max: 2500 num_instances: *max_num_config_instances instance_start: 1 - default: -1 + default: 0 PWM_MAIN_TRIM${i}: description: @@ -128,7 +77,6 @@ parameters: long: | Enable to invert the channel. Warning: Use this parameter when connected to a servo only. - For a brushless motor, invert manually two phases to reverse the direction. type: boolean num_instances: *max_num_config_instances instance_start: 1