From e920206e8db00a72423626840ccff9b4505a8391 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 24 Sep 2017 12:32:10 +0200 Subject: [PATCH] Autostart: Allow overriding airframe defaults This is necessary to enable setting new airframe defaults after significant configuration changes. --- .../init.d/1000_rc_fw_easystar.hil | 2 +- .../px4fmu_common/init.d/10015_tbs_discovery | 2 +- ROMFS/px4fmu_common/init.d/10016_3dr_iris | 2 +- .../init.d/10017_steadidrone_qu4d | 2 +- .../px4fmu_common/init.d/10018_tbs_endurance | 2 +- ROMFS/px4fmu_common/init.d/10020_3dr_quad | 2 +- .../init.d/12002_steadidrone_mavrik | 2 +- .../init.d/13001_caipirinha_vtol | 2 +- ROMFS/px4fmu_common/init.d/13002_firefly6 | 2 +- .../init.d/13003_quad_tailsitter | 2 +- .../init.d/13004_quad+_tailsitter | 2 +- .../init.d/13005_vtol_AAERT_quad | 2 +- .../init.d/13006_vtol_standard_delta | 2 +- .../init.d/13007_vtol_AAVVT_quad | 2 +- ROMFS/px4fmu_common/init.d/13008_QuadRanger | 2 +- .../init.d/13009_vtol_spt_ranger | 2 +- ROMFS/px4fmu_common/init.d/13010_claire | 2 +- ROMFS/px4fmu_common/init.d/13012_convergence | 2 +- ROMFS/px4fmu_common/init.d/13013_deltaquad | 2 +- ROMFS/px4fmu_common/init.d/15001_coax_heli | 2 +- ROMFS/px4fmu_common/init.d/16001_helicopter | 2 +- ROMFS/px4fmu_common/init.d/2105_maja | 2 +- ROMFS/px4fmu_common/init.d/2106_albatross | 2 +- ROMFS/px4fmu_common/init.d/24001_dodeca_cox | 2 +- ROMFS/px4fmu_common/init.d/3030_io_camflyer | 2 +- ROMFS/px4fmu_common/init.d/3031_phantom | 2 +- ROMFS/px4fmu_common/init.d/3032_skywalker_x5 | 2 +- ROMFS/px4fmu_common/init.d/3033_wingwing | 2 +- ROMFS/px4fmu_common/init.d/3034_fx79 | 2 +- ROMFS/px4fmu_common/init.d/3036_pigeon | 2 +- .../init.d/3037_parrot_disco_mod | 2 +- .../px4fmu_common/init.d/3100_tbs_caipirinha | 2 +- ROMFS/px4fmu_common/init.d/4003_qavr5 | 2 +- ROMFS/px4fmu_common/init.d/4009_qav250 | 2 +- ROMFS/px4fmu_common/init.d/4010_dji_f330 | 2 +- ROMFS/px4fmu_common/init.d/4011_dji_f450 | 2 +- ROMFS/px4fmu_common/init.d/4012_quad_x_can | 2 +- ROMFS/px4fmu_common/init.d/4013_bebop | 2 +- ROMFS/px4fmu_common/init.d/4020_hk_micro_pcb | 2 +- ROMFS/px4fmu_common/init.d/4030_solo | 2 +- ROMFS/px4fmu_common/init.d/4040_reaper | 2 +- ROMFS/px4fmu_common/init.d/4050_generic_250 | 2 +- ROMFS/px4fmu_common/init.d/4051_s250aq | 2 +- .../px4fmu_common/init.d/4060_dji_matrice_100 | 2 +- ROMFS/px4fmu_common/init.d/4070_aerofc | 2 +- ROMFS/px4fmu_common/init.d/4080_zmr250 | 2 +- ROMFS/px4fmu_common/init.d/4090_nanomind | 2 +- ROMFS/px4fmu_common/init.d/4900_crazyflie | 2 +- .../init.d/50002_traxxas_stampede_2wd | 2 +- .../init.d/rc.axialracing_ax10_defaults | 2 +- ROMFS/px4fmu_common/init.d/rc.fw_defaults | 2 +- ROMFS/px4fmu_common/init.d/rc.gnd_defaults | 2 +- ROMFS/px4fmu_common/init.d/rc.mc_defaults | 2 +- ROMFS/px4fmu_common/init.d/rc.vtol_defaults | 2 +- ROMFS/px4fmu_common/init.d/rcS | 37 ++++++++++++++----- 55 files changed, 81 insertions(+), 64 deletions(-) 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 8cbf81b496ec..3403326bef64 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 -o $NEW_DEFAULTS == yes ] then param set BAT_N_CELLS 3 param set FW_AIRSPD_MAX 20 diff --git a/ROMFS/px4fmu_common/init.d/10015_tbs_discovery b/ROMFS/px4fmu_common/init.d/10015_tbs_discovery index 77647e51eb7c..cf6d1363b838 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 -o $NEW_DEFAULTS == 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 f270153c7ce7..70c4d74feeec 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 -o $NEW_DEFAULTS == 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 b6ef969ed450..f26612f8398f 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 -o $NEW_DEFAULTS == yes ] then param set MC_ROLL_P 7.0 param set MC_ROLLRATE_P 0.13 diff --git a/ROMFS/px4fmu_common/init.d/10018_tbs_endurance b/ROMFS/px4fmu_common/init.d/10018_tbs_endurance index 5447911dd159..ee85d73c38a6 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 -o $NEW_DEFAULTS == yes ] then param set BAT_N_CELLS 6 param set BAT_V_EMPTY 3.5 diff --git a/ROMFS/px4fmu_common/init.d/10020_3dr_quad b/ROMFS/px4fmu_common/init.d/10020_3dr_quad index 0bdfb8f5abb2..428c581a82d2 100644 --- a/ROMFS/px4fmu_common/init.d/10020_3dr_quad +++ b/ROMFS/px4fmu_common/init.d/10020_3dr_quad @@ -10,7 +10,7 @@ sh /etc/init.d/4001_quad_x -if [ $AUTOCNF == yes ] +if [ $AUTOCNF == yes -o $NEW_DEFAULTS == yes ] then param set MC_ROLL_P 6.5 param set MC_ROLLRATE_P 0.14 diff --git a/ROMFS/px4fmu_common/init.d/12002_steadidrone_mavrik b/ROMFS/px4fmu_common/init.d/12002_steadidrone_mavrik index 3db8e69db2fa..55bbcc0ed106 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 -o $NEW_DEFAULTS == yes ] then param set MC_PITCH_P 4.0 param set MC_PITCHRATE_P 0.24 diff --git a/ROMFS/px4fmu_common/init.d/13001_caipirinha_vtol b/ROMFS/px4fmu_common/init.d/13001_caipirinha_vtol index 9566db9134eb..47569e39f9e3 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 -o $NEW_DEFAULTS == 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 504b9056a3cf..cc7d68da42ae 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 -o $NEW_DEFAULTS == 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 ae820f6224eb..7b97ada64df5 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 -o $NEW_DEFAULTS == yes ] then param set VT_MOT_COUNT 4 param set VT_IDLE_PWM_MC 1080 diff --git a/ROMFS/px4fmu_common/init.d/13004_quad+_tailsitter b/ROMFS/px4fmu_common/init.d/13004_quad+_tailsitter index 75bdb8a331c7..da94d31622d6 100644 --- a/ROMFS/px4fmu_common/init.d/13004_quad+_tailsitter +++ b/ROMFS/px4fmu_common/init.d/13004_quad+_tailsitter @@ -19,7 +19,7 @@ sh /etc/init.d/rc.vtol_defaults -if [ $AUTOCNF == yes ] +if [ $AUTOCNF == yes -o $NEW_DEFAULTS == yes ] then param set VT_MOT_COUNT 4 param set VT_IDLE_PWM_MC 1080 diff --git a/ROMFS/px4fmu_common/init.d/13005_vtol_AAERT_quad b/ROMFS/px4fmu_common/init.d/13005_vtol_AAERT_quad index 2ffd8c580fea..f066ba04b66e 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 -o $NEW_DEFAULTS == yes ] then param set VT_TYPE 2 param set VT_MOT_COUNT 4 diff --git a/ROMFS/px4fmu_common/init.d/13006_vtol_standard_delta b/ROMFS/px4fmu_common/init.d/13006_vtol_standard_delta index 2aee278579aa..1770dc639e53 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 -o $NEW_DEFAULTS == yes ] then param set VT_TYPE 2 param set VT_MOT_COUNT 4 diff --git a/ROMFS/px4fmu_common/init.d/13007_vtol_AAVVT_quad b/ROMFS/px4fmu_common/init.d/13007_vtol_AAVVT_quad index 4b8ad807f61e..647d15bd9ee2 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 -o $NEW_DEFAULTS == yes ] then param set VT_TYPE 2 param set VT_MOT_COUNT 4 diff --git a/ROMFS/px4fmu_common/init.d/13008_QuadRanger b/ROMFS/px4fmu_common/init.d/13008_QuadRanger index 4767e02ed232..c3454ebd6dcc 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 -o $NEW_DEFAULTS == yes ] then param set VT_TYPE 2 param set VT_MOT_COUNT 4 diff --git a/ROMFS/px4fmu_common/init.d/13009_vtol_spt_ranger b/ROMFS/px4fmu_common/init.d/13009_vtol_spt_ranger index da41a4204b1e..edcf5f5703b4 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 -o $NEW_DEFAULTS == yes ] then param set VT_TYPE 2 param set VT_MOT_COUNT 4 diff --git a/ROMFS/px4fmu_common/init.d/13010_claire b/ROMFS/px4fmu_common/init.d/13010_claire index 2b3f7c5483de..10a40b3e9659 100644 --- a/ROMFS/px4fmu_common/init.d/13010_claire +++ b/ROMFS/px4fmu_common/init.d/13010_claire @@ -10,7 +10,7 @@ sh /etc/init.d/rc.vtol_defaults -if [ $AUTOCNF == yes ] +if [ $AUTOCNF == yes -o $NEW_DEFAULTS == yes ] then param set VT_TYPE 1 param set VT_TILT_MC 0.08 diff --git a/ROMFS/px4fmu_common/init.d/13012_convergence b/ROMFS/px4fmu_common/init.d/13012_convergence index c07ee5800fe9..511405fdd365 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 -o $NEW_DEFAULTS == yes ] then param set VT_MOT_COUNT 3 param set VT_FW_MOT_OFFID 3 diff --git a/ROMFS/px4fmu_common/init.d/13013_deltaquad b/ROMFS/px4fmu_common/init.d/13013_deltaquad index 895ec3402cd4..951f0eafea11 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 -o $NEW_DEFAULTS == yes ] then param set VT_TYPE 2 param set VT_MOT_COUNT 4 diff --git a/ROMFS/px4fmu_common/init.d/15001_coax_heli b/ROMFS/px4fmu_common/init.d/15001_coax_heli index 853bc4823aaa..37d724e0ffb6 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 -o $NEW_DEFAULTS == yes ] then param set NAV_ACC_RAD 2.0 param set RTL_RETURN_ALT 30.0 diff --git a/ROMFS/px4fmu_common/init.d/16001_helicopter b/ROMFS/px4fmu_common/init.d/16001_helicopter index a91a60fb5f57..6aeb6517c634 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 -o $NEW_DEFAULTS == yes ] then param set MC_ROLL_P 5.0 param set MC_ROLLRATE_P 0.0 diff --git a/ROMFS/px4fmu_common/init.d/2105_maja b/ROMFS/px4fmu_common/init.d/2105_maja index 7a8fd88c4a53..0bae61788594 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 -o $NEW_DEFAULTS == 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 edd5f9ef058b..6f781e6de7c8 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 -o $NEW_DEFAULTS == 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 fb2ed1301be3..869a65e06f2e 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 -o $NEW_DEFAULTS == yes ] then param set NAV_ACC_RAD 2.0 param set RTL_RETURN_ALT 30.0 diff --git a/ROMFS/px4fmu_common/init.d/3030_io_camflyer b/ROMFS/px4fmu_common/init.d/3030_io_camflyer index 2e88892795a6..2dc8a895e486 100644 --- a/ROMFS/px4fmu_common/init.d/3030_io_camflyer +++ b/ROMFS/px4fmu_common/init.d/3030_io_camflyer @@ -20,7 +20,7 @@ sh /etc/init.d/rc.fw_defaults -if [ $AUTOCNF == yes ] +if [ $AUTOCNF == yes -o $NEW_DEFAULTS == 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 6a05205c096d..eba71279951d 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 -o $NEW_DEFAULTS == 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 4e24659351d8..e1a8692f88a9 100644 --- a/ROMFS/px4fmu_common/init.d/3032_skywalker_x5 +++ b/ROMFS/px4fmu_common/init.d/3032_skywalker_x5 @@ -20,7 +20,7 @@ sh /etc/init.d/rc.fw_defaults -if [ $AUTOCNF == yes ] +if [ $AUTOCNF == yes -o $NEW_DEFAULTS == 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 c7ce143ac4d6..6a2fe4621fe2 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 -o $NEW_DEFAULTS == 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 a83098028ed6..e0fc74aa8185 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 -o $NEW_DEFAULTS == yes ] then param set NAV_LOITER_RAD 150 param set FW_AIRSPD_MAX 30 diff --git a/ROMFS/px4fmu_common/init.d/3036_pigeon b/ROMFS/px4fmu_common/init.d/3036_pigeon index ed7e88cb6c13..f9dbd95f9020 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 -o $NEW_DEFAULTS == 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 c383c2e589f0..2d6992a694d0 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 -o $NEW_DEFAULTS == yes ] then #################################### diff --git a/ROMFS/px4fmu_common/init.d/3100_tbs_caipirinha b/ROMFS/px4fmu_common/init.d/3100_tbs_caipirinha index 1091803a16ab..0ae219af5871 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 -o $NEW_DEFAULTS == yes ] then param set FW_AIRSPD_MAX 25 param set FW_AIRSPD_MIN 12.5 diff --git a/ROMFS/px4fmu_common/init.d/4003_qavr5 b/ROMFS/px4fmu_common/init.d/4003_qavr5 index 4e5f64133263..e5649a5b0e4e 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 -o $NEW_DEFAULTS == yes ] then param set MC_ROLL_P 8.0 param set MC_ROLLRATE_P 0.08 diff --git a/ROMFS/px4fmu_common/init.d/4009_qav250 b/ROMFS/px4fmu_common/init.d/4009_qav250 index dc92f5eb5afa..1ba6872623ed 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 -o $NEW_DEFAULTS == yes ] then param set MC_ROLL_P 6.0 param set MC_ROLLRATE_P 0.14 diff --git a/ROMFS/px4fmu_common/init.d/4010_dji_f330 b/ROMFS/px4fmu_common/init.d/4010_dji_f330 index 230323371a75..9ba2a7a32505 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 -o $NEW_DEFAULTS == 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 be3321f62573..1a0f615487a1 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 -o $NEW_DEFAULTS == 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 7a7b565f6a44..3acd585604d9 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 -o $NEW_DEFAULTS == 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 b68bf8408545..f31614e62786 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 -o $NEW_DEFAULTS == yes ] then # Set all params here, then disable autoconfig param set MC_ROLL_P 6.5 diff --git a/ROMFS/px4fmu_common/init.d/4020_hk_micro_pcb b/ROMFS/px4fmu_common/init.d/4020_hk_micro_pcb index f16cd70db0b1..d167893519e5 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 -o $NEW_DEFAULTS == 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_solo b/ROMFS/px4fmu_common/init.d/4030_solo index ce02c41e14fe..e84b895fad38 100644 --- a/ROMFS/px4fmu_common/init.d/4030_solo +++ b/ROMFS/px4fmu_common/init.d/4030_solo @@ -16,7 +16,7 @@ sh /etc/init.d/rc.mc_defaults -if [ $AUTOCNF == yes ] +if [ $AUTOCNF == yes -o $NEW_DEFAULTS == yes ] then # tuning param set MC_PITCHRATE_P 0.11 diff --git a/ROMFS/px4fmu_common/init.d/4040_reaper b/ROMFS/px4fmu_common/init.d/4040_reaper index 57ad4fa3520b..20b469417dfb 100644 --- a/ROMFS/px4fmu_common/init.d/4040_reaper +++ b/ROMFS/px4fmu_common/init.d/4040_reaper @@ -10,7 +10,7 @@ sh /etc/init.d/rc.mc_defaults -if [ $AUTOCNF == yes ] +if [ $AUTOCNF == yes -o $NEW_DEFAULTS == 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 f636cd88279f..c8f5e5135901 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 -o $NEW_DEFAULTS == yes ] then param set MC_ROLL_P 8.0 param set MC_ROLLRATE_P 0.19 diff --git a/ROMFS/px4fmu_common/init.d/4051_s250aq b/ROMFS/px4fmu_common/init.d/4051_s250aq index 473c11e647d6..10bcda6f182f 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 -o $NEW_DEFAULTS == yes ] then param set MC_ROLL_P 8.0 param set MC_ROLLRATE_P 0.19 diff --git a/ROMFS/px4fmu_common/init.d/4060_dji_matrice_100 b/ROMFS/px4fmu_common/init.d/4060_dji_matrice_100 index 1366f42c8725..0737f9d59fb6 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 -o $NEW_DEFAULTS == yes ] then param set MC_ROLL_P 6.5 param set MC_ROLLRATE_P 0.05 diff --git a/ROMFS/px4fmu_common/init.d/4070_aerofc b/ROMFS/px4fmu_common/init.d/4070_aerofc index f9a6d8a99208..637562807fef 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 -o $NEW_DEFAULTS == 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 9ec94c2638dd..de222228ad67 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 -o $NEW_DEFAULTS == yes ] then param set MC_ROLL_P 2.0 param set MC_ROLLRATE_P 0.05 diff --git a/ROMFS/px4fmu_common/init.d/4090_nanomind b/ROMFS/px4fmu_common/init.d/4090_nanomind index 0d16f79c5ba7..806962fc951a 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 -o $NEW_DEFAULTS == yes ] then param set MC_ROLL_P 8.0 param set MC_ROLLRATE_P 0.19 diff --git a/ROMFS/px4fmu_common/init.d/4900_crazyflie b/ROMFS/px4fmu_common/init.d/4900_crazyflie index ef43b2282c10..1f8d5fcd8fbe 100644 --- a/ROMFS/px4fmu_common/init.d/4900_crazyflie +++ b/ROMFS/px4fmu_common/init.d/4900_crazyflie @@ -18,7 +18,7 @@ sh /etc/init.d/4001_quad_x -if [ $AUTOCNF == yes ] +if [ $AUTOCNF == yes -o $NEW_DEFAULTS == yes ] then param set COM_RC_IN_MODE 2 param set BAT_N_CELLS 1 diff --git a/ROMFS/px4fmu_common/init.d/50002_traxxas_stampede_2wd b/ROMFS/px4fmu_common/init.d/50002_traxxas_stampede_2wd index c229b1453c09..2bf966f1d992 100644 --- a/ROMFS/px4fmu_common/init.d/50002_traxxas_stampede_2wd +++ b/ROMFS/px4fmu_common/init.d/50002_traxxas_stampede_2wd @@ -15,7 +15,7 @@ sh /etc/init.d/rc.gnd_defaults -if [ $AUTOCNF == yes ] +if [ $AUTOCNF == yes -o $NEW_DEFAULTS == yes ] then param set BAT_N_CELLS 7 diff --git a/ROMFS/px4fmu_common/init.d/rc.axialracing_ax10_defaults b/ROMFS/px4fmu_common/init.d/rc.axialracing_ax10_defaults index 7caac82b5425..0419ff5c6719 100644 --- a/ROMFS/px4fmu_common/init.d/rc.axialracing_ax10_defaults +++ b/ROMFS/px4fmu_common/init.d/rc.axialracing_ax10_defaults @@ -4,7 +4,7 @@ set VEHICLE_TYPE ugv # 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 -o $NEW_DEFAULTS == yes ] then # PWM default value for "disarmed" mode # this centers the steering and throttle, which means no motion diff --git a/ROMFS/px4fmu_common/init.d/rc.fw_defaults b/ROMFS/px4fmu_common/init.d/rc.fw_defaults index 56a15e37d662..853f9a20fb53 100644 --- a/ROMFS/px4fmu_common/init.d/rc.fw_defaults +++ b/ROMFS/px4fmu_common/init.d/rc.fw_defaults @@ -2,7 +2,7 @@ set VEHICLE_TYPE fw -if [ $AUTOCNF == yes ] +if [ $AUTOCNF == yes -o $NEW_DEFAULTS == yes ] then # # Default parameters for FW diff --git a/ROMFS/px4fmu_common/init.d/rc.gnd_defaults b/ROMFS/px4fmu_common/init.d/rc.gnd_defaults index 556098f92426..88361a4eb636 100644 --- a/ROMFS/px4fmu_common/init.d/rc.gnd_defaults +++ b/ROMFS/px4fmu_common/init.d/rc.gnd_defaults @@ -2,7 +2,7 @@ set VEHICLE_TYPE ugv -if [ $AUTOCNF == yes ] +if [ $AUTOCNF == yes -o $NEW_DEFAULTS == yes ] then # # Default parameters for UGVs diff --git a/ROMFS/px4fmu_common/init.d/rc.mc_defaults b/ROMFS/px4fmu_common/init.d/rc.mc_defaults index 6f04791f61ef..39ab3a38adf7 100644 --- a/ROMFS/px4fmu_common/init.d/rc.mc_defaults +++ b/ROMFS/px4fmu_common/init.d/rc.mc_defaults @@ -2,7 +2,7 @@ set VEHICLE_TYPE mc -if [ $AUTOCNF == yes ] +if [ $AUTOCNF == yes -o $NEW_DEFAULTS == yes ] then param set NAV_ACC_RAD 2.0 param set RTL_RETURN_ALT 30.0 diff --git a/ROMFS/px4fmu_common/init.d/rc.vtol_defaults b/ROMFS/px4fmu_common/init.d/rc.vtol_defaults index f4580b252285..486dfc4abd28 100644 --- a/ROMFS/px4fmu_common/init.d/rc.vtol_defaults +++ b/ROMFS/px4fmu_common/init.d/rc.vtol_defaults @@ -2,7 +2,7 @@ set VEHICLE_TYPE vtol -if [ $AUTOCNF == yes ] +if [ $AUTOCNF == yes -o $NEW_DEFAULTS == yes ] then param set MC_ROLL_P 6.0 param set MC_PITCH_P 6.0 diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS index e8e57397c828..af64610c72c5 100644 --- a/ROMFS/px4fmu_common/init.d/rcS +++ b/ROMFS/px4fmu_common/init.d/rcS @@ -33,6 +33,15 @@ set +e # UART7 /dev/ttyS5 ? # UART8 /dev/ttyS6 CONSOLE +# +# Configuration defaults +# +# Increment this variable if the system default configuration +# changes significantly. This will not wipe the param storage +# but force setting the airframe parameters again. +# +set DEFAULTS_VER 1 + # # Mount the procfs. # @@ -151,16 +160,16 @@ then set AUTOCNF yes else set AUTOCNF no + fi - # - # Release 1.4.0 transitional support: - # set to old default if unconfigured. - # this preserves the previous behaviour - # - if param compare BAT_N_CELLS 0 - then - param set BAT_N_CELLS 3 - fi + # + # Allow overriding airframe defaults as we change them + # + if param compare SYS_PARAM_VER ${DEFAULTS_VER} + then + set NEW_DEFAULTS no + else + set NEW_DEFAULTS yes fi # @@ -283,7 +292,7 @@ then # # If autoconfig parameter was set, reset it and save parameters # - if [ $AUTOCNF == yes ] + if [ $AUTOCNF == yes -o $NEW_DEFAULTS == yes ] then # Disable safety switch by default on Pixracer if ver hwcmp PX4FMU_V4 @@ -294,6 +303,14 @@ then fi unset AUTOCNF + if [ $NEW_DEFAULTS == yes ] + then + param set SYS_PARAM_VER ${DEFAULTS_VER} + param save + set NEW_DEFAULTS no + reboot + fi + set IO_PRESENT no if [ $USE_IO == yes ]