diff --git a/ROMFS/px4fmu_common/init.d/airframes/10018_tbs_endurance b/ROMFS/px4fmu_common/init.d/airframes/10018_tbs_endurance index 5188d861cc..e0a56b753e 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/10018_tbs_endurance +++ b/ROMFS/px4fmu_common/init.d/airframes/10018_tbs_endurance @@ -46,7 +46,7 @@ then param set MPC_XY_VEL_MAX 2 - param set PWM_MIN 1080 + param set PWM_MAIN_MIN 1080 fi set MIXER quad_w 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 f1908d58a1..5ed66b32ad 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/13000_generic_vtol_standard +++ b/ROMFS/px4fmu_common/init.d/airframes/13000_generic_vtol_standard @@ -27,7 +27,7 @@ if [ $AUTOCNF = yes ] then param set PWM_AUX_DIS5 950 - param set PWM_RATE 400 + param set PWM_MAIN_RATE 400 param set VT_TYPE 2 param set VT_MOT_ID 1234 diff --git a/ROMFS/px4fmu_common/init.d/airframes/13002_firefly6 b/ROMFS/px4fmu_common/init.d/airframes/13002_firefly6 index b6aaa1cba7..ef17798b67 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/13002_firefly6 +++ b/ROMFS/px4fmu_common/init.d/airframes/13002_firefly6 @@ -42,7 +42,7 @@ then param set MC_YAWRATE_D 0 param set MC_YAWRATE_FF 0 - param set PWM_RATE 400 + param set PWM_MAIN_RATE 400 param set VT_FW_MOT_OFFID 34 param set VT_IDLE_PWM_MC 1080 diff --git a/ROMFS/px4fmu_common/init.d/airframes/13003_quad_tailsitter b/ROMFS/px4fmu_common/init.d/airframes/13003_quad_tailsitter index 8bb2ce544c..4c92111fc9 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/13003_quad_tailsitter +++ b/ROMFS/px4fmu_common/init.d/airframes/13003_quad_tailsitter @@ -16,8 +16,8 @@ if [ $AUTOCNF = yes ] then - param set PWM_MAX 2000 - param set PWM_RATE 400 + param set PWM_MAIN_MAX 2000 + param set PWM_MAIN_RATE 400 param set VT_MOT_ID 1234 param set VT_IDLE_PWM_MC 1080 diff --git a/ROMFS/px4fmu_common/init.d/airframes/13004_quad+_tailsitter b/ROMFS/px4fmu_common/init.d/airframes/13004_quad+_tailsitter index 8b744eb508..8a77cf0d17 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/13004_quad+_tailsitter +++ b/ROMFS/px4fmu_common/init.d/airframes/13004_quad+_tailsitter @@ -25,8 +25,8 @@ if [ $AUTOCNF = yes ] then - param set PWM_MAX 2000 - param set PWM_RATE 400 + param set PWM_MAIN_MAX 2000 + param set PWM_MAIN_RATE 400 param set VT_IDLE_PWM_MC 1080 param set VT_TYPE 0 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 7897374264..112b539f9e 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/13005_vtol_AAERT_quad +++ b/ROMFS/px4fmu_common/init.d/airframes/13005_vtol_AAERT_quad @@ -28,7 +28,7 @@ if [ $AUTOCNF = yes ] then param set PWM_AUX_DIS5 950 - param set PWM_RATE 400 + param set PWM_MAIN_RATE 400 param set MC_ROLL_P 6 param set MC_ROLLRATE_P 0.17 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 e7957724ed..30933013fa 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/13006_vtol_standard_delta +++ b/ROMFS/px4fmu_common/init.d/airframes/13006_vtol_standard_delta @@ -47,7 +47,7 @@ then param set MPC_YAWRAUTO_MAX 20 param set PWM_AUX_DIS3 950 - param set PWM_RATE 400 + param set PWM_MAIN_RATE 400 param set VT_MOT_ID 1234 param set VT_FW_MOT_OFFID 1234 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 6d890eea4d..778bd798c6 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/13007_vtol_AAVVT_quad +++ b/ROMFS/px4fmu_common/init.d/airframes/13007_vtol_AAVVT_quad @@ -36,7 +36,7 @@ then param set MPC_YAWRAUTO_MAX 40 param set PWM_AUX_DIS5 950 - param set PWM_RATE 400 + param set PWM_MAIN_RATE 400 param set VT_F_TRANS_THR 0.75 param set VT_MOT_ID 1234 diff --git a/ROMFS/px4fmu_common/init.d/airframes/13008_QuadRanger b/ROMFS/px4fmu_common/init.d/airframes/13008_QuadRanger index 2d3b54e746..ed33d7cc7d 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/13008_QuadRanger +++ b/ROMFS/px4fmu_common/init.d/airframes/13008_QuadRanger @@ -50,7 +50,7 @@ then param set PWM_AUX_DIS5 950 param set PWM_AUX_REV1 1 param set PWM_AUX_REV2 1 - param set PWM_RATE 400 + param set PWM_MAIN_RATE 400 param set VT_ARSP_TRANS 15 param set VT_ARSP_BLEND 8 diff --git a/ROMFS/px4fmu_common/init.d/airframes/13009_vtol_spt_ranger b/ROMFS/px4fmu_common/init.d/airframes/13009_vtol_spt_ranger index 4a234eadef..4892c292f9 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/13009_vtol_spt_ranger +++ b/ROMFS/px4fmu_common/init.d/airframes/13009_vtol_spt_ranger @@ -70,7 +70,7 @@ then param set PWM_AUX_DIS5 950 - param set PWM_RATE 400 + param set PWM_MAIN_RATE 400 param set VT_ARSP_TRANS 15 param set VT_B_TRANS_DUR 4 diff --git a/ROMFS/px4fmu_common/init.d/airframes/13010_claire b/ROMFS/px4fmu_common/init.d/airframes/13010_claire index 630a795383..0b8eaf0245 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/13010_claire +++ b/ROMFS/px4fmu_common/init.d/airframes/13010_claire @@ -21,8 +21,8 @@ then param set PWM_AUX_MIN 1000 param set PWM_AUX_RATE 50 - param set PWM_MAX 2000 - param set PWM_RATE 400 + param set PWM_MAIN_MAX 2000 + param set PWM_MAIN_RATE 400 param set VT_MOT_ID 1234 param set VT_FW_MOT_OFFID 13 diff --git a/ROMFS/px4fmu_common/init.d/airframes/13012_convergence b/ROMFS/px4fmu_common/init.d/airframes/13012_convergence index 06f64c6a85..b3a26c1b56 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/13012_convergence +++ b/ROMFS/px4fmu_common/init.d/airframes/13012_convergence @@ -61,7 +61,7 @@ then param set MPC_TKO_SPEED 2.5 param set MPC_Z_VEL_MAX_UP 3 - param set PWM_RATE 400 + param set PWM_MAIN_RATE 400 param set SENS_BOARD_ROT 8 diff --git a/ROMFS/px4fmu_common/init.d/airframes/13013_deltaquad b/ROMFS/px4fmu_common/init.d/airframes/13013_deltaquad index 68f70ecbcf..7bb7a3252e 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/13013_deltaquad +++ b/ROMFS/px4fmu_common/init.d/airframes/13013_deltaquad @@ -122,7 +122,7 @@ then param set PWM_MAIN_DIS7 900 param set PWM_MAIN_DIS8 900 - param set PWM_RATE 400 + param set PWM_MAIN_RATE 400 param set SENS_BOARD_ROT 18 diff --git a/ROMFS/px4fmu_common/init.d/airframes/13014_vtol_babyshark b/ROMFS/px4fmu_common/init.d/airframes/13014_vtol_babyshark index 4a9e0e636f..224994c462 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/13014_vtol_babyshark +++ b/ROMFS/px4fmu_common/init.d/airframes/13014_vtol_babyshark @@ -90,7 +90,7 @@ then param set PWM_MAIN_DIS3 1000 param set PWM_MAIN_MIN3 1120 - param set PWM_MIN 950 + param set PWM_MAIN_MIN 950 param set SENS_BOARD_ROT 4 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 2293d34398..497936162c 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/13050_generic_vtol_octo +++ b/ROMFS/px4fmu_common/init.d/airframes/13050_generic_vtol_octo @@ -29,7 +29,7 @@ if [ $AUTOCNF = yes ] then param set PWM_AUX_DIS5 950 - param set PWM_RATE 400 + param set PWM_MAIN_RATE 400 param set VT_TYPE 2 param set VT_MOT_ID 12345678 diff --git a/ROMFS/px4fmu_common/init.d/airframes/15001_coax_heli b/ROMFS/px4fmu_common/init.d/airframes/15001_coax_heli index 5191b34f5b..7b05fbf986 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/15001_coax_heli +++ b/ROMFS/px4fmu_common/init.d/airframes/15001_coax_heli @@ -41,10 +41,10 @@ then param set NAV_ACC_RAD 2 param set PWM_AUX_RATE 50 - param set PWM_DISARMED 900 - param set PWM_MIN 1075 - param set PWM_MAX 1950 - param set PWM_RATE 400 + param set PWM_MAIN_DISARM 900 + param set PWM_MAIN_MIN 1075 + param set PWM_MAIN_MAX 1950 + param set PWM_MAIN_RATE 400 param set RTL_RETURN_ALT 30 param set RTL_DESCEND_ALT 10 diff --git a/ROMFS/px4fmu_common/init.d/airframes/16001_helicopter b/ROMFS/px4fmu_common/init.d/airframes/16001_helicopter index 02e217d66e..d22d4d21bf 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/16001_helicopter +++ b/ROMFS/px4fmu_common/init.d/airframes/16001_helicopter @@ -56,5 +56,5 @@ then param set MPC_THR_MIN 0.06 param set MPC_MANTHR_MIN 0.06 - param set PWM_MIN 1075 + param set PWM_MAIN_MIN 1075 fi diff --git a/ROMFS/px4fmu_common/init.d/airframes/17002_TF-AutoG2 b/ROMFS/px4fmu_common/init.d/airframes/17002_TF-AutoG2 index b6db51403d..3887d288b2 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/17002_TF-AutoG2 +++ b/ROMFS/px4fmu_common/init.d/airframes/17002_TF-AutoG2 @@ -32,7 +32,7 @@ then param set BAT_N_CELLS 3 param set PWM_AUX_RATE 50 - param set PWM_RATE 50 + param set PWM_MAIN_RATE 50 param set SENS_BOARD_ROT 8 diff --git a/ROMFS/px4fmu_common/init.d/airframes/17003_TF-G2 b/ROMFS/px4fmu_common/init.d/airframes/17003_TF-G2 index 328b180b30..0b9a95ab8f 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/17003_TF-G2 +++ b/ROMFS/px4fmu_common/init.d/airframes/17003_TF-G2 @@ -27,7 +27,7 @@ then param set BAT_N_CELLS 3 param set PWM_AUX_RATE 50 - param set PWM_RATE 50 + param set PWM_MAIN_RATE 50 param set SENS_BOARD_ROT 4 diff --git a/ROMFS/px4fmu_common/init.d/airframes/2100_standard_plane b/ROMFS/px4fmu_common/init.d/airframes/2100_standard_plane index 9a5346797b..a30883c1e0 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/2100_standard_plane +++ b/ROMFS/px4fmu_common/init.d/airframes/2100_standard_plane @@ -27,7 +27,7 @@ if [ $AUTOCNF = yes ] then param set PWM_AUX_RATE 50 - param set PWM_RATE 50 + param set PWM_MAIN_RATE 50 fi set MIXER AETRFG diff --git a/ROMFS/px4fmu_common/init.d/airframes/2105_maja b/ROMFS/px4fmu_common/init.d/airframes/2105_maja index 8c60637989..24458feac8 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/2105_maja +++ b/ROMFS/px4fmu_common/init.d/airframes/2105_maja @@ -43,7 +43,7 @@ then param set FW_W_RMAX 0 # set disarmed value for the ESC - param set PWM_DISARMED 1000 + param set PWM_MAIN_DISARM 1000 fi set MIXER AAERTWF diff --git a/ROMFS/px4fmu_common/init.d/airframes/2106_albatross b/ROMFS/px4fmu_common/init.d/airframes/2106_albatross index 074ceb1e82..19c8bab4e2 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/2106_albatross +++ b/ROMFS/px4fmu_common/init.d/airframes/2106_albatross @@ -43,7 +43,7 @@ then param set FW_W_RMAX 0 # set disarmed value for the ESC - param set PWM_DISARMED 1000 + param set PWM_MAIN_DISARM 1000 fi set MIXER AAVVTWFF diff --git a/ROMFS/px4fmu_common/init.d/airframes/2200_mini_talon b/ROMFS/px4fmu_common/init.d/airframes/2200_mini_talon index d7c1f6d402..b02c794583 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/2200_mini_talon +++ b/ROMFS/px4fmu_common/init.d/airframes/2200_mini_talon @@ -44,7 +44,7 @@ then param set FW_W_RMAX 0 # set disarmed value for the ESC - param set PWM_DISARMED 1000 + param set PWM_MAIN_DISARM 1000 fi # The Mini Talon does not have a wheel and diff --git a/ROMFS/px4fmu_common/init.d/airframes/24001_dodeca_cox b/ROMFS/px4fmu_common/init.d/airframes/24001_dodeca_cox index 243b11c107..c7e71a7ce4 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/24001_dodeca_cox +++ b/ROMFS/px4fmu_common/init.d/airframes/24001_dodeca_cox @@ -37,9 +37,9 @@ then param set PWM_AUX_MIN 1075 param set PWM_AUX_MAX 1950 - param set PWM_MIN 1075 - param set PWM_MAX 1950 - param set PWM_RATE 400 + param set PWM_MAIN_MIN 1075 + param set PWM_MAIN_MAX 1950 + param set PWM_MAIN_RATE 400 param set RTL_DESCEND_ALT 10 param set RTL_RETURN_ALT 30 diff --git a/ROMFS/px4fmu_common/init.d/airframes/3030_io_camflyer b/ROMFS/px4fmu_common/init.d/airframes/3030_io_camflyer index fb32401de2..bc38a74319 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/3030_io_camflyer +++ b/ROMFS/px4fmu_common/init.d/airframes/3030_io_camflyer @@ -44,7 +44,7 @@ then param set FW_RR_IMAX 0.2 param set FW_RR_P 0.04 - param set PWM_DISARMED 1000 + param set PWM_MAIN_DISARM 1000 fi set MIXER fw_generic_wing diff --git a/ROMFS/px4fmu_common/init.d/airframes/3031_phantom b/ROMFS/px4fmu_common/init.d/airframes/3031_phantom index 45c4e7b74b..38907b090b 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/3031_phantom +++ b/ROMFS/px4fmu_common/init.d/airframes/3031_phantom @@ -45,7 +45,7 @@ then param set FW_R_LIM 50 param set FW_R_RMAX 50 - param set PWM_DISARMED 1000 + param set PWM_MAIN_DISARM 1000 # Bottom of bay and nominal zero-pitch attitude differ # the payload bay is pitched up about 7 degrees diff --git a/ROMFS/px4fmu_common/init.d/airframes/3033_wingwing b/ROMFS/px4fmu_common/init.d/airframes/3033_wingwing index f6e67213f9..a7c71e0e62 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/3033_wingwing +++ b/ROMFS/px4fmu_common/init.d/airframes/3033_wingwing @@ -44,7 +44,7 @@ then param set FW_RR_FF 0.6 param set FW_RR_P 0.04 - param set PWM_DISARMED 1000 + param set PWM_MAIN_DISARM 1000 fi # Configure this as plane. diff --git a/ROMFS/px4fmu_common/init.d/airframes/3036_pigeon b/ROMFS/px4fmu_common/init.d/airframes/3036_pigeon index e5bf662cfb..ddd75b6882 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/3036_pigeon +++ b/ROMFS/px4fmu_common/init.d/airframes/3036_pigeon @@ -45,7 +45,7 @@ then param set FW_R_RMAX 50 param set FW_R_TC 0.3 - param set PWM_DISARMED 1000 + param set PWM_MAIN_DISARM 1000 # Bottom of bay and nominal zero-pitch attitude differ # the payload bay is pitched up about 7 degrees 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 7105193779..26f9c22fe8 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/3037_parrot_disco_mod +++ b/ROMFS/px4fmu_common/init.d/airframes/3037_parrot_disco_mod @@ -85,7 +85,7 @@ then # Roll Integrator Anti-Windup param set FW_RR_IMAX 0.2 - param set PWM_DISARMED 1000 + param set PWM_MAIN_DISARM 1000 fi set MIXER fw_generic_wing.main.mix diff --git a/ROMFS/px4fmu_common/init.d/airframes/3100_tbs_caipirinha b/ROMFS/px4fmu_common/init.d/airframes/3100_tbs_caipirinha index 1ccee1c144..7482a9c015 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/3100_tbs_caipirinha +++ b/ROMFS/px4fmu_common/init.d/airframes/3100_tbs_caipirinha @@ -61,8 +61,8 @@ then param set PWM_MAIN_REV1 1 param set PWM_MAIN_REV2 1 - param set PWM_MIN 900 - param set PWM_MAX 2100 + param set PWM_MAIN_MIN 900 + param set PWM_MAIN_MAX 2100 fi set MIXER caipi diff --git a/ROMFS/px4fmu_common/init.d/airframes/4003_qavr5 b/ROMFS/px4fmu_common/init.d/airframes/4003_qavr5 index a7c5c6d6cd..c4c2ccc9cf 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4003_qavr5 +++ b/ROMFS/px4fmu_common/init.d/airframes/4003_qavr5 @@ -34,5 +34,5 @@ then param set MPC_THR_MIN 0.06 param set MPC_MANTHR_MIN 0.06 - param set PWM_MIN 1075 + param set PWM_MAIN_MIN 1075 fi diff --git a/ROMFS/px4fmu_common/init.d/airframes/4009_qav250 b/ROMFS/px4fmu_common/init.d/airframes/4009_qav250 index 02f2c8be0a..66a9c56fe8 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4009_qav250 +++ b/ROMFS/px4fmu_common/init.d/airframes/4009_qav250 @@ -37,5 +37,5 @@ then param set MC_YAWRATE_D 0 param set MPC_THR_MIN 0.06 - param set PWM_MIN 1075 + param set PWM_MAIN_MIN 1075 fi diff --git a/ROMFS/px4fmu_common/init.d/airframes/4010_dji_f330 b/ROMFS/px4fmu_common/init.d/airframes/4010_dji_f330 index 6fd2e0d802..e82faa6b5c 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4010_dji_f330 +++ b/ROMFS/px4fmu_common/init.d/airframes/4010_dji_f330 @@ -29,5 +29,5 @@ then param set MC_YAWRATE_D 0 # DJI ESCs do not support calibration and need a higher min - param set PWM_MIN 1230 + param set PWM_MAIN_MIN 1230 fi diff --git a/ROMFS/px4fmu_common/init.d/airframes/4011_dji_f450 b/ROMFS/px4fmu_common/init.d/airframes/4011_dji_f450 index 463b39d8f3..5e8d318a45 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4011_dji_f450 +++ b/ROMFS/px4fmu_common/init.d/airframes/4011_dji_f450 @@ -29,5 +29,5 @@ then param set MC_YAWRATE_D 0 # DJI ESCs do not support calibration and need a higher min - param set PWM_MIN 1230 + param set PWM_MAIN_MIN 1230 fi diff --git a/ROMFS/px4fmu_common/init.d/airframes/4016_holybro_px4vision b/ROMFS/px4fmu_common/init.d/airframes/4016_holybro_px4vision index d4eaf2a540..7e5ddeb2c3 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4016_holybro_px4vision +++ b/ROMFS/px4fmu_common/init.d/airframes/4016_holybro_px4vision @@ -104,11 +104,11 @@ then param set NAV_ACC_RAD 2 # PWM and RC Parameters - param set PWM_MAX 1950 - param set PWM_MIN 1075 + param set PWM_MAIN_MAX 1950 + param set PWM_MAIN_MIN 1075 # use oneshot motor output protocol - param set PWM_RATE 0 + param set PWM_MAIN_RATE 0 # RTL Parameters param set RTL_DESCEND_ALT 5 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 d59650c80f..46d0fffa85 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4020_hk_micro_pcb +++ b/ROMFS/px4fmu_common/init.d/airframes/4020_hk_micro_pcb @@ -37,5 +37,5 @@ then param set MC_YAWRATE_I 0.1 param set MC_YAWRATE_D 0 - param set PWM_MIN 1200 + param set PWM_MAIN_MIN 1200 fi diff --git a/ROMFS/px4fmu_common/init.d/airframes/4040_reaper b/ROMFS/px4fmu_common/init.d/airframes/4040_reaper index 474c4123bb..e8cd64dfb1 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4040_reaper +++ b/ROMFS/px4fmu_common/init.d/airframes/4040_reaper @@ -37,9 +37,9 @@ then param set PWM_AUX_DISARMED 950 param set PWM_AUX_RATE 50 - param set PWM_MIN 1100 - param set PWM_MAX 1900 - param set PWM_RATE 50 + param set PWM_MAIN_MIN 1100 + param set PWM_MAIN_MAX 1900 + param set PWM_MAIN_RATE 50 param set RTL_RETURN_ALT 30 param set RTL_DESCEND_ALT 10 diff --git a/ROMFS/px4fmu_common/init.d/airframes/4050_generic_250 b/ROMFS/px4fmu_common/init.d/airframes/4050_generic_250 index 963fe986c4..0cfe7ae48f 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4050_generic_250 +++ b/ROMFS/px4fmu_common/init.d/airframes/4050_generic_250 @@ -41,9 +41,9 @@ then # use thrust curve factor (instead of TPA) param set THR_MDL_FAC 0.3 - param set PWM_MIN 1075 + param set PWM_MAIN_MIN 1075 # enable one-shot - param set PWM_RATE 0 + param set PWM_MAIN_RATE 0 # enable high-rate logging profile (helps with tuning) param set SDLOG_PROFILE 19 diff --git a/ROMFS/px4fmu_common/init.d/airframes/4051_s250aq b/ROMFS/px4fmu_common/init.d/airframes/4051_s250aq index 40d4614644..5b648850ba 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4051_s250aq +++ b/ROMFS/px4fmu_common/init.d/airframes/4051_s250aq @@ -55,5 +55,5 @@ then param set MPC_THR_MIN 0.06 param set MPC_MANTHR_MIN 0.06 - param set PWM_MIN 1075 + param set PWM_MAIN_MIN 1075 fi diff --git a/ROMFS/px4fmu_common/init.d/airframes/4052_holybro_qav250 b/ROMFS/px4fmu_common/init.d/airframes/4052_holybro_qav250 index 1a7b4d924c..e2b033f9b0 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4052_holybro_qav250 +++ b/ROMFS/px4fmu_common/init.d/airframes/4052_holybro_qav250 @@ -50,10 +50,10 @@ then param set MPC_THR_MIN 0.05 param set MPC_Z_VEL_I_ACC 1.7 - param set PWM_MAX 1950 - param set PWM_MIN 1050 + param set PWM_MAIN_MAX 1950 + param set PWM_MAIN_MIN 1050 - param set PWM_RATE 0 + param set PWM_MAIN_RATE 0 param set THR_MDL_FAC 0.3 fi 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 72b220ff52..f240de6b8c 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4060_dji_matrice_100 +++ b/ROMFS/px4fmu_common/init.d/airframes/4060_dji_matrice_100 @@ -33,5 +33,5 @@ then param set MC_YAWRATE_I 0 param set MC_YAWRATE_D 0 - param set PWM_MIN 1200 + param set PWM_MAIN_MIN 1200 fi diff --git a/ROMFS/px4fmu_common/init.d/airframes/4071_ifo b/ROMFS/px4fmu_common/init.d/airframes/4071_ifo index d82ee30e9f..f6356d7d0f 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4071_ifo +++ b/ROMFS/px4fmu_common/init.d/airframes/4071_ifo @@ -65,9 +65,9 @@ then #param set THR_MDL_FAC 0.25 # System - param set PWM_MAX 1950 - param set PWM_MIN 1100 - param set PWM_RATE 0 + param set PWM_MAIN_MAX 1950 + param set PWM_MAIN_MIN 1100 + param set PWM_MAIN_RATE 0 #param set SYS_FMU_TASK 1 param set SENS_BOARD_ROT 10 diff --git a/ROMFS/px4fmu_common/init.d/airframes/4072_draco b/ROMFS/px4fmu_common/init.d/airframes/4072_draco index 4541937873..8a8def2c0b 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4072_draco +++ b/ROMFS/px4fmu_common/init.d/airframes/4072_draco @@ -67,11 +67,11 @@ then param set THR_MDL_FAC 0.3 # System - param set PWM_MAX 1950 - param set PWM_MIN 1180 + param set PWM_MAIN_MAX 1950 + param set PWM_MAIN_MIN 1180 # enable one-shot - param set PWM_RATE 0 + param set PWM_MAIN_RATE 0 param set 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 fefc1c02ad..e2f4ce70b7 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4073_ifo-s +++ b/ROMFS/px4fmu_common/init.d/airframes/4073_ifo-s @@ -61,9 +61,9 @@ then #param set THR_MDL_FAC 0.25 # Obsolete - #param set PWM_MAX 1950 - #param set PWM_MIN 1100 - #param set PWM_RATE 0 + #param set PWM_MAIN_MAX 1950 + #param set PWM_MAIN_MIN 1100 + #param set PWM_MAIN_RATE 0 # Sensors param set SENS_BOARD_ROT 10 diff --git a/ROMFS/px4fmu_common/init.d/airframes/4080_zmr250 b/ROMFS/px4fmu_common/init.d/airframes/4080_zmr250 index 71f15a6154..771f0489d1 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4080_zmr250 +++ b/ROMFS/px4fmu_common/init.d/airframes/4080_zmr250 @@ -42,7 +42,7 @@ then # param set NAV_RCL_ACT 6 # Lockdown - param set PWM_MIN 1075 - param set PWM_RATE 400 - param set PWM_DISARMED 900 + param set PWM_MAIN_MIN 1075 + param set PWM_MAIN_RATE 400 + param set PWM_MAIN_DISARM 900 fi diff --git a/ROMFS/px4fmu_common/init.d/airframes/4090_nanomind b/ROMFS/px4fmu_common/init.d/airframes/4090_nanomind index ed075cd2d2..e5947e78cc 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4090_nanomind +++ b/ROMFS/px4fmu_common/init.d/airframes/4090_nanomind @@ -38,7 +38,7 @@ then param set MC_YAWRATE_I 0.1 param set MC_YAWRATE_D 0 - param set PWM_DISARMED 0 - param set PWM_MIN 500 - param set PWM_MAX 2200 + param set PWM_MAIN_DISARM 0 + param set PWM_MAIN_MIN 500 + param set PWM_MAIN_MAX 2200 fi diff --git a/ROMFS/px4fmu_common/init.d/airframes/4250_teal b/ROMFS/px4fmu_common/init.d/airframes/4250_teal index ae1c9de06e..a84d950a84 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4250_teal +++ b/ROMFS/px4fmu_common/init.d/airframes/4250_teal @@ -171,11 +171,11 @@ then param set NAV_RCL_ACT 1 # pwm control - param set PWM_DISARMED 900 - param set PWM_MAX 1850 - param set PWM_MIN 1075 + param set PWM_MAIN_DISARM 900 + param set PWM_MAIN_MAX 1850 + param set PWM_MAIN_MIN 1075 # Oneshot125 - param set PWM_RATE 0 + param set PWM_MAIN_RATE 0 # rtl param set RTL_DESCEND_ALT 5 diff --git a/ROMFS/px4fmu_common/init.d/airframes/4900_crazyflie b/ROMFS/px4fmu_common/init.d/airframes/4900_crazyflie index 4b8b45bb1e..57dc6d7848 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4900_crazyflie +++ b/ROMFS/px4fmu_common/init.d/airframes/4900_crazyflie @@ -60,12 +60,12 @@ then param set NAV_RCL_ACT 3 - param set PWM_DISARMED 0 - param set PWM_MIN 0 - param set PWM_MAX 255 + param set PWM_MAIN_DISARM 0 + param set PWM_MAIN_MIN 0 + param set PWM_MAIN_MAX 255 # Run the motors at 328.125 kHz (recommended) - param set PWM_RATE 3921 + param set PWM_MAIN_RATE 3921 param set SDLOG_PROFILE 1 @@ -73,9 +73,9 @@ then fi -set PWM_DISARMED none -set PWM_MAX none -set PWM_MIN none +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 968f1f6a76..2435312c19 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4901_crazyflie21 +++ b/ROMFS/px4fmu_common/init.d/airframes/4901_crazyflie21 @@ -59,12 +59,12 @@ then param set NAV_RCL_ACT 3 - param set PWM_DISARMED 0 - param set PWM_MIN 0 - param set PWM_MAX 255 + param set PWM_MAIN_DISARM 0 + param set PWM_MAIN_MIN 0 + param set PWM_MAIN_MAX 255 # Run the motors at 328.125 kHz (recommended) - param set PWM_RATE 3921 + param set PWM_MAIN_RATE 3921 param set SDLOG_PROFILE 1 @@ -73,9 +73,9 @@ then fi -set PWM_DISARMED none -set PWM_MAX none -set PWM_MIN none +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 18518915d7..db15429244 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/50000_generic_ground_vehicle +++ b/ROMFS/px4fmu_common/init.d/airframes/50000_generic_ground_vehicle @@ -50,9 +50,9 @@ then param set NAV_ACC_RAD 0.5 # Provide ESC a constant 1500 us pulse - param set PWM_DISARMED 1500 - param set PWM_MAX 2000 - param set PWM_MIN 1000 + param set PWM_MAIN_DISARM 1500 + param set PWM_MAIN_MAX 2000 + param set PWM_MAIN_MIN 1000 fi # Configure this as rover 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 2abf85c25f..7ab3d3df6a 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 @@ -62,11 +62,11 @@ then # Provide ESC a constant 1500 us pulse, which corresponds to # idle on the Roboclaw motor controller on the Aion R1 - param set PWM_DISARMED 1500 + param set PWM_MAIN_DISARM 1500 param set PWM_MAIN_DIS0 1500 param set PWM_MAIN_DIS1 1500 - param set PWM_MAX 2000 - param set PWM_MIN 1000 + param set PWM_MAIN_MAX 2000 + param set PWM_MAIN_MIN 1000 # Enable Airspeed check circuit breaker because Rovers will have no airspeed sensor param set CBRK_AIRSPD_CHK 162128 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 2ef1b50588..472334f0b0 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 @@ -56,13 +56,13 @@ then param set NAV_ACC_RAD 0.5 # Provide ESC a constant 1500 us pulse to idle - param set PWM_DISARMED 1500 + param set PWM_MAIN_DISARM 1500 param set PWM_MAIN_DIS3 1485 param set PWM_MAIN_DIS4 1485 param set PWM_MAIN_FAIL3 1485 param set PWM_MAIN_FAIL4 1485 - param set PWM_MAX 2000 - param set PWM_MIN 1000 + param set PWM_MAIN_MAX 2000 + param set PWM_MAIN_MIN 1000 param set PWM_MAIN_MIN3 970 param set PWM_MAIN_MIN4 970 diff --git a/ROMFS/px4fmu_common/init.d/airframes/6002_draco_r b/ROMFS/px4fmu_common/init.d/airframes/6002_draco_r index 20e8a5ce33..e4e2eae66d 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/6002_draco_r +++ b/ROMFS/px4fmu_common/init.d/airframes/6002_draco_r @@ -83,8 +83,8 @@ then param set THR_MDL_FAC 0.25 # System - param set PWM_MAX 1950 - param set PWM_MIN 1100 + param set PWM_MAIN_MAX 1950 + param set PWM_MAIN_MIN 1100 param set PWM_MAIN_DIS5 980 param set PWM_MAIN_DIS6 980 @@ -115,7 +115,7 @@ then param set COM_DISARM_LAND 3 # PWM ONESHOT - param set PWM_RATE 0 + param set PWM_MAIN_RATE 0 # Battery param set BAT_SOURCE 0 diff --git a/ROMFS/px4fmu_common/init.d/rc.boat_defaults b/ROMFS/px4fmu_common/init.d/rc.boat_defaults index 5c8e952bc9..237aac9546 100644 --- a/ROMFS/px4fmu_common/init.d/rc.boat_defaults +++ b/ROMFS/px4fmu_common/init.d/rc.boat_defaults @@ -33,7 +33,7 @@ set PWM_OUT 1234 # PWM Hz - 50 Hz is the normal rate in RC cars, higher rates # may damage analog servos. # -set PWM_RATE 50 +set PWM_MAIN_RATE 50 # # This is the gimbal pass mixer. diff --git a/ROMFS/px4fmu_common/init.d/rc.fw_defaults b/ROMFS/px4fmu_common/init.d/rc.fw_defaults index aacd9ffa8d..8e12dbb61d 100644 --- a/ROMFS/px4fmu_common/init.d/rc.fw_defaults +++ b/ROMFS/px4fmu_common/init.d/rc.fw_defaults @@ -45,7 +45,7 @@ then param set MIS_LTRMIN_ALT 25 param set MIS_TAKEOFF_ALT 25 - param set PWM_RATE 50 + param set PWM_MAIN_RATE 50 # # FW takeoff acceleration can easily exceed ublox GPS 2G default. diff --git a/ROMFS/px4fmu_common/init.d/rc.interface b/ROMFS/px4fmu_common/init.d/rc.interface index 7e597fdb31..61a096dc5d 100644 --- a/ROMFS/px4fmu_common/init.d/rc.interface +++ b/ROMFS/px4fmu_common/init.d/rc.interface @@ -254,9 +254,9 @@ then if [ $PWM_OUT != none ] then # Set PWM output frequency. - if [ $PWM_RATE != none ] + if [ $PWM_MAIN_RATE != none ] then - pwm rate -c ${PWM_OUT} -r ${PWM_RATE} + pwm rate -c ${PWM_OUT} -r ${PWM_MAIN_RATE} fi fi fi diff --git a/ROMFS/px4fmu_common/init.d/rc.mc_defaults b/ROMFS/px4fmu_common/init.d/rc.mc_defaults index 362cf60c05..7baf262862 100644 --- a/ROMFS/px4fmu_common/init.d/rc.mc_defaults +++ b/ROMFS/px4fmu_common/init.d/rc.mc_defaults @@ -14,9 +14,9 @@ then param set RTL_RETURN_ALT 30 param set RTL_DESCEND_ALT 10 - param set PWM_MAX 1950 - param set PWM_MIN 1075 - param set PWM_RATE 400 + param set PWM_MAIN_MAX 1950 + param set PWM_MAIN_MIN 1075 + param set PWM_MAIN_RATE 400 param set GPS_UBX_DYNMODEL 6 fi diff --git a/ROMFS/px4fmu_common/init.d/rc.rover_defaults b/ROMFS/px4fmu_common/init.d/rc.rover_defaults index 5c8e952bc9..237aac9546 100644 --- a/ROMFS/px4fmu_common/init.d/rc.rover_defaults +++ b/ROMFS/px4fmu_common/init.d/rc.rover_defaults @@ -33,7 +33,7 @@ set PWM_OUT 1234 # PWM Hz - 50 Hz is the normal rate in RC cars, higher rates # may damage analog servos. # -set PWM_RATE 50 +set PWM_MAIN_RATE 50 # # This is the gimbal pass mixer. diff --git a/ROMFS/px4fmu_common/init.d/rc.uuv_defaults b/ROMFS/px4fmu_common/init.d/rc.uuv_defaults index 804e41e3f1..600eabef49 100644 --- a/ROMFS/px4fmu_common/init.d/rc.uuv_defaults +++ b/ROMFS/px4fmu_common/init.d/rc.uuv_defaults @@ -9,9 +9,9 @@ set VEHICLE_TYPE uuv if [ $AUTOCNF = yes ] then - param set PWM_MAX 1950 - param set PWM_MIN 1050 - param set PWM_DISARMED 1500 + param set PWM_MAIN_MAX 1950 + param set PWM_MAIN_MIN 1050 + param set PWM_MAIN_DISARM 1500 fi @@ -19,13 +19,11 @@ fi # PWM Hz - 50 Hz is the normal rate in RC cars, boats etc, # higher rates may damage analog servos. # -set PWM_RATE 50 +set PWM_MAIN_RATE 50 # # Enable servo output on pins 1-4 set PWM_OUT 1234 -set PWM_DISARMED 1500 - # # This is the gimbal pass mixer. diff --git a/ROMFS/px4fmu_common/init.d/rc.vtol_defaults b/ROMFS/px4fmu_common/init.d/rc.vtol_defaults index 9517b77a24..663c57997b 100644 --- a/ROMFS/px4fmu_common/init.d/rc.vtol_defaults +++ b/ROMFS/px4fmu_common/init.d/rc.vtol_defaults @@ -31,7 +31,7 @@ then param set NAV_ACC_RAD 3 param set PWM_AUX_RATE 50 - param set PWM_RATE 400 + param set PWM_MAIN_RATE 400 param set RTL_TYPE 1 diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS index ebb4262162..c8960c08b0 100644 --- a/ROMFS/px4fmu_common/init.d/rcS +++ b/ROMFS/px4fmu_common/init.d/rcS @@ -41,19 +41,10 @@ set MK_MODE none set MKBLCTRL_ARG "" set OUTPUT_MODE none set PARAM_FILE /fs/microsd/params -set PWM_DISARMED p:PWM_DISARMED -set PWM_MAX p:PWM_MAX -set PWM_MIN p:PWM_MIN set PWM_OUT none -set PWM_RATE p:PWM_RATE -set PWM_AUX_DISARMED p:PWM_AUX_DISARMED -set PWM_AUX_MAX p:PWM_AUX_MAX -set PWM_AUX_MIN p:PWM_AUX_MIN +set PWM_MAIN_RATE p:PWM_MAIN_RATE set PWM_AUX_OUT none set PWM_AUX_RATE p:PWM_AUX_RATE -set PWM_EXTRA_DISARMED p:PWM_EXTRA_DISARMED -set PWM_EXTRA_MAX p:PWM_EXTRA_MAX -set PWM_EXTRA_MIN p:PWM_EXTRA_MIN set PWM_EXTRA_OUT none set PWM_EXTRA_RATE p:PWM_EXTRA_RATE set EXTRA_MIXER_MODE none @@ -598,16 +589,12 @@ unset MKBLCTRL_ARG unset OUTPUT_MODE unset PARAM_DEFAULTS_VER unset PARAM_FILE -unset PWM_AUX_DISARMED -unset PWM_AUX_MAX -unset PWM_AUX_MIN unset PWM_AUX_OUT unset PWM_AUX_RATE -unset PWM_DISARMED -unset PWM_MAX -unset PWM_MIN +unset PWM_MAIN_RATE unset PWM_OUT -unset PWM_RATE +unset PWM_EXTRA_OUT +unset PWM_EXTRA_RATE unset RC_INPUT_ARGS unset SDCARD_MIXERS_PATH unset STARTUP_TUNE diff --git a/posix-configs/bbblue/px4.config b/posix-configs/bbblue/px4.config index afde6b6f66..ed127ef660 100644 --- a/posix-configs/bbblue/px4.config +++ b/posix-configs/bbblue/px4.config @@ -22,8 +22,8 @@ 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_MIN 1120 -# param set PWM_MAX 1920 +# 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 707dc9991c..11ec56d554 100644 --- a/posix-configs/bbblue/px4_fw.config +++ b/posix-configs/bbblue/px4_fw.config @@ -22,8 +22,8 @@ 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_MIN 1120 -# param set PWM_MAX 1920 +# 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/linux_pwm_out/linux_pwm_out.cpp b/src/drivers/linux_pwm_out/linux_pwm_out.cpp index ebf6d5c054..fd360187f6 100644 --- a/src/drivers/linux_pwm_out/linux_pwm_out.cpp +++ b/src/drivers/linux_pwm_out/linux_pwm_out.cpp @@ -559,9 +559,9 @@ int linux_pwm_out_main(int argc, char *argv[]) } /** gets the parameters for the esc's pwm */ - param_get(param_find("PWM_DISARMED"), &linux_pwm_out::_pwm_disarmed); - param_get(param_find("PWM_MIN"), &linux_pwm_out::_pwm_min); - param_get(param_find("PWM_MAX"), &linux_pwm_out::_pwm_max); + param_get(param_find("PWM_MAIN_DISARM"), &linux_pwm_out::_pwm_disarmed); + param_get(param_find("PWM_MAIN_MIN"), &linux_pwm_out::_pwm_min); + param_get(param_find("PWM_MAIN_MAX"), &linux_pwm_out::_pwm_max); /* * Start/load the driver. diff --git a/src/drivers/pca9685_pwm_out/main.cpp b/src/drivers/pca9685_pwm_out/main.cpp index 6522bb3de9..cd4d2a7b28 100644 --- a/src/drivers/pca9685_pwm_out/main.cpp +++ b/src/drivers/pca9685_pwm_out/main.cpp @@ -185,25 +185,25 @@ void PCA9685Wrapper::updatePWMParams() default_pwm_fail = PWM_DEFAULT_MIN, default_pwm_dis = PWM_MOTOR_OFF; - param_t param_h = param_find("PWM_MAX"); + param_t param_h = param_find("PWM_MAIN_MAX"); if (param_h != PARAM_INVALID) { param_get(param_h, &default_pwm_max); } else { - PX4_DEBUG("PARAM_INVALID: %s", "PWM_MAX"); + PX4_DEBUG("PARAM_INVALID: %s", "PWM_MAIN_MAX"); } - param_h = param_find("PWM_MIN"); + param_h = param_find("PWM_MAIN_MIN"); if (param_h != PARAM_INVALID) { param_get(param_h, &default_pwm_min); } else { - PX4_DEBUG("PARAM_INVALID: %s", "PWM_MIN"); + PX4_DEBUG("PARAM_INVALID: %s", "PWM_MAIN_MIN"); } - param_h = param_find("PWM_RATE"); + param_h = param_find("PWM_MAIN_RATE"); if (param_h != PARAM_INVALID) { int32_t pval = 0; @@ -215,7 +215,7 @@ void PCA9685Wrapper::updatePWMParams() } } else { - PX4_DEBUG("PARAM_INVALID: %s", "PWM_RATE"); + PX4_DEBUG("PARAM_INVALID: %s", "PWM_MAIN_RATE"); } for (int i = 0; i < PCA9685_PWM_CHANNEL_COUNT; i++) { diff --git a/src/drivers/pwm_out/PWMOut.cpp b/src/drivers/pwm_out/PWMOut.cpp index e9241c751b..45f07466ae 100644 --- a/src/drivers/pwm_out/PWMOut.cpp +++ b/src/drivers/pwm_out/PWMOut.cpp @@ -572,17 +572,17 @@ void PWMOut::update_params() if (_class_instance == CLASS_DEVICE_PRIMARY) { prefix = "PWM_MAIN"; - param_get(param_find("PWM_MIN"), &pwm_min_default); - param_get(param_find("PWM_MAX"), &pwm_max_default); - param_get(param_find("PWM_DISARMED"), &pwm_disarmed_default); - param_get(param_find("PWM_RATE"), &pwm_rate_default); + 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_DISARMED"), &pwm_disarmed_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) { diff --git a/src/drivers/pwm_out/pwm_aux_params.yaml b/src/drivers/pwm_out/pwm_aux_params.yaml index 32e8cefe28..bb9d939d7c 100644 --- a/src/drivers/pwm_out/pwm_aux_params.yaml +++ b/src/drivers/pwm_out/pwm_aux_params.yaml @@ -40,7 +40,7 @@ parameters: max: 2200 default: 2000 - PWM_AUX_DISARMED: + PWM_AUX_DISARM: description: short: PWM aux disarmed value long: | diff --git a/src/drivers/pwm_out/pwm_main_params.yaml b/src/drivers/pwm_out/pwm_main_params.yaml index 28f5414dc0..d17dc69466 100644 --- a/src/drivers/pwm_out/pwm_main_params.yaml +++ b/src/drivers/pwm_out/pwm_main_params.yaml @@ -6,7 +6,7 @@ parameters: - group: PWM Outputs definitions: - PWM_RATE: + PWM_MAIN_RATE: description: short: PWM main output frequency long: | @@ -40,7 +40,7 @@ parameters: max: 2200 default: 2000 - PWM_DISARMED: + PWM_MAIN_DISARM: description: short: PWM main disarmed value long: | diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp index 9b8f837beb..370c0755f8 100644 --- a/src/drivers/px4io/px4io.cpp +++ b/src/drivers/px4io/px4io.cpp @@ -1206,10 +1206,10 @@ void PX4IO::update_params() const char *prefix = "PWM_MAIN"; - param_get(param_find("PWM_MIN"), &pwm_min_default); - param_get(param_find("PWM_MAX"), &pwm_max_default); - param_get(param_find("PWM_DISARMED"), &pwm_disarmed_default); - param_get(param_find("PWM_RATE"), &pwm_rate_default); + 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]; diff --git a/src/drivers/snapdragon_pwm_out/snapdragon_pwm_out.cpp b/src/drivers/snapdragon_pwm_out/snapdragon_pwm_out.cpp index 3eb739ed0f..883a94d8df 100644 --- a/src/drivers/snapdragon_pwm_out/snapdragon_pwm_out.cpp +++ b/src/drivers/snapdragon_pwm_out/snapdragon_pwm_out.cpp @@ -557,9 +557,9 @@ int snapdragon_pwm_out_main(int argc, char *argv[]) } // gets the parameters for the esc's pwm - param_get(param_find("PWM_DISARMED"), &snapdragon_pwm::_pwm_disarmed); - param_get(param_find("PWM_MIN"), &snapdragon_pwm::_pwm_min); - param_get(param_find("PWM_MAX"), &snapdragon_pwm::_pwm_max); + param_get(param_find("PWM_MAIN_DISARM"), &snapdragon_pwm::_pwm_disarmed); + param_get(param_find("PWM_MAIN_MIN"), &snapdragon_pwm::_pwm_min); + param_get(param_find("PWM_MAIN_MAX"), &snapdragon_pwm::_pwm_max); /* * Start/load the driver. diff --git a/src/lib/parameters/param_translation.cpp b/src/lib/parameters/param_translation.cpp index 3a5d9aae31..cc1621a4a1 100644 --- a/src/lib/parameters/param_translation.cpp +++ b/src/lib/parameters/param_translation.cpp @@ -141,6 +141,29 @@ 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"); + } + } + // translate (SPI) calibration ID parameters. This can be removed after the next release (current release=1.10) if (node->type != BSON_INT32) {