diff --git a/ROMFS/CMakeLists.txt b/ROMFS/CMakeLists.txt index d8ef8b9cda..1abd3505eb 100644 --- a/ROMFS/CMakeLists.txt +++ b/ROMFS/CMakeLists.txt @@ -172,12 +172,11 @@ set_target_properties(romfs PROPERTIES LINKER_LANGUAGE C) find_program(SHELLCHECK_PATH shellcheck) if(SHELLCHECK_PATH) - # TODO: fix SC2039, SC2086, SC2166 + # TODO: fix SC2086, SC2166 add_custom_target(shellcheck COMMAND ${SHELLCHECK_PATH} --shell=sh --exclude=SC2121 # SC2121: To assign a variable, use just 'var=value' --exclude=SC2086 # SC2086: Double quote to prevent globbing and word splitting. - --exclude=SC2039 # SC2039: In POSIX sh, == in place of = is undefined. --exclude=SC2166 # SC2166: Prefer [ p ] || [ q ] as [ p -o q ] is not well defined. --exclude=SC2154 # SC2154: is referenced but not assigned (NuttX uses different asssignment) init.d/* diff --git a/ROMFS/px4fmu_common/init.d/1000_rc_fw_easystar.hil b/ROMFS/px4fmu_common/init.d/1000_rc_fw_easystar.hil index 117b1b84a2..e9ea68b3f8 100644 --- a/ROMFS/px4fmu_common/init.d/1000_rc_fw_easystar.hil +++ b/ROMFS/px4fmu_common/init.d/1000_rc_fw_easystar.hil @@ -17,7 +17,7 @@ sh /etc/init.d/rc.fw_defaults -if [ $AUTOCNF == yes ] +if [ $AUTOCNF = yes ] then param set BAT_N_CELLS 3 diff --git a/ROMFS/px4fmu_common/init.d/10015_tbs_discovery b/ROMFS/px4fmu_common/init.d/10015_tbs_discovery index 77647e51eb..8c547882a6 100644 --- a/ROMFS/px4fmu_common/init.d/10015_tbs_discovery +++ b/ROMFS/px4fmu_common/init.d/10015_tbs_discovery @@ -22,7 +22,7 @@ sh /etc/init.d/rc.mc_defaults -if [ $AUTOCNF == yes ] +if [ $AUTOCNF = yes ] then param set MC_ROLL_P 6.5 param set MC_ROLLRATE_P 0.1 diff --git a/ROMFS/px4fmu_common/init.d/10016_3dr_iris b/ROMFS/px4fmu_common/init.d/10016_3dr_iris index 3ea7fead9f..e8aafe9c3c 100644 --- a/ROMFS/px4fmu_common/init.d/10016_3dr_iris +++ b/ROMFS/px4fmu_common/init.d/10016_3dr_iris @@ -20,7 +20,7 @@ sh /etc/init.d/rc.mc_defaults -if [ $AUTOCNF == yes ] +if [ $AUTOCNF = yes ] then # TODO tune roll/pitch separately param set MC_ROLL_P 7.0 diff --git a/ROMFS/px4fmu_common/init.d/10017_steadidrone_qu4d b/ROMFS/px4fmu_common/init.d/10017_steadidrone_qu4d index 8738498d4d..1a64d70e15 100644 --- a/ROMFS/px4fmu_common/init.d/10017_steadidrone_qu4d +++ b/ROMFS/px4fmu_common/init.d/10017_steadidrone_qu4d @@ -22,7 +22,7 @@ sh /etc/init.d/rc.mc_defaults -if [ $AUTOCNF == yes ] +if [ $AUTOCNF = yes ] then param set BAT_N_CELLS 4 diff --git a/ROMFS/px4fmu_common/init.d/10018_tbs_endurance b/ROMFS/px4fmu_common/init.d/10018_tbs_endurance index df8ee39c6c..d89aa15934 100644 --- a/ROMFS/px4fmu_common/init.d/10018_tbs_endurance +++ b/ROMFS/px4fmu_common/init.d/10018_tbs_endurance @@ -22,7 +22,7 @@ sh /etc/init.d/rc.mc_defaults -if [ $AUTOCNF == yes ] +if [ $AUTOCNF = yes ] then param set BAT_N_CELLS 6 param set BAT_V_EMPTY 3.5 diff --git a/ROMFS/px4fmu_common/init.d/1002_standard_vtol.hil b/ROMFS/px4fmu_common/init.d/1002_standard_vtol.hil index 9243736711..9944c893eb 100644 --- a/ROMFS/px4fmu_common/init.d/1002_standard_vtol.hil +++ b/ROMFS/px4fmu_common/init.d/1002_standard_vtol.hil @@ -10,7 +10,7 @@ sh /etc/init.d/rc.vtol_defaults -if [ $AUTOCNF == yes ] +if [ $AUTOCNF = yes ] then param set BAT_N_CELLS 3 diff --git a/ROMFS/px4fmu_common/init.d/12002_steadidrone_mavrik b/ROMFS/px4fmu_common/init.d/12002_steadidrone_mavrik index 2be4f39005..ae9ffc90f4 100644 --- a/ROMFS/px4fmu_common/init.d/12002_steadidrone_mavrik +++ b/ROMFS/px4fmu_common/init.d/12002_steadidrone_mavrik @@ -19,7 +19,7 @@ sh /etc/init.d/rc.mc_defaults -if [ $AUTOCNF == yes ] +if [ $AUTOCNF = yes ] then param set MC_PITCH_P 4.0 param set MC_PITCHRATE_P 0.24 diff --git a/ROMFS/px4fmu_common/init.d/13000_generic_vtol_standard b/ROMFS/px4fmu_common/init.d/13000_generic_vtol_standard index 284b531458..b7c0d8667a 100644 --- a/ROMFS/px4fmu_common/init.d/13000_generic_vtol_standard +++ b/ROMFS/px4fmu_common/init.d/13000_generic_vtol_standard @@ -20,7 +20,7 @@ sh /etc/init.d/rc.vtol_defaults -if [ $AUTOCNF == yes ] +if [ $AUTOCNF = yes ] then param set PWM_AUX_DIS5 950 param set PWM_RATE 400 diff --git a/ROMFS/px4fmu_common/init.d/13001_caipirinha_vtol b/ROMFS/px4fmu_common/init.d/13001_caipirinha_vtol index 006ea1e3e3..2c122852f5 100644 --- a/ROMFS/px4fmu_common/init.d/13001_caipirinha_vtol +++ b/ROMFS/px4fmu_common/init.d/13001_caipirinha_vtol @@ -15,7 +15,7 @@ sh /etc/init.d/rc.vtol_defaults -if [ $AUTOCNF == yes ] +if [ $AUTOCNF = yes ] then param set MC_ROLL_P 6.0 param set MC_ROLLRATE_P 0.12 diff --git a/ROMFS/px4fmu_common/init.d/13002_firefly6 b/ROMFS/px4fmu_common/init.d/13002_firefly6 index 9be4a8ca68..7a96f3c691 100644 --- a/ROMFS/px4fmu_common/init.d/13002_firefly6 +++ b/ROMFS/px4fmu_common/init.d/13002_firefly6 @@ -20,7 +20,7 @@ sh /etc/init.d/rc.vtol_defaults -if [ $AUTOCNF == yes ] +if [ $AUTOCNF = yes ] then param set MC_ROLL_P 7.0 param set MC_ROLLRATE_P 0.19 diff --git a/ROMFS/px4fmu_common/init.d/13003_quad_tailsitter b/ROMFS/px4fmu_common/init.d/13003_quad_tailsitter index 67bf1f49a5..6b1f533388 100644 --- a/ROMFS/px4fmu_common/init.d/13003_quad_tailsitter +++ b/ROMFS/px4fmu_common/init.d/13003_quad_tailsitter @@ -10,7 +10,7 @@ sh /etc/init.d/rc.vtol_defaults -if [ $AUTOCNF == yes ] +if [ $AUTOCNF = yes ] then param set PWM_MAX 2000 param set PWM_RATE 400 diff --git a/ROMFS/px4fmu_common/init.d/13004_quad+_tailsitter b/ROMFS/px4fmu_common/init.d/13004_quad+_tailsitter index b5558dcd99..cebe3c8a49 100644 --- a/ROMFS/px4fmu_common/init.d/13004_quad+_tailsitter +++ b/ROMFS/px4fmu_common/init.d/13004_quad+_tailsitter @@ -21,7 +21,7 @@ sh /etc/init.d/rc.vtol_defaults -if [ $AUTOCNF == yes ] +if [ $AUTOCNF = yes ] then param set PWM_MAX 2000 param set PWM_RATE 400 diff --git a/ROMFS/px4fmu_common/init.d/13005_vtol_AAERT_quad b/ROMFS/px4fmu_common/init.d/13005_vtol_AAERT_quad index 450f55f7c8..ed84f66db7 100644 --- a/ROMFS/px4fmu_common/init.d/13005_vtol_AAERT_quad +++ b/ROMFS/px4fmu_common/init.d/13005_vtol_AAERT_quad @@ -20,7 +20,7 @@ sh /etc/init.d/rc.vtol_defaults -if [ $AUTOCNF == yes ] +if [ $AUTOCNF = yes ] then param set PWM_AUX_DIS5 950 diff --git a/ROMFS/px4fmu_common/init.d/13006_vtol_standard_delta b/ROMFS/px4fmu_common/init.d/13006_vtol_standard_delta index 62563f114a..b1ee2431c8 100644 --- a/ROMFS/px4fmu_common/init.d/13006_vtol_standard_delta +++ b/ROMFS/px4fmu_common/init.d/13006_vtol_standard_delta @@ -18,7 +18,7 @@ sh /etc/init.d/rc.vtol_defaults -if [ $AUTOCNF == yes ] +if [ $AUTOCNF = yes ] then param set MC_ROLL_P 6.5 param set MC_ROLLRATE_P 0.15 diff --git a/ROMFS/px4fmu_common/init.d/13007_vtol_AAVVT_quad b/ROMFS/px4fmu_common/init.d/13007_vtol_AAVVT_quad index b482a5b252..9562b16e36 100644 --- a/ROMFS/px4fmu_common/init.d/13007_vtol_AAVVT_quad +++ b/ROMFS/px4fmu_common/init.d/13007_vtol_AAVVT_quad @@ -10,7 +10,7 @@ sh /etc/init.d/rc.vtol_defaults -if [ $AUTOCNF == yes ] +if [ $AUTOCNF = yes ] then param set MC_ROLL_P 7.0 param set MC_ROLLRATE_P 0.15 diff --git a/ROMFS/px4fmu_common/init.d/13008_QuadRanger b/ROMFS/px4fmu_common/init.d/13008_QuadRanger index 23e7a577b1..33cbdb9507 100644 --- a/ROMFS/px4fmu_common/init.d/13008_QuadRanger +++ b/ROMFS/px4fmu_common/init.d/13008_QuadRanger @@ -10,7 +10,7 @@ sh /etc/init.d/rc.vtol_defaults -if [ $AUTOCNF == yes ] +if [ $AUTOCNF = yes ] then param set FW_THR_CRUISE 65.0 param set FW_PR_P 0.08 diff --git a/ROMFS/px4fmu_common/init.d/13009_vtol_spt_ranger b/ROMFS/px4fmu_common/init.d/13009_vtol_spt_ranger index e356db452a..6943506762 100644 --- a/ROMFS/px4fmu_common/init.d/13009_vtol_spt_ranger +++ b/ROMFS/px4fmu_common/init.d/13009_vtol_spt_ranger @@ -10,7 +10,7 @@ sh /etc/init.d/rc.vtol_defaults -if [ $AUTOCNF == yes ] +if [ $AUTOCNF = yes ] then param set FW_AIRSPD_MAX 22.0 param set FW_AIRSPD_MIN 14.0 diff --git a/ROMFS/px4fmu_common/init.d/13010_claire b/ROMFS/px4fmu_common/init.d/13010_claire index 1b12d65d1b..981d7b8666 100644 --- a/ROMFS/px4fmu_common/init.d/13010_claire +++ b/ROMFS/px4fmu_common/init.d/13010_claire @@ -12,7 +12,7 @@ sh /etc/init.d/rc.vtol_defaults -if [ $AUTOCNF == yes ] +if [ $AUTOCNF = yes ] then param set PWM_AUX_DISARMED 1000 param set PWM_AUX_MAX 2000 diff --git a/ROMFS/px4fmu_common/init.d/13012_convergence b/ROMFS/px4fmu_common/init.d/13012_convergence index d6a78aaf40..013d171190 100644 --- a/ROMFS/px4fmu_common/init.d/13012_convergence +++ b/ROMFS/px4fmu_common/init.d/13012_convergence @@ -19,7 +19,7 @@ sh /etc/init.d/rc.vtol_defaults -if [ $AUTOCNF == yes ] +if [ $AUTOCNF = yes ] then param set CBRK_AIRSPD_CHK 162128 diff --git a/ROMFS/px4fmu_common/init.d/13013_deltaquad b/ROMFS/px4fmu_common/init.d/13013_deltaquad index cd7c4c1626..7adcb391f4 100644 --- a/ROMFS/px4fmu_common/init.d/13013_deltaquad +++ b/ROMFS/px4fmu_common/init.d/13013_deltaquad @@ -19,7 +19,7 @@ sh /etc/init.d/rc.vtol_defaults -if [ $AUTOCNF == yes ] +if [ $AUTOCNF = yes ] then param set BAT_CAPACITY 23000 param set BAT_N_CELLS 4 diff --git a/ROMFS/px4fmu_common/init.d/15001_coax_heli b/ROMFS/px4fmu_common/init.d/15001_coax_heli index 8c58344a46..b13da1b240 100644 --- a/ROMFS/px4fmu_common/init.d/15001_coax_heli +++ b/ROMFS/px4fmu_common/init.d/15001_coax_heli @@ -16,7 +16,7 @@ sh /etc/init.d/rc.mc_defaults set MIXER coax -if [ $AUTOCNF == yes ] +if [ $AUTOCNF = yes ] then param set MC_ROLL_P 6.5 param set MC_ROLLRATE_P 0.17 diff --git a/ROMFS/px4fmu_common/init.d/16001_helicopter b/ROMFS/px4fmu_common/init.d/16001_helicopter index cd958a7bc4..d4e3ffed4d 100644 --- a/ROMFS/px4fmu_common/init.d/16001_helicopter +++ b/ROMFS/px4fmu_common/init.d/16001_helicopter @@ -23,7 +23,7 @@ set MIXER blade130 #set PWM_OUT 1234 -if [ $AUTOCNF == yes ] +if [ $AUTOCNF = yes ] then param set ATT_BIAS_MAX 0.0 diff --git a/ROMFS/px4fmu_common/init.d/2100_standard_plane b/ROMFS/px4fmu_common/init.d/2100_standard_plane index a047c711d3..c723befd20 100644 --- a/ROMFS/px4fmu_common/init.d/2100_standard_plane +++ b/ROMFS/px4fmu_common/init.d/2100_standard_plane @@ -21,7 +21,7 @@ sh /etc/init.d/rc.fw_defaults -if [ $AUTOCNF == yes ] +if [ $AUTOCNF = yes ] then param set PWM_AUX_RATE 50 param set PWM_RATE 50 diff --git a/ROMFS/px4fmu_common/init.d/2105_maja b/ROMFS/px4fmu_common/init.d/2105_maja index e713b37919..74f841bb36 100644 --- a/ROMFS/px4fmu_common/init.d/2105_maja +++ b/ROMFS/px4fmu_common/init.d/2105_maja @@ -22,7 +22,7 @@ sh /etc/init.d/rc.fw_defaults -if [ $AUTOCNF == yes ] +if [ $AUTOCNF = yes ] then param set FW_AIRSPD_MIN 10 param set FW_AIRSPD_TRIM 15 diff --git a/ROMFS/px4fmu_common/init.d/2106_albatross b/ROMFS/px4fmu_common/init.d/2106_albatross index c0fe27aa23..822ca8dd9d 100644 --- a/ROMFS/px4fmu_common/init.d/2106_albatross +++ b/ROMFS/px4fmu_common/init.d/2106_albatross @@ -23,7 +23,7 @@ sh /etc/init.d/rc.fw_defaults -if [ $AUTOCNF == yes ] +if [ $AUTOCNF = yes ] then param set FW_AIRSPD_MIN 10 param set FW_AIRSPD_TRIM 15 diff --git a/ROMFS/px4fmu_common/init.d/24001_dodeca_cox b/ROMFS/px4fmu_common/init.d/24001_dodeca_cox index d47e559497..b2c0ac6fef 100644 --- a/ROMFS/px4fmu_common/init.d/24001_dodeca_cox +++ b/ROMFS/px4fmu_common/init.d/24001_dodeca_cox @@ -25,7 +25,7 @@ set VEHICLE_TYPE mc -if [ $AUTOCNF == yes ] +if [ $AUTOCNF = yes ] then param set NAV_ACC_RAD 2.0 diff --git a/ROMFS/px4fmu_common/init.d/3030_io_camflyer b/ROMFS/px4fmu_common/init.d/3030_io_camflyer index 7620fd6017..1d5a8ecefb 100644 --- a/ROMFS/px4fmu_common/init.d/3030_io_camflyer +++ b/ROMFS/px4fmu_common/init.d/3030_io_camflyer @@ -18,7 +18,7 @@ sh /etc/init.d/rc.fw_defaults -if [ $AUTOCNF == yes ] +if [ $AUTOCNF = yes ] then param set FW_AIRSPD_MAX 15 param set FW_AIRSPD_MIN 10 diff --git a/ROMFS/px4fmu_common/init.d/3031_phantom b/ROMFS/px4fmu_common/init.d/3031_phantom index aa1761a091..35f7ec0322 100644 --- a/ROMFS/px4fmu_common/init.d/3031_phantom +++ b/ROMFS/px4fmu_common/init.d/3031_phantom @@ -20,7 +20,7 @@ sh /etc/init.d/rc.fw_defaults -if [ $AUTOCNF == yes ] +if [ $AUTOCNF = yes ] then param set FW_AIRSPD_MIN 13 param set FW_AIRSPD_TRIM 15 diff --git a/ROMFS/px4fmu_common/init.d/3032_skywalker_x5 b/ROMFS/px4fmu_common/init.d/3032_skywalker_x5 index 84b4dcb591..8763eae674 100644 --- a/ROMFS/px4fmu_common/init.d/3032_skywalker_x5 +++ b/ROMFS/px4fmu_common/init.d/3032_skywalker_x5 @@ -18,7 +18,7 @@ sh /etc/init.d/rc.fw_defaults -if [ $AUTOCNF == yes ] +if [ $AUTOCNF = yes ] then param set FW_AIRSPD_MIN 15 param set FW_AIRSPD_TRIM 20 diff --git a/ROMFS/px4fmu_common/init.d/3033_wingwing b/ROMFS/px4fmu_common/init.d/3033_wingwing index fa7ccd6614..d850d207e0 100644 --- a/ROMFS/px4fmu_common/init.d/3033_wingwing +++ b/ROMFS/px4fmu_common/init.d/3033_wingwing @@ -20,7 +20,7 @@ sh /etc/init.d/rc.fw_defaults -if [ $AUTOCNF == yes ] +if [ $AUTOCNF = yes ] then param set BAT_N_CELLS 2 param set FW_AIRSPD_MAX 15 diff --git a/ROMFS/px4fmu_common/init.d/3034_fx79 b/ROMFS/px4fmu_common/init.d/3034_fx79 index 41ead073cb..88f134bbbc 100644 --- a/ROMFS/px4fmu_common/init.d/3034_fx79 +++ b/ROMFS/px4fmu_common/init.d/3034_fx79 @@ -10,7 +10,7 @@ sh /etc/init.d/rc.fw_defaults -if [ $AUTOCNF == yes ] +if [ $AUTOCNF = yes ] then param set FW_AIRSPD_MAX 30 param set FW_AIRSPD_MIN 13 diff --git a/ROMFS/px4fmu_common/init.d/3036_pigeon b/ROMFS/px4fmu_common/init.d/3036_pigeon index b4f33fd25d..30bdf39f57 100644 --- a/ROMFS/px4fmu_common/init.d/3036_pigeon +++ b/ROMFS/px4fmu_common/init.d/3036_pigeon @@ -20,7 +20,7 @@ sh /etc/init.d/rc.fw_defaults -if [ $AUTOCNF == yes ] +if [ $AUTOCNF = yes ] then param set FW_AIRSPD_MIN 15 param set FW_AIRSPD_TRIM 20 diff --git a/ROMFS/px4fmu_common/init.d/3037_parrot_disco_mod b/ROMFS/px4fmu_common/init.d/3037_parrot_disco_mod index 8884aa94a2..3a8b8b3cf5 100644 --- a/ROMFS/px4fmu_common/init.d/3037_parrot_disco_mod +++ b/ROMFS/px4fmu_common/init.d/3037_parrot_disco_mod @@ -20,7 +20,7 @@ sh /etc/init.d/rc.fw_defaults -if [ $AUTOCNF == yes ] +if [ $AUTOCNF = yes ] then #################################### diff --git a/ROMFS/px4fmu_common/init.d/3100_tbs_caipirinha b/ROMFS/px4fmu_common/init.d/3100_tbs_caipirinha index f541b10f40..79bfd0309f 100644 --- a/ROMFS/px4fmu_common/init.d/3100_tbs_caipirinha +++ b/ROMFS/px4fmu_common/init.d/3100_tbs_caipirinha @@ -10,7 +10,7 @@ sh /etc/init.d/rc.fw_defaults -if [ $AUTOCNF == yes ] +if [ $AUTOCNF = yes ] then param set FW_AIRSPD_MAX 25 param set FW_AIRSPD_MIN 12.5 diff --git a/ROMFS/px4fmu_common/init.d/4002_quad_x_mount b/ROMFS/px4fmu_common/init.d/4002_quad_x_mount index e9b0dfb9ee..0829921074 100644 --- a/ROMFS/px4fmu_common/init.d/4002_quad_x_mount +++ b/ROMFS/px4fmu_common/init.d/4002_quad_x_mount @@ -22,7 +22,7 @@ sh /etc/init.d/rc.mc_defaults -if [ $AUTOCNF == yes ] +if [ $AUTOCNF = yes ] then param set PWM_AUX_RATE 50 fi diff --git a/ROMFS/px4fmu_common/init.d/4003_qavr5 b/ROMFS/px4fmu_common/init.d/4003_qavr5 index 78b9fa87d3..5da6d7fe8b 100644 --- a/ROMFS/px4fmu_common/init.d/4003_qavr5 +++ b/ROMFS/px4fmu_common/init.d/4003_qavr5 @@ -12,7 +12,7 @@ sh /etc/init.d/4001_quad_x -if [ $AUTOCNF == yes ] +if [ $AUTOCNF = yes ] then param set MC_ROLL_P 8.0 param set MC_ROLLRATE_P 0.08 diff --git a/ROMFS/px4fmu_common/init.d/4004_H4_680mm b/ROMFS/px4fmu_common/init.d/4004_H4_680mm index 0e2a0bd2aa..b1efdd95a4 100644 --- a/ROMFS/px4fmu_common/init.d/4004_H4_680mm +++ b/ROMFS/px4fmu_common/init.d/4004_H4_680mm @@ -15,7 +15,7 @@ sh /etc/init.d/4002_quad_x_mount # see http://www.zhiyun-tech.com/uploadfile/datedown/instruction/Tiny2_English_instructionV1.03.pdf # under Gimbal Connection Instruction -if [ $AUTOCNF == yes ] +if [ $AUTOCNF = yes ] then param set PWM_AUX_DISARMED 1520 param set PWM_AUX_MIN 1020 diff --git a/ROMFS/px4fmu_common/init.d/4009_qav250 b/ROMFS/px4fmu_common/init.d/4009_qav250 index 54aaa40a42..4f4675e0c0 100644 --- a/ROMFS/px4fmu_common/init.d/4009_qav250 +++ b/ROMFS/px4fmu_common/init.d/4009_qav250 @@ -10,7 +10,7 @@ sh /etc/init.d/4001_quad_x -if [ $AUTOCNF == yes ] +if [ $AUTOCNF = yes ] then param set ATT_BIAS_MAX 0.0 diff --git a/ROMFS/px4fmu_common/init.d/4010_dji_f330 b/ROMFS/px4fmu_common/init.d/4010_dji_f330 index 6b37996f86..bff740b026 100644 --- a/ROMFS/px4fmu_common/init.d/4010_dji_f330 +++ b/ROMFS/px4fmu_common/init.d/4010_dji_f330 @@ -10,7 +10,7 @@ sh /etc/init.d/4001_quad_x -if [ $AUTOCNF == yes ] +if [ $AUTOCNF = yes ] then param set MC_ROLL_P 7.0 param set MC_ROLLRATE_P 0.15 diff --git a/ROMFS/px4fmu_common/init.d/4011_dji_f450 b/ROMFS/px4fmu_common/init.d/4011_dji_f450 index 6210b0e459..88794155d5 100644 --- a/ROMFS/px4fmu_common/init.d/4011_dji_f450 +++ b/ROMFS/px4fmu_common/init.d/4011_dji_f450 @@ -10,7 +10,7 @@ sh /etc/init.d/4001_quad_x -if [ $AUTOCNF == yes ] +if [ $AUTOCNF = yes ] then param set MC_ROLL_P 7.0 param set MC_ROLLRATE_P 0.15 diff --git a/ROMFS/px4fmu_common/init.d/4012_quad_x_can b/ROMFS/px4fmu_common/init.d/4012_quad_x_can index 7a7b565f6a..a0c39c7e27 100644 --- a/ROMFS/px4fmu_common/init.d/4012_quad_x_can +++ b/ROMFS/px4fmu_common/init.d/4012_quad_x_can @@ -10,7 +10,7 @@ sh /etc/init.d/4001_quad_x -if [ $AUTOCNF == yes ] +if [ $AUTOCNF = yes ] then param set MC_ROLL_P 7.0 param set MC_ROLLRATE_P 0.16 diff --git a/ROMFS/px4fmu_common/init.d/4013_bebop b/ROMFS/px4fmu_common/init.d/4013_bebop index 0459a45280..37669463b2 100644 --- a/ROMFS/px4fmu_common/init.d/4013_bebop +++ b/ROMFS/px4fmu_common/init.d/4013_bebop @@ -20,7 +20,7 @@ sh /etc/init.d/rc.mc_defaults # # Load default params for this platform # -if [ $AUTOCNF == yes ] +if [ $AUTOCNF = yes ] then # Set all params here, then disable autoconfig param set MC_ROLL_P 6.5 diff --git a/ROMFS/px4fmu_common/init.d/4014_s500 b/ROMFS/px4fmu_common/init.d/4014_s500 index cf65af24a6..923bb878ec 100644 --- a/ROMFS/px4fmu_common/init.d/4014_s500 +++ b/ROMFS/px4fmu_common/init.d/4014_s500 @@ -10,7 +10,7 @@ sh /etc/init.d/4001_quad_x -if [ $AUTOCNF == yes ] +if [ $AUTOCNF = yes ] then param set MC_ROLL_P 6.5 param set MC_ROLLRATE_P 0.18 diff --git a/ROMFS/px4fmu_common/init.d/4020_hk_micro_pcb b/ROMFS/px4fmu_common/init.d/4020_hk_micro_pcb index 9bf5c97616..ce9e7fb596 100644 --- a/ROMFS/px4fmu_common/init.d/4020_hk_micro_pcb +++ b/ROMFS/px4fmu_common/init.d/4020_hk_micro_pcb @@ -17,7 +17,7 @@ sh /etc/init.d/4001_quad_x -if [ $AUTOCNF == yes ] +if [ $AUTOCNF = yes ] then param set MC_ROLL_P 7.0 param set MC_ROLLRATE_P 0.1 diff --git a/ROMFS/px4fmu_common/init.d/4030_3dr_solo b/ROMFS/px4fmu_common/init.d/4030_3dr_solo index 636a70c4b4..089245826d 100644 --- a/ROMFS/px4fmu_common/init.d/4030_3dr_solo +++ b/ROMFS/px4fmu_common/init.d/4030_3dr_solo @@ -16,7 +16,7 @@ sh /etc/init.d/rc.mc_defaults -if [ $AUTOCNF == yes ] +if [ $AUTOCNF = yes ] then # tuning param set MC_PITCHRATE_P 0.11 diff --git a/ROMFS/px4fmu_common/init.d/4031_3dr_quad b/ROMFS/px4fmu_common/init.d/4031_3dr_quad index 0bdfb8f5ab..bf892f853a 100644 --- a/ROMFS/px4fmu_common/init.d/4031_3dr_quad +++ b/ROMFS/px4fmu_common/init.d/4031_3dr_quad @@ -10,7 +10,7 @@ sh /etc/init.d/4001_quad_x -if [ $AUTOCNF == yes ] +if [ $AUTOCNF = yes ] then param set MC_ROLL_P 6.5 param set MC_ROLLRATE_P 0.14 diff --git a/ROMFS/px4fmu_common/init.d/4040_reaper b/ROMFS/px4fmu_common/init.d/4040_reaper index 28c15cd287..799d2a5dea 100644 --- a/ROMFS/px4fmu_common/init.d/4040_reaper +++ b/ROMFS/px4fmu_common/init.d/4040_reaper @@ -17,7 +17,7 @@ sh /etc/init.d/rc.mc_defaults -if [ $AUTOCNF == yes ] +if [ $AUTOCNF = yes ] then param set MC_ROLL_P 6.5 param set MC_ROLLRATE_P 0.14 diff --git a/ROMFS/px4fmu_common/init.d/4050_generic_250 b/ROMFS/px4fmu_common/init.d/4050_generic_250 index 333ffbf37b..a69a34f297 100644 --- a/ROMFS/px4fmu_common/init.d/4050_generic_250 +++ b/ROMFS/px4fmu_common/init.d/4050_generic_250 @@ -10,7 +10,7 @@ sh /etc/init.d/4001_quad_x -if [ $AUTOCNF == yes ] +if [ $AUTOCNF = yes ] then param set MC_ROLL_P 8.0 param set MC_ROLLRATE_P 0.08 diff --git a/ROMFS/px4fmu_common/init.d/4051_s250aq b/ROMFS/px4fmu_common/init.d/4051_s250aq index ede53fed03..e861fa637c 100644 --- a/ROMFS/px4fmu_common/init.d/4051_s250aq +++ b/ROMFS/px4fmu_common/init.d/4051_s250aq @@ -26,7 +26,7 @@ set MAV_TYPE 2 set PWM_OUT 1234 -if [ $AUTOCNF == yes ] +if [ $AUTOCNF = yes ] then param set ATT_BIAS_MAX 0.0 diff --git a/ROMFS/px4fmu_common/init.d/4060_dji_matrice_100 b/ROMFS/px4fmu_common/init.d/4060_dji_matrice_100 index 094ebef7a4..e6e198c0be 100644 --- a/ROMFS/px4fmu_common/init.d/4060_dji_matrice_100 +++ b/ROMFS/px4fmu_common/init.d/4060_dji_matrice_100 @@ -10,7 +10,7 @@ sh /etc/init.d/4001_quad_x -if [ $AUTOCNF == yes ] +if [ $AUTOCNF = yes ] then param set BAT_N_CELLS 6 diff --git a/ROMFS/px4fmu_common/init.d/4070_aerofc b/ROMFS/px4fmu_common/init.d/4070_aerofc index bee3fa1003..84d81fcada 100644 --- a/ROMFS/px4fmu_common/init.d/4070_aerofc +++ b/ROMFS/px4fmu_common/init.d/4070_aerofc @@ -19,7 +19,7 @@ sh /etc/init.d/rc.mc_defaults # # Load default params for this platform # -if [ $AUTOCNF == yes ] +if [ $AUTOCNF = yes ] then # Set all params here, then disable autoconfig diff --git a/ROMFS/px4fmu_common/init.d/4080_zmr250 b/ROMFS/px4fmu_common/init.d/4080_zmr250 index bc88ba3bd7..f2d85a8982 100644 --- a/ROMFS/px4fmu_common/init.d/4080_zmr250 +++ b/ROMFS/px4fmu_common/init.d/4080_zmr250 @@ -15,7 +15,7 @@ sh /etc/init.d/rc.mc_defaults set MIXER zmr250 set PWM_OUT 1234 -if [ $AUTOCNF == yes ] +if [ $AUTOCNF = yes ] then param set CBRK_IO_SAFETY 22027 diff --git a/ROMFS/px4fmu_common/init.d/4090_nanomind b/ROMFS/px4fmu_common/init.d/4090_nanomind index f64b18fabb..e4a47d0d22 100644 --- a/ROMFS/px4fmu_common/init.d/4090_nanomind +++ b/ROMFS/px4fmu_common/init.d/4090_nanomind @@ -17,7 +17,7 @@ sh /etc/init.d/4001_quad_x -if [ $AUTOCNF == yes ] +if [ $AUTOCNF = yes ] then param set BAT_N_CELLS 1 diff --git a/ROMFS/px4fmu_common/init.d/4900_crazyflie b/ROMFS/px4fmu_common/init.d/4900_crazyflie index b5a1427d72..69357d8ee8 100644 --- a/ROMFS/px4fmu_common/init.d/4900_crazyflie +++ b/ROMFS/px4fmu_common/init.d/4900_crazyflie @@ -15,7 +15,7 @@ # @maintainer Dennis Shtatov # sh /etc/init.d/4001_quad_x -if [ $AUTOCNF == yes ] +if [ $AUTOCNF = yes ] then param set BAT_N_CELLS 1 param set BAT_CAPACITY 240 diff --git a/ROMFS/px4fmu_common/init.d/50000_generic_ground_vehicle b/ROMFS/px4fmu_common/init.d/50000_generic_ground_vehicle index 87b747e5fe..dc23d35d90 100644 --- a/ROMFS/px4fmu_common/init.d/50000_generic_ground_vehicle +++ b/ROMFS/px4fmu_common/init.d/50000_generic_ground_vehicle @@ -15,7 +15,7 @@ sh /etc/init.d/rc.ugv_defaults -if [ $AUTOCNF == yes ] +if [ $AUTOCNF = yes ] then param set BAT_N_CELLS 2 diff --git a/ROMFS/px4fmu_common/init.d/50001_axialracing_ax10 b/ROMFS/px4fmu_common/init.d/50001_axialracing_ax10 index e114eccee2..7a89a94833 100644 --- a/ROMFS/px4fmu_common/init.d/50001_axialracing_ax10 +++ b/ROMFS/px4fmu_common/init.d/50001_axialracing_ax10 @@ -23,7 +23,7 @@ sh /etc/init.d/rc.ugv_defaults # This section can be enabled once tuning parameters for this particular # rover model are known. It allows to configure default gains via the GUI. # -if [ $AUTOCNF == yes ] +if [ $AUTOCNF = yes ] then # PWM default value for "disarmed" mode. # This centers the steering and throttle, which means diff --git a/ROMFS/px4fmu_common/init.d/50002_traxxas_stampede_2wd b/ROMFS/px4fmu_common/init.d/50002_traxxas_stampede_2wd index 5c0428b423..c7166b291a 100644 --- a/ROMFS/px4fmu_common/init.d/50002_traxxas_stampede_2wd +++ b/ROMFS/px4fmu_common/init.d/50002_traxxas_stampede_2wd @@ -17,7 +17,7 @@ sh /etc/init.d/rc.ugv_defaults -if [ $AUTOCNF == yes ] +if [ $AUTOCNF = yes ] then param set BAT_N_CELLS 7 diff --git a/ROMFS/px4fmu_common/init.d/rc.fw_defaults b/ROMFS/px4fmu_common/init.d/rc.fw_defaults index 4d65de2ac1..101201be98 100644 --- a/ROMFS/px4fmu_common/init.d/rc.fw_defaults +++ b/ROMFS/px4fmu_common/init.d/rc.fw_defaults @@ -7,7 +7,7 @@ set VEHICLE_TYPE fw -if [ $AUTOCNF == yes ] +if [ $AUTOCNF = yes ] then # # Default parameters for fixed wing UAVs. diff --git a/ROMFS/px4fmu_common/init.d/rc.interface b/ROMFS/px4fmu_common/init.d/rc.interface index 55b7113737..f8c27b1880 100644 --- a/ROMFS/px4fmu_common/init.d/rc.interface +++ b/ROMFS/px4fmu_common/init.d/rc.interface @@ -30,7 +30,7 @@ then set MIXER_AUX none fi -if [ $USE_IO == no ] +if [ $USE_IO = no ] then set MIXER_AUX none fi @@ -38,12 +38,12 @@ fi # # Set the default output mode if none was set. # -if [ $OUTPUT_MODE == none ] +if [ $OUTPUT_MODE = none ] then - if [ $USE_IO == yes ] + if [ $USE_IO = yes ] then # Enable IO output only if IO is present. - if [ $IO_PRESENT == yes ] + if [ $IO_PRESENT = yes ] then set OUTPUT_MODE io fi @@ -53,17 +53,17 @@ then fi # -# If OUTPUT_MODE == none then something is wrong with setup and we shouldn't try to enable output. +# If OUTPUT_MODE = none then something is wrong with setup and we shouldn't try to enable output. # if [ $OUTPUT_MODE != none ] then - if [ $OUTPUT_MODE == mkblctrl ] + if [ $OUTPUT_MODE = mkblctrl ] then - if [ $MKBLCTRL_MODE == x ] + if [ $MKBLCTRL_MODE = x ] then set MKBLCTRL_ARG "-mkmode x" fi - if [ $MKBLCTRL_MODE == + ] + if [ $MKBLCTRL_MODE = + ] then set MKBLCTRL_ARG "-mkmode +" fi @@ -75,7 +75,7 @@ then fi fi - if [ $OUTPUT_MODE == hil -o $OUTPUT_MODE == sim ] + if [ $OUTPUT_MODE = hil -o $OUTPUT_MODE = sim ] then if ! pwm_out_sim start then @@ -84,7 +84,7 @@ then fi fi - if [ $OUTPUT_MODE == fmu ] + if [ $OUTPUT_MODE = fmu ] then if ! fmu mode_$FMU_MODE $FMU_ARGS then @@ -94,7 +94,7 @@ then fi fi - if [ $OUTPUT_MODE == uavcan_esc ] + if [ $OUTPUT_MODE = uavcan_esc ] then if param compare UAVCAN_ENABLE 0 then @@ -102,7 +102,7 @@ then fi fi - if [ $OUTPUT_MODE == io -o $OUTPUT_MODE == uavcan_esc ] + if [ $OUTPUT_MODE = io -o $OUTPUT_MODE = uavcan_esc ] then sh /etc/init.d/rc.io fi @@ -110,7 +110,7 @@ then # # Start IO for RC input if needed. # - if [ $IO_PRESENT == yes ] + if [ $IO_PRESENT = yes ] then if [ $OUTPUT_MODE != io ] then @@ -124,12 +124,12 @@ then # # Load main mixer. # - if [ $MIXER_AUX == none -a $USE_IO == yes ] + if [ $MIXER_AUX = none -a $USE_IO = yes ] then set MIXER_AUX ${MIXER} fi - if [ "$MIXER_FILE" == none ] + if [ "$MIXER_FILE" = none ] then if [ -f ${SDCARD_MIXERS_PATH}/${MIXER}.main.mix ] then @@ -146,19 +146,19 @@ then fi fi - if [ $OUTPUT_MODE == mkblctrl ] + if [ $OUTPUT_MODE = mkblctrl ] then set OUTPUT_DEV /dev/mkblctrl0 else set OUTPUT_DEV /dev/pwm_output0 fi - if [ $OUTPUT_MODE == uavcan_esc ] + if [ $OUTPUT_MODE = uavcan_esc ] then set OUTPUT_DEV /dev/uavcan/esc fi - if [ $OUTPUT_MODE == tap_esc ] + if [ $OUTPUT_MODE = tap_esc ] then set OUTPUT_DEV /dev/tap_esc fi @@ -311,7 +311,7 @@ then fi fi -if [ $OUTPUT_MODE == fmu -o $OUTPUT_MODE == io ] +if [ $OUTPUT_MODE = fmu -o $OUTPUT_MODE = io ] then if [ $PWM_OUT != none ] then diff --git a/ROMFS/px4fmu_common/init.d/rc.io b/ROMFS/px4fmu_common/init.d/rc.io index abd09db465..c539bd339a 100644 --- a/ROMFS/px4fmu_common/init.d/rc.io +++ b/ROMFS/px4fmu_common/init.d/rc.io @@ -2,7 +2,7 @@ # # PX4IO interface init script. # -if [ $USE_IO == yes -a $IO_PRESENT == yes ] +if [ $USE_IO = yes -a $IO_PRESENT = yes ] then if px4io start then diff --git a/ROMFS/px4fmu_common/init.d/rc.mc_defaults b/ROMFS/px4fmu_common/init.d/rc.mc_defaults index 71effde4b4..13460df31c 100644 --- a/ROMFS/px4fmu_common/init.d/rc.mc_defaults +++ b/ROMFS/px4fmu_common/init.d/rc.mc_defaults @@ -7,7 +7,7 @@ set VEHICLE_TYPE mc -if [ $AUTOCNF == yes ] +if [ $AUTOCNF = yes ] then param set NAV_ACC_RAD 2.0 diff --git a/ROMFS/px4fmu_common/init.d/rc.sensors b/ROMFS/px4fmu_common/init.d/rc.sensors index b1a22ed9a9..5ac2eee781 100644 --- a/ROMFS/px4fmu_common/init.d/rc.sensors +++ b/ROMFS/px4fmu_common/init.d/rc.sensors @@ -218,7 +218,7 @@ then # external LSM303D is rotated 270 degrees yaw lsm303d -X -R 6 start - if [ $BOARD_FMUV3 == 20 ] + if [ $BOARD_FMUV3 = 20 ] then # v2.0 internal MPU6000 is rotated 180 deg roll, 270 deg yaw mpu6000 -R 14 start @@ -227,14 +227,14 @@ then hmc5883 -C -T -S -R 8 start fi - if [ $BOARD_FMUV3 == 21 ] + if [ $BOARD_FMUV3 = 21 ] then # v2.1 internal MPU9250 is rotated 180 deg roll, 270 deg yaw mpu9250 -R 14 start fi else - # $BOARD_FMUV3 == 0 -> FMUv2 + # $BOARD_FMUV3 = 0 -> FMUv2 mpu6000 start @@ -364,7 +364,7 @@ fi # Begin Optional drivers # ############################################################################### -if [ ${VEHICLE_TYPE} == fw -o ${VEHICLE_TYPE} == vtol ] +if [ ${VEHICLE_TYPE} = fw -o ${VEHICLE_TYPE} = vtol ] then if param compare CBRK_AIRSPD_CHK 0 then @@ -374,7 +374,7 @@ then # detected as MS5525 because the chip manufacturer was so # clever to assign the same I2C address and skip a WHO_AM_I # register. - if [ $BOARD_FMUV3 == 21 ] + if [ $BOARD_FMUV3 = 21 ] then ms5525_airspeed start -b 2 else diff --git a/ROMFS/px4fmu_common/init.d/rc.ugv_defaults b/ROMFS/px4fmu_common/init.d/rc.ugv_defaults index 4d0ec0aec8..c2ce7524a2 100644 --- a/ROMFS/px4fmu_common/init.d/rc.ugv_defaults +++ b/ROMFS/px4fmu_common/init.d/rc.ugv_defaults @@ -7,7 +7,7 @@ set VEHICLE_TYPE ugv -if [ $AUTOCNF == yes ] +if [ $AUTOCNF = yes ] then # # Default parameters for UGVs. diff --git a/ROMFS/px4fmu_common/init.d/rc.vehicle_setup b/ROMFS/px4fmu_common/init.d/rc.vehicle_setup index 74757bd695..703457abca 100644 --- a/ROMFS/px4fmu_common/init.d/rc.vehicle_setup +++ b/ROMFS/px4fmu_common/init.d/rc.vehicle_setup @@ -8,15 +8,15 @@ # # Fixed wing setup. # -if [ $VEHICLE_TYPE == fw ] +if [ $VEHICLE_TYPE = fw ] then - if [ $MIXER == none ] + if [ $MIXER = none ] then # Set default mixer for fixed wing if not defined. set MIXER AERT fi - if [ $MAV_TYPE == none ] + if [ $MAV_TYPE = none ] then # Set a default MAV_TYPE = 1 if not defined. set MAV_TYPE 1 @@ -35,40 +35,40 @@ fi # # Multicopter setup. # -if [ $VEHICLE_TYPE == mc ] +if [ $VEHICLE_TYPE = mc ] then - if [ $MIXER == none ] + if [ $MIXER = none ] then echo "MC mixer undefined" fi - if [ $MAV_TYPE == none ] + if [ $MAV_TYPE = none ] then # Set a default MAV_TYPE = 2 if not defined. set MAV_TYPE 2 # Use mixer to detect vehicle type - if [ $MIXER == coax ] + if [ $MIXER = coax ] then set MAV_TYPE 3 fi - if [ $MIXER == hexa_x -o $MIXER == hexa_+ ] + if [ $MIXER = hexa_x -o $MIXER = hexa_+ ] then set MAV_TYPE 13 fi - if [ $MIXER == hexa_cox ] + if [ $MIXER = hexa_cox ] then set MAV_TYPE 13 fi - if [ $MIXER == octo_x -o $MIXER == octo_+ ] + if [ $MIXER = octo_x -o $MIXER = octo_+ ] then set MAV_TYPE 14 fi - if [ $MIXER == octo_cox -o $MIXER == octo_cox_w ] + if [ $MIXER = octo_cox -o $MIXER = octo_cox_w ] then set MAV_TYPE 14 fi - if [ $MIXER == tri_y_yaw- -o $MIXER == tri_y_yaw+ ] + if [ $MIXER = tri_y_yaw- -o $MIXER = tri_y_yaw+ ] then set MAV_TYPE 15 fi @@ -87,15 +87,15 @@ fi # # UGV setup. # -if [ $VEHICLE_TYPE == ugv ] +if [ $VEHICLE_TYPE = ugv ] then - if [ $MIXER == none ] + if [ $MIXER = none ] then # Set default mixer for UGV if not defined. set MIXER ugv_generic fi - if [ $MAV_TYPE == none ] + if [ $MAV_TYPE = none ] then # Set a default MAV_TYPE = 10 if not defined. set MAV_TYPE 10 @@ -114,24 +114,24 @@ fi # # VTOL setup. # -if [ $VEHICLE_TYPE == vtol ] +if [ $VEHICLE_TYPE = vtol ] then - if [ $MIXER == none ] + if [ $MIXER = none ] then echo "VTOL mixer undefined" fi - if [ $MAV_TYPE == none ] + if [ $MAV_TYPE = none ] then # Set a default MAV_TYPE = 19 if not defined. set MAV_TYPE 19 # Use mixer to detect vehicle type. - if [ $MIXER == firefly6 ] + if [ $MIXER = firefly6 ] then set MAV_TYPE 21 fi - if [ $MIXER == quad_x_pusher_vtol ] + if [ $MIXER = quad_x_pusher_vtol ] then set MAV_TYPE 22 fi @@ -150,7 +150,7 @@ fi # # Generic setup (autostart ID not found). # -if [ $VEHICLE_TYPE == none ] +if [ $VEHICLE_TYPE = none ] then echo "No autostart ID found" ekf2 start diff --git a/ROMFS/px4fmu_common/init.d/rc.vtol_defaults b/ROMFS/px4fmu_common/init.d/rc.vtol_defaults index dfec641a38..3ea1abd4bb 100644 --- a/ROMFS/px4fmu_common/init.d/rc.vtol_defaults +++ b/ROMFS/px4fmu_common/init.d/rc.vtol_defaults @@ -7,7 +7,7 @@ set VEHICLE_TYPE vtol -if [ $AUTOCNF == yes ] +if [ $AUTOCNF = yes ] then param set MIS_TAKEOFF_ALT 20 param set MIS_YAW_TMT 10 diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS index 33cc0f94fe..cd59fe865e 100644 --- a/ROMFS/px4fmu_common/init.d/rcS +++ b/ROMFS/px4fmu_common/init.d/rcS @@ -163,7 +163,7 @@ fi if ! ver hwcmp CRAZYFLIE AEROCORE2 then # Run no SD alarm. - if [ $LOG_FILE == /dev/null ] + if [ $LOG_FILE = /dev/null ] then # tune Make FS MBAGP tune_control play -t 2 @@ -335,7 +335,7 @@ else # # If autoconfig parameter was set, reset it and save parameters. # - if [ $AUTOCNF == yes ] + if [ $AUTOCNF = yes ] then # Run FMU as task on Pixracer and on boards with enough RAM. if ver hwcmp PX4FMU_V4 PX4FMU_V4PRO PX4FMU_V5 @@ -406,7 +406,7 @@ else fi fi - if [ $IO_PRESENT == no ] + if [ $IO_PRESENT = no ] then echo "PX4IO update failed" >> $LOG_FILE # Error tune. @@ -424,14 +424,14 @@ else set USE_IO yes fi - if [ $USE_IO == yes -a $IO_PRESENT == no ] + if [ $USE_IO = yes -a $IO_PRESENT = no ] then echo "PX4IO not found" >> $LOG_FILE # Error tune. tune_control play -t 2 fi - if [ $IO_PRESENT == no -o $USE_IO == no ] + if [ $IO_PRESENT = no -o $USE_IO = no ] then rc_input start fi diff --git a/ROMFS/px4fmu_test/init.d/rc.sensors b/ROMFS/px4fmu_test/init.d/rc.sensors index dac49f865c..0ac92f72f0 100644 --- a/ROMFS/px4fmu_test/init.d/rc.sensors +++ b/ROMFS/px4fmu_test/init.d/rc.sensors @@ -46,7 +46,7 @@ then set BOARD_FMUV3 false fi - if [ $BOARD_FMUV3 == true ] + if [ $BOARD_FMUV3 = true ] then # external L3GD20H is rotated 180 degrees yaw if l3gd20 -X -R 4 start diff --git a/ROMFS/px4fmu_test/init.d/rcS b/ROMFS/px4fmu_test/init.d/rcS index 996b541689..9082104075 100644 --- a/ROMFS/px4fmu_test/init.d/rcS +++ b/ROMFS/px4fmu_test/init.d/rcS @@ -24,7 +24,7 @@ fi # Try to mount the microSD card. # mount -t vfat /dev/mmcsd0 /fs/microsd -if [ $? == 0 ] +if [ $? = 0 ] then echo "[i] card mounted at /fs/microsd" # Start playing the startup tune diff --git a/ROMFS/tap_common/init.d/rc.fw_defaults b/ROMFS/tap_common/init.d/rc.fw_defaults index 2c2da70168..74777e6167 100644 --- a/ROMFS/tap_common/init.d/rc.fw_defaults +++ b/ROMFS/tap_common/init.d/rc.fw_defaults @@ -2,7 +2,7 @@ set VEHICLE_TYPE fw -if [ $AUTOCNF == yes ] +if [ $AUTOCNF = yes ] then # # Default parameters for FW diff --git a/ROMFS/tap_common/init.d/rc.interface b/ROMFS/tap_common/init.d/rc.interface index 65071be478..11979210bb 100644 --- a/ROMFS/tap_common/init.d/rc.interface +++ b/ROMFS/tap_common/init.d/rc.interface @@ -16,7 +16,7 @@ then set OUTPUT_DEV /dev/pwm_output0 - if [ $OUTPUT_MODE == tap_esc ] + if [ $OUTPUT_MODE = tap_esc ] then set OUTPUT_DEV /dev/tap_esc fi @@ -40,7 +40,7 @@ else fi fi -if [ $OUTPUT_MODE == fmu -o $OUTPUT_MODE == io ] +if [ $OUTPUT_MODE = fmu -o $OUTPUT_MODE = io ] then if [ $PWM_OUT != none ] then diff --git a/ROMFS/tap_common/init.d/rc.mc_defaults b/ROMFS/tap_common/init.d/rc.mc_defaults index c5f178bb86..f7ca870b7f 100644 --- a/ROMFS/tap_common/init.d/rc.mc_defaults +++ b/ROMFS/tap_common/init.d/rc.mc_defaults @@ -2,7 +2,7 @@ set VEHICLE_TYPE mc -if [ $AUTOCNF == yes ] +if [ $AUTOCNF = yes ] then param set PWM_DISARMED 900 param set PWM_MIN 1075 diff --git a/ROMFS/tap_common/init.d/rc.vtol_defaults b/ROMFS/tap_common/init.d/rc.vtol_defaults index 58e24d1dbe..1dbff43e25 100644 --- a/ROMFS/tap_common/init.d/rc.vtol_defaults +++ b/ROMFS/tap_common/init.d/rc.vtol_defaults @@ -2,7 +2,7 @@ set VEHICLE_TYPE vtol -if [ $AUTOCNF == yes ] +if [ $AUTOCNF = yes ] then param set MC_ROLL_P 6.0 param set MC_PITCH_P 6.0 diff --git a/ROMFS/tap_common/init.d/rcS b/ROMFS/tap_common/init.d/rcS index de70122891..d90962e929 100644 --- a/ROMFS/tap_common/init.d/rcS +++ b/ROMFS/tap_common/init.d/rcS @@ -125,7 +125,7 @@ sh /etc/init.d/rc.autostart # # If autoconfig parameter was set, reset it and save parameters # -if [ $AUTOCNF == yes ] +if [ $AUTOCNF = yes ] then param set SYS_AUTOCONFIG 0 param save @@ -135,9 +135,9 @@ unset AUTOCNF # # Set default output if not set # -if [ $OUTPUT_MODE == none ] +if [ $OUTPUT_MODE = none ] then - if [ $USE_IO == yes ] + if [ $USE_IO = yes ] then set OUTPUT_MODE io else @@ -181,17 +181,17 @@ mavlink start -r 60000 -d /dev/ttyACM0 -m config # # Fixed wing setup # -if [ $VEHICLE_TYPE == fw ] +if [ $VEHICLE_TYPE = fw ] then echo "INFO [init] Fixedwing" - if [ $MIXER == none ] + if [ $MIXER = none ] then # Set default mixer for fixed wing if not defined set MIXER AERT fi - if [ $MAV_TYPE == none ] + if [ $MAV_TYPE = none ] then # Use MAV_TYPE = 1 (fixed wing) if not defined set MAV_TYPE 1 @@ -209,50 +209,50 @@ fi # # Multicopters setup # -if [ $VEHICLE_TYPE == mc ] +if [ $VEHICLE_TYPE = mc ] then echo "INFO [init] Multicopter" - if [ $MIXER == none ] + if [ $MIXER = none ] then echo "INFO [init] Mixer undefined" fi - if [ $MAV_TYPE == none ] + if [ $MAV_TYPE = none ] then # Use mixer to detect vehicle type - if [ $MIXER == quad_x -o $MIXER == quad_+ ] + if [ $MIXER = quad_x -o $MIXER = quad_+ ] then set MAV_TYPE 2 fi - if [ $MIXER == quad_w ] + if [ $MIXER = quad_w ] then set MAV_TYPE 2 fi - if [ $MIXER == quad_h ] + if [ $MIXER = quad_h ] then set MAV_TYPE 2 fi - if [ $MIXER == tri_y_yaw- -o $MIXER == tri_y_yaw+ ] + if [ $MIXER = tri_y_yaw- -o $MIXER = tri_y_yaw+ ] then set MAV_TYPE 15 fi - if [ $MIXER == hexa_x -o $MIXER == hexa_+ ] + if [ $MIXER = hexa_x -o $MIXER = hexa_+ ] then set MAV_TYPE 13 fi - if [ $MIXER == hexa_cox ] + if [ $MIXER = hexa_cox ] then set MAV_TYPE 13 fi - if [ $MIXER == octo_x -o $MIXER == octo_+ ] + if [ $MIXER = octo_x -o $MIXER = octo_+ ] then set MAV_TYPE 14 fi fi # Still no MAV_TYPE found - if [ $MAV_TYPE == none ] + if [ $MAV_TYPE = none ] then echo "WARN [init] Unknown MAV_TYPE" param set MAV_TYPE 2 @@ -270,34 +270,34 @@ fi # # VTOL setup # -if [ $VEHICLE_TYPE == vtol ] +if [ $VEHICLE_TYPE = vtol ] then echo "INFO [init] VTOL" - if [ $MIXER == none ] + if [ $MIXER = none ] then echo "WARN [init] VTOL mixer undefined" fi - if [ $MAV_TYPE == none ] + if [ $MAV_TYPE = none ] then # Use mixer to detect vehicle type - if [ $MIXER == caipirinha_vtol ] + if [ $MIXER = caipirinha_vtol ] then set MAV_TYPE 19 fi - if [ $MIXER == firefly6 ] + if [ $MIXER = firefly6 ] then set MAV_TYPE 21 fi - if [ $MIXER == quad_x_pusher_vtol ] + if [ $MIXER = quad_x_pusher_vtol ] then set MAV_TYPE 22 fi fi # Still no MAV_TYPE found - if [ $MAV_TYPE == none ] + if [ $MAV_TYPE = none ] then echo "WARN [init] Unknown MAV_TYPE" param set MAV_TYPE 19 @@ -315,7 +315,7 @@ fi # # UGV/Rover setup # -if [ $VEHICLE_TYPE == ugv ] +if [ $VEHICLE_TYPE = ugv ] then # 10 is MAV_TYPE_GROUND_ROVER set MAV_TYPE 10 diff --git a/Tools/serial/rc.serial_port.jinja b/Tools/serial/rc.serial_port.jinja index f22b4d80c7..869ffb0452 100644 --- a/Tools/serial/rc.serial_port.jinja +++ b/Tools/serial/rc.serial_port.jinja @@ -6,7 +6,7 @@ set SERIAL_DEV none {% for serial_device in serial_devices -%} if param compare "$PRT" {{ serial_device.index }} then - if [ "x$PRT_{{ serial_device.tag }}_" == "x" ] + if [ "x$PRT_{{ serial_device.tag }}_" = "x" ] then set SERIAL_DEV {{ serial_device.device }} set BAUD_PARAM SER_{{ serial_device.tag }}_BAUD