From b06f7f4f2e47dbaf33b255c9ecdffaa51f35f4a4 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 17 Nov 2014 14:56:11 +0100 Subject: [PATCH 1/5] Reduce ROMFS footprint --- ROMFS/px4fmu_common/init.d/rc.interface | 21 +++++++++++---------- 1 file changed, 11 insertions(+), 10 deletions(-) diff --git a/ROMFS/px4fmu_common/init.d/rc.interface b/ROMFS/px4fmu_common/init.d/rc.interface index e44cd0953d..10c6d75118 100644 --- a/ROMFS/px4fmu_common/init.d/rc.interface +++ b/ROMFS/px4fmu_common/init.d/rc.interface @@ -8,12 +8,11 @@ then # # Load mixer # - set MIXERSD /fs/microsd/etc/mixers/$MIXER.mix #Use the mixer file from the SD-card if it exists - if [ -f $MIXERSD ] + if [ -f /fs/microsd/etc/mixers/$MIXER.mix ] then - set MIXER_FILE $MIXERSD + set MIXER_FILE /fs/microsd/etc/mixers/$MIXER.mix else set MIXER_FILE /etc/mixers/$MIXER.mix fi @@ -35,19 +34,21 @@ then echo "[init] Mixer loaded: $MIXER_FILE" else echo "[init] Error loading mixer: $MIXER_FILE" - tone_alarm $TUNE_OUT_ERROR + tone_alarm $TUNE_ERR fi + + unset MIXER_FILE else if [ $MIXER != skip ] then echo "[init] Mixer not defined" - tone_alarm $TUNE_OUT_ERROR + tone_alarm $TUNE_ERR fi fi if [ $OUTPUT_MODE == fmu -o $OUTPUT_MODE == io ] then - if [ $PWM_OUTPUTS != none ] + if [ $PWM_OUT != none ] then # # Set PWM output frequency @@ -55,7 +56,7 @@ then if [ $PWM_RATE != none ] then echo "[init] Set PWM rate: $PWM_RATE" - pwm rate -c $PWM_OUTPUTS -r $PWM_RATE + pwm rate -c $PWM_OUT -r $PWM_RATE fi # @@ -64,17 +65,17 @@ then if [ $PWM_DISARMED != none ] then echo "[init] Set PWM disarmed: $PWM_DISARMED" - pwm disarmed -c $PWM_OUTPUTS -p $PWM_DISARMED + pwm disarmed -c $PWM_OUT -p $PWM_DISARMED fi if [ $PWM_MIN != none ] then echo "[init] Set PWM min: $PWM_MIN" - pwm min -c $PWM_OUTPUTS -p $PWM_MIN + pwm min -c $PWM_OUT -p $PWM_MIN fi if [ $PWM_MAX != none ] then echo "[init] Set PWM max: $PWM_MAX" - pwm max -c $PWM_OUTPUTS -p $PWM_MAX + pwm max -c $PWM_OUT -p $PWM_MAX fi fi From 489b4c4839a3796c520629850bc703c42bef636c Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 17 Nov 2014 14:58:29 +0100 Subject: [PATCH 2/5] Reduce too chatty content, de-allocate non-needed string buffers --- ROMFS/px4fmu_common/init.d/rc.interface | 14 +-- ROMFS/px4fmu_common/init.d/rcS | 150 ++++++++++++------------ 2 files changed, 82 insertions(+), 82 deletions(-) diff --git a/ROMFS/px4fmu_common/init.d/rc.interface b/ROMFS/px4fmu_common/init.d/rc.interface index 10c6d75118..0f703c3b38 100644 --- a/ROMFS/px4fmu_common/init.d/rc.interface +++ b/ROMFS/px4fmu_common/init.d/rc.interface @@ -31,9 +31,9 @@ then if mixer load $OUTPUT_DEV $MIXER_FILE then - echo "[init] Mixer loaded: $MIXER_FILE" + echo "[i] Mixer: $MIXER_FILE" else - echo "[init] Error loading mixer: $MIXER_FILE" + echo "[i] Error loading mixer: $MIXER_FILE" tone_alarm $TUNE_ERR fi @@ -41,7 +41,7 @@ then else if [ $MIXER != skip ] then - echo "[init] Mixer not defined" + echo "[i] Mixer not defined" tone_alarm $TUNE_ERR fi fi @@ -55,7 +55,7 @@ then # if [ $PWM_RATE != none ] then - echo "[init] Set PWM rate: $PWM_RATE" + echo "[i] PWM rate: $PWM_RATE" pwm rate -c $PWM_OUT -r $PWM_RATE fi @@ -64,17 +64,17 @@ then # if [ $PWM_DISARMED != none ] then - echo "[init] Set PWM disarmed: $PWM_DISARMED" + echo "[i] PWM disarmed: $PWM_DISARMED" pwm disarmed -c $PWM_OUT -p $PWM_DISARMED fi if [ $PWM_MIN != none ] then - echo "[init] Set PWM min: $PWM_MIN" + echo "[i] PWM min: $PWM_MIN" pwm min -c $PWM_OUT -p $PWM_MIN fi if [ $PWM_MAX != none ] then - echo "[init] Set PWM max: $PWM_MAX" + echo "[i] PWM max: $PWM_MAX" pwm max -c $PWM_OUT -p $PWM_MAX fi fi diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS index f9c8226350..7532d38115 100644 --- a/ROMFS/px4fmu_common/init.d/rcS +++ b/ROMFS/px4fmu_common/init.d/rcS @@ -7,25 +7,25 @@ # set MODE autostart -set RC_FILE /fs/microsd/etc/rc.txt -set CONFIG_FILE /fs/microsd/etc/config.txt -set EXTRAS_FILE /fs/microsd/etc/extras.txt +set FRC /fs/microsd/etc/rc.txt +set FCONFIG /fs/microsd/etc/config.txt +set FEXTRAS /fs/microsd/etc/extras.txt -set TUNE_OUT_ERROR ML<> $LOG_FILE - tone_alarm $TUNE_OUT_ERROR + tone_alarm $TUNE_ERR fi else echo "PX4IO update failed" >> $LOG_FILE - tone_alarm $TUNE_OUT_ERROR + tone_alarm $TUNE_ERR fi fi if [ $IO_PRESENT == no ] then - echo "[init] ERROR: PX4IO not found" - tone_alarm $TUNE_OUT_ERROR + echo "[i] ERROR: PX4IO not found" + tone_alarm $TUNE_ERR fi fi @@ -251,7 +252,7 @@ then then # Need IO for output but it not present, disable output set OUTPUT_MODE none - echo "[init] ERROR: PX4IO not found, disabling output" + echo "[i] ERROR: PX4IO not found, disabling output" # Avoid using ttyS0 for MAVLink on FMUv1 if ver hwcmp PX4FMU_V1 @@ -294,33 +295,31 @@ then then if param compare UAVCAN_ENABLE 0 then - echo "[init] OVERRIDING UAVCAN_ENABLE = 1" + echo "[i] OVERRIDING UAVCAN_ENABLE = 1" param set UAVCAN_ENABLE 1 fi fi if [ $OUTPUT_MODE == io -o $OUTPUT_MODE == uavcan_esc ] then - echo "[init] Use PX4IO PWM as primary output" if px4io start then - echo "[init] PX4IO started" + echo "[i] PX4IO started" sh /etc/init.d/rc.io else - echo "[init] ERROR: PX4IO start failed" - tone_alarm $TUNE_OUT_ERROR + echo "[i] ERROR: PX4IO start failed" + tone_alarm $TUNE_ERR fi fi if [ $OUTPUT_MODE == fmu -o $OUTPUT_MODE == ardrone ] then - echo "[init] Use FMU as primary output" if fmu mode_$FMU_MODE then - echo "[init] FMU mode_$FMU_MODE started" + echo "[i] FMU mode_$FMU_MODE started" else - echo "[init] ERROR: FMU mode_$FMU_MODE start failed" - tone_alarm $TUNE_OUT_ERROR + echo "[i] ERROR: FMU mode_$FMU_MODE start failed" + tone_alarm $TUNE_ERR fi if ver hwcmp PX4FMU_V1 @@ -338,36 +337,34 @@ then if [ $OUTPUT_MODE == mkblctrl ] then - echo "[init] Use MKBLCTRL as primary output" set MKBLCTRL_ARG "" - if [ $MKBLCTRL_MODE == x ] + if [ $MK_MODE == x ] then set MKBLCTRL_ARG "-mkmode x" fi - if [ $MKBLCTRL_MODE == + ] + if [ $MK_MODE == + ] then set MKBLCTRL_ARG "-mkmode +" fi if mkblctrl $MKBLCTRL_ARG then - echo "[init] MKBLCTRL started" + echo "[i] MK started" else - echo "[init] ERROR: MKBLCTRL start failed" - tone_alarm $TUNE_OUT_ERROR + echo "[i] ERROR: MK start failed" + tone_alarm $TUNE_ERR fi fi if [ $OUTPUT_MODE == hil ] then - echo "[init] Use HIL as primary output" if hil mode_port2_pwm8 then - echo "[init] HIL output started" + echo "[i] HIL output started" else - echo "[init] ERROR: HIL output start failed" - tone_alarm $TUNE_OUT_ERROR + echo "[i] ERROR: HIL output start failed" + tone_alarm $TUNE_ERR fi fi @@ -380,11 +377,11 @@ then then if px4io start then - echo "[init] PX4IO started" + echo "[i] PX4IO started" sh /etc/init.d/rc.io else - echo "[init] ERROR: PX4IO start failed" - tone_alarm $TUNE_OUT_ERROR + echo "[i] ERROR: PX4IO start failed" + tone_alarm $TUNE_ERR fi fi else @@ -392,10 +389,10 @@ then then if fmu mode_$FMU_MODE then - echo "[init] FMU mode_$FMU_MODE started" + echo "[i] FMU mode_$FMU_MODE started" else - echo "[init] ERROR: FMU mode_$FMU_MODE start failed" - tone_alarm $TUNE_OUT_ERROR + echo "[i] ERROR: FMU mode_$FMU_MODE start failed" + tone_alarm $TUNE_ERR fi if ver hwcmp PX4FMU_V1 @@ -413,23 +410,24 @@ then fi fi - if [ $MAVLINK_FLAGS == default ] + if [ $MAVLINK_F == default ] then # Normal mode, use baudrate 57600 (default) and data rate 1000 bytes/s if [ $TTYS1_BUSY == yes ] then # Start MAVLink on ttyS0, because FMU ttyS1 pins configured as something else - set MAVLINK_FLAGS "-r 1000 -d /dev/ttyS0" + set MAVLINK_F "-r 1000 -d /dev/ttyS0" # Exit from nsh to free port for mavlink set EXIT_ON_END yes else # Start MAVLink on default port: ttyS1 - set MAVLINK_FLAGS "-r 1000" + set MAVLINK_F "-r 1000" fi fi - mavlink start $MAVLINK_FLAGS + mavlink start $MAVLINK_F + unset MAVLINK_F # # UAVCAN @@ -444,15 +442,16 @@ then if [ $GPS == yes ] then - echo "[init] Start GPS" + echo "[i] Start GPS" if [ $GPS_FAKE == yes ] then - echo "[init] Faking GPS" + echo "[i] Faking GPS" gps start -f else gps start fi fi + unset GPS_FAKE # # Start up ARDrone Motor interface @@ -467,7 +466,7 @@ then # if [ $VEHICLE_TYPE == fw ] then - echo "[init] Vehicle type: FIXED WING" + echo "[i] FIXED WING" if [ $MIXER == none ] then @@ -481,13 +480,13 @@ then set MAV_TYPE 1 fi - param set MAV_TYPE $MAV_TYPE + #param set MAV_TYPE $MAV_TYPE # Load mixer and configure outputs sh /etc/init.d/rc.interface # Start standard fixedwing apps - if [ $LOAD_DEFAULT_APPS == yes ] + if [ $LOAD_DAPPS == yes ] then sh /etc/init.d/rc.fw_apps fi @@ -498,11 +497,11 @@ then # if [ $VEHICLE_TYPE == mc ] then - echo "[init] Vehicle type: MULTICOPTER" + echo "[i] MULTICOPTER" if [ $MIXER == none ] then - echo "Default mixer for multicopter not defined" + echo "Mixer undefined" fi if [ $MAV_TYPE == none ] @@ -546,7 +545,7 @@ then sh /etc/init.d/rc.interface # Start standard multicopter apps - if [ $LOAD_DEFAULT_APPS == yes ] + if [ $LOAD_DAPPS == yes ] then sh /etc/init.d/rc.mc_apps fi @@ -562,22 +561,23 @@ then # if [ $VEHICLE_TYPE == none ] then - echo "[init] Vehicle type: No autostart ID found" + echo "[i] No autostart ID found" fi # Start any custom addons - if [ -f $EXTRAS_FILE ] + if [ -f $FEXTRAS ] then - echo "[init] Starting addons script: $EXTRAS_FILE" - sh $EXTRAS_FILE + echo "[i] Addons script: $FEXTRAS" + sh $FEXTRAS else - echo "[init] No addons script: $EXTRAS_FILE" + echo "[i] No addons script: $FEXTRAS" fi + unset FEXTRAS if [ $EXIT_ON_END == yes ] then - echo "[init] Exit from nsh" + echo "Exit from nsh" exit fi From b808cc9a1b498aedfaccf35777c440e7ea286ac4 Mon Sep 17 00:00:00 2001 From: Thomas Gubler Date: Mon, 17 Nov 2014 16:38:20 +0100 Subject: [PATCH 3/5] fix variable name in rc.uavcan --- ROMFS/px4fmu_common/init.d/rc.uavcan | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ROMFS/px4fmu_common/init.d/rc.uavcan b/ROMFS/px4fmu_common/init.d/rc.uavcan index 9a470a6b8d..55a3726096 100644 --- a/ROMFS/px4fmu_common/init.d/rc.uavcan +++ b/ROMFS/px4fmu_common/init.d/rc.uavcan @@ -13,6 +13,6 @@ then echo "[init] UAVCAN started" else echo "[init] ERROR: Could not start UAVCAN" - tone_alarm $TUNE_OUT_ERROR + tone_alarm $TUNE_ERR fi fi From 32f88bbe847bfeb7d040345df6fb534d223fb2bb Mon Sep 17 00:00:00 2001 From: Thomas Gubler Date: Mon, 17 Nov 2014 17:02:57 +0100 Subject: [PATCH 4/5] rename PWM_OUTPUTS to PWM_OUT in all files --- ROMFS/px4fmu_common/init.d/10015_tbs_discovery | 2 +- ROMFS/px4fmu_common/init.d/10016_3dr_iris | 2 +- ROMFS/px4fmu_common/init.d/10017_steadidrone_qu4d | 2 +- ROMFS/px4fmu_common/init.d/11001_hexa_cox | 2 +- ROMFS/px4fmu_common/init.d/12001_octo_cox | 2 +- ROMFS/px4fmu_common/init.d/3030_io_camflyer | 2 +- ROMFS/px4fmu_common/init.d/3031_phantom | 2 +- ROMFS/px4fmu_common/init.d/3033_wingwing | 2 +- ROMFS/px4fmu_common/init.d/4001_quad_x | 2 +- ROMFS/px4fmu_common/init.d/5001_quad_+ | 2 +- ROMFS/px4fmu_common/init.d/6001_hexa_x | 2 +- ROMFS/px4fmu_common/init.d/7001_hexa_+ | 2 +- ROMFS/px4fmu_common/init.d/8001_octo_x | 2 +- ROMFS/px4fmu_common/init.d/9001_octo_+ | 2 +- 14 files changed, 14 insertions(+), 14 deletions(-) diff --git a/ROMFS/px4fmu_common/init.d/10015_tbs_discovery b/ROMFS/px4fmu_common/init.d/10015_tbs_discovery index c8379e3a1a..7801bbed9f 100644 --- a/ROMFS/px4fmu_common/init.d/10015_tbs_discovery +++ b/ROMFS/px4fmu_common/init.d/10015_tbs_discovery @@ -26,5 +26,5 @@ fi set MIXER FMU_quad_w -set PWM_OUTPUTS 1234 +set PWM_OUT 1234 set PWM_MIN 1200 diff --git a/ROMFS/px4fmu_common/init.d/10016_3dr_iris b/ROMFS/px4fmu_common/init.d/10016_3dr_iris index 0b422de7e2..dc11192f13 100644 --- a/ROMFS/px4fmu_common/init.d/10016_3dr_iris +++ b/ROMFS/px4fmu_common/init.d/10016_3dr_iris @@ -29,7 +29,7 @@ fi set MIXER FMU_quad_w -set PWM_OUTPUTS 1234 +set PWM_OUT 1234 set PWM_MIN 1200 set PWM_MAX 1950 diff --git a/ROMFS/px4fmu_common/init.d/10017_steadidrone_qu4d b/ROMFS/px4fmu_common/init.d/10017_steadidrone_qu4d index a621de7ce8..d79a527351 100644 --- a/ROMFS/px4fmu_common/init.d/10017_steadidrone_qu4d +++ b/ROMFS/px4fmu_common/init.d/10017_steadidrone_qu4d @@ -31,4 +31,4 @@ set MIXER FMU_quad_w set PWM_MIN 1210 set PWM_MAX 2100 -set PWM_OUTPUTS 1234 +set PWM_OUT 1234 diff --git a/ROMFS/px4fmu_common/init.d/11001_hexa_cox b/ROMFS/px4fmu_common/init.d/11001_hexa_cox index e4d96fbd56..50f717e3df 100644 --- a/ROMFS/px4fmu_common/init.d/11001_hexa_cox +++ b/ROMFS/px4fmu_common/init.d/11001_hexa_cox @@ -10,4 +10,4 @@ sh /etc/init.d/rc.mc_defaults set MIXER FMU_hexa_cox # Need to set all 8 channels -set PWM_OUTPUTS 12345678 +set PWM_OUT 12345678 diff --git a/ROMFS/px4fmu_common/init.d/12001_octo_cox b/ROMFS/px4fmu_common/init.d/12001_octo_cox index f820251ad3..e0a8381851 100644 --- a/ROMFS/px4fmu_common/init.d/12001_octo_cox +++ b/ROMFS/px4fmu_common/init.d/12001_octo_cox @@ -9,4 +9,4 @@ sh /etc/init.d/rc.mc_defaults set MIXER FMU_octo_cox -set PWM_OUTPUTS 12345678 +set PWM_OUT 12345678 diff --git a/ROMFS/px4fmu_common/init.d/3030_io_camflyer b/ROMFS/px4fmu_common/init.d/3030_io_camflyer index 0f0cb3a89f..fe0269557f 100644 --- a/ROMFS/px4fmu_common/init.d/3030_io_camflyer +++ b/ROMFS/px4fmu_common/init.d/3030_io_camflyer @@ -4,5 +4,5 @@ sh /etc/init.d/rc.fw_defaults set MIXER FMU_Q # Provide ESC a constant 1000 us pulse while disarmed -set PWM_OUTPUTS 4 +set PWM_OUT 4 set PWM_DISARMED 1000 diff --git a/ROMFS/px4fmu_common/init.d/3031_phantom b/ROMFS/px4fmu_common/init.d/3031_phantom index a7749cba6e..d2b2f6c85c 100644 --- a/ROMFS/px4fmu_common/init.d/3031_phantom +++ b/ROMFS/px4fmu_common/init.d/3031_phantom @@ -36,5 +36,5 @@ fi set MIXER phantom # Provide ESC a constant 1000 us pulse -set PWM_OUTPUTS 4 +set PWM_OUT 4 set PWM_DISARMED 1000 diff --git a/ROMFS/px4fmu_common/init.d/3033_wingwing b/ROMFS/px4fmu_common/init.d/3033_wingwing index 919eefb4a8..64c3fb5fb9 100644 --- a/ROMFS/px4fmu_common/init.d/3033_wingwing +++ b/ROMFS/px4fmu_common/init.d/3033_wingwing @@ -44,5 +44,5 @@ fi set MIXER wingwing # Provide ESC a constant 1000 us pulse -set PWM_OUTPUTS 4 +set PWM_OUT 4 set PWM_DISARMED 1000 diff --git a/ROMFS/px4fmu_common/init.d/4001_quad_x b/ROMFS/px4fmu_common/init.d/4001_quad_x index 8fe8961c5c..4677f9fc3a 100644 --- a/ROMFS/px4fmu_common/init.d/4001_quad_x +++ b/ROMFS/px4fmu_common/init.d/4001_quad_x @@ -9,4 +9,4 @@ sh /etc/init.d/rc.mc_defaults set MIXER FMU_quad_x -set PWM_OUTPUTS 1234 +set PWM_OUT 1234 diff --git a/ROMFS/px4fmu_common/init.d/5001_quad_+ b/ROMFS/px4fmu_common/init.d/5001_quad_+ index 5512aa738a..c789113919 100644 --- a/ROMFS/px4fmu_common/init.d/5001_quad_+ +++ b/ROMFS/px4fmu_common/init.d/5001_quad_+ @@ -9,4 +9,4 @@ sh /etc/init.d/rc.mc_defaults set MIXER FMU_quad_+ -set PWM_OUTPUTS 1234 +set PWM_OUT 1234 diff --git a/ROMFS/px4fmu_common/init.d/6001_hexa_x b/ROMFS/px4fmu_common/init.d/6001_hexa_x index 1043ad8adb..0df25b11a1 100644 --- a/ROMFS/px4fmu_common/init.d/6001_hexa_x +++ b/ROMFS/px4fmu_common/init.d/6001_hexa_x @@ -10,4 +10,4 @@ sh /etc/init.d/rc.mc_defaults set MIXER FMU_hexa_x # Need to set all 8 channels -set PWM_OUTPUTS 12345678 +set PWM_OUT 12345678 diff --git a/ROMFS/px4fmu_common/init.d/7001_hexa_+ b/ROMFS/px4fmu_common/init.d/7001_hexa_+ index 84ab88883c..16c772ee1e 100644 --- a/ROMFS/px4fmu_common/init.d/7001_hexa_+ +++ b/ROMFS/px4fmu_common/init.d/7001_hexa_+ @@ -10,4 +10,4 @@ sh /etc/init.d/rc.mc_defaults set MIXER FMU_hexa_+ # Need to set all 8 channels -set PWM_OUTPUTS 12345678 +set PWM_OUT 12345678 diff --git a/ROMFS/px4fmu_common/init.d/8001_octo_x b/ROMFS/px4fmu_common/init.d/8001_octo_x index 74e304cd96..bae36737f9 100644 --- a/ROMFS/px4fmu_common/init.d/8001_octo_x +++ b/ROMFS/px4fmu_common/init.d/8001_octo_x @@ -9,4 +9,4 @@ sh /etc/init.d/rc.mc_defaults set MIXER FMU_octo_x -set PWM_OUTPUTS 12345678 +set PWM_OUT 12345678 diff --git a/ROMFS/px4fmu_common/init.d/9001_octo_+ b/ROMFS/px4fmu_common/init.d/9001_octo_+ index f7c06c6c80..ca5439f68f 100644 --- a/ROMFS/px4fmu_common/init.d/9001_octo_+ +++ b/ROMFS/px4fmu_common/init.d/9001_octo_+ @@ -9,4 +9,4 @@ sh /etc/init.d/rc.mc_defaults set MIXER FMU_octo_+ -set PWM_OUTPUTS 12345678 \ No newline at end of file +set PWM_OUT 12345678 From 1b47f05b1409f5006f288458b5b176a855174e7f Mon Sep 17 00:00:00 2001 From: Thomas Gubler Date: Mon, 17 Nov 2014 17:10:47 +0100 Subject: [PATCH 5/5] rename DO_AUTOCONFIG to AUTOCNF in all files --- ROMFS/px4fmu_common/init.d/10015_tbs_discovery | 2 +- ROMFS/px4fmu_common/init.d/10016_3dr_iris | 2 +- ROMFS/px4fmu_common/init.d/10017_steadidrone_qu4d | 2 +- ROMFS/px4fmu_common/init.d/1005_rc_fw_Malolo1.hil | 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/3100_tbs_caipirinha | 4 ++-- ROMFS/px4fmu_common/init.d/4008_ardrone | 4 ++-- 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/4020_hk_micro_pcb | 2 +- ROMFS/px4fmu_common/init.d/rc.fw_defaults | 4 ++-- ROMFS/px4fmu_common/init.d/rc.mc_defaults | 2 +- 15 files changed, 18 insertions(+), 18 deletions(-) diff --git a/ROMFS/px4fmu_common/init.d/10015_tbs_discovery b/ROMFS/px4fmu_common/init.d/10015_tbs_discovery index 7801bbed9f..c1b366de83 100644 --- a/ROMFS/px4fmu_common/init.d/10015_tbs_discovery +++ b/ROMFS/px4fmu_common/init.d/10015_tbs_discovery @@ -7,7 +7,7 @@ sh /etc/init.d/rc.mc_defaults -if [ $DO_AUTOCONFIG == yes ] +if [ $AUTOCNF == yes ] then # TODO review MC_YAWRATE_I param set MC_ROLL_P 8.0 diff --git a/ROMFS/px4fmu_common/init.d/10016_3dr_iris b/ROMFS/px4fmu_common/init.d/10016_3dr_iris index dc11192f13..3879737a8e 100644 --- a/ROMFS/px4fmu_common/init.d/10016_3dr_iris +++ b/ROMFS/px4fmu_common/init.d/10016_3dr_iris @@ -7,7 +7,7 @@ sh /etc/init.d/rc.mc_defaults -if [ $DO_AUTOCONFIG == 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 d79a527351..57f77754c8 100644 --- a/ROMFS/px4fmu_common/init.d/10017_steadidrone_qu4d +++ b/ROMFS/px4fmu_common/init.d/10017_steadidrone_qu4d @@ -7,7 +7,7 @@ sh /etc/init.d/rc.mc_defaults -if [ $DO_AUTOCONFIG == 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/1005_rc_fw_Malolo1.hil b/ROMFS/px4fmu_common/init.d/1005_rc_fw_Malolo1.hil index 00b97d675c..f208b692a0 100644 --- a/ROMFS/px4fmu_common/init.d/1005_rc_fw_Malolo1.hil +++ b/ROMFS/px4fmu_common/init.d/1005_rc_fw_Malolo1.hil @@ -7,7 +7,7 @@ sh /etc/init.d/rc.fw_defaults -if [ $DO_AUTOCONFIG == yes ] +if [ $AUTOCNF == yes ] then param set FW_AIRSPD_MIN 12 param set FW_AIRSPD_TRIM 25 diff --git a/ROMFS/px4fmu_common/init.d/3031_phantom b/ROMFS/px4fmu_common/init.d/3031_phantom index d2b2f6c85c..c7dd1dfc5c 100644 --- a/ROMFS/px4fmu_common/init.d/3031_phantom +++ b/ROMFS/px4fmu_common/init.d/3031_phantom @@ -7,7 +7,7 @@ sh /etc/init.d/rc.fw_defaults -if [ $DO_AUTOCONFIG == 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 26c7c95e67..94363bf6ab 100644 --- a/ROMFS/px4fmu_common/init.d/3032_skywalker_x5 +++ b/ROMFS/px4fmu_common/init.d/3032_skywalker_x5 @@ -7,7 +7,7 @@ sh /etc/init.d/rc.fw_defaults -if [ $DO_AUTOCONFIG == 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 64c3fb5fb9..add905b115 100644 --- a/ROMFS/px4fmu_common/init.d/3033_wingwing +++ b/ROMFS/px4fmu_common/init.d/3033_wingwing @@ -7,7 +7,7 @@ sh /etc/init.d/rc.fw_defaults -if [ $DO_AUTOCONFIG == 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/3100_tbs_caipirinha b/ROMFS/px4fmu_common/init.d/3100_tbs_caipirinha index 9bfd9d9ed5..9eafac1c59 100644 --- a/ROMFS/px4fmu_common/init.d/3100_tbs_caipirinha +++ b/ROMFS/px4fmu_common/init.d/3100_tbs_caipirinha @@ -7,9 +7,9 @@ sh /etc/init.d/rc.fw_defaults -if [ $DO_AUTOCONFIG == yes ] +if [ $AUTOCNF == yes ] then - + # TODO: these are the X5 default parameters, update them to the caipi param set FW_AIRSPD_MIN 15 diff --git a/ROMFS/px4fmu_common/init.d/4008_ardrone b/ROMFS/px4fmu_common/init.d/4008_ardrone index 0488e3928e..c3358ef4c8 100644 --- a/ROMFS/px4fmu_common/init.d/4008_ardrone +++ b/ROMFS/px4fmu_common/init.d/4008_ardrone @@ -8,7 +8,7 @@ sh /etc/init.d/rc.mc_defaults # # Load default params for this platform # -if [ $DO_AUTOCONFIG == yes ] +if [ $AUTOCNF == yes ] then # Set all params here, then disable autoconfig param set MC_ROLL_P 6.0 @@ -24,7 +24,7 @@ then param set MC_YAWRATE_I 0.2 param set MC_YAWRATE_D 0.0 param set MC_YAW_FF 0.8 - + param set BAT_V_SCALING 0.00838095238 fi diff --git a/ROMFS/px4fmu_common/init.d/4010_dji_f330 b/ROMFS/px4fmu_common/init.d/4010_dji_f330 index f0cc052075..8e5dc76b1f 100644 --- a/ROMFS/px4fmu_common/init.d/4010_dji_f330 +++ b/ROMFS/px4fmu_common/init.d/4010_dji_f330 @@ -7,7 +7,7 @@ sh /etc/init.d/4001_quad_x -if [ $DO_AUTOCONFIG == 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/4011_dji_f450 b/ROMFS/px4fmu_common/init.d/4011_dji_f450 index 1ca716a6b3..ea35b3ba9b 100644 --- a/ROMFS/px4fmu_common/init.d/4011_dji_f450 +++ b/ROMFS/px4fmu_common/init.d/4011_dji_f450 @@ -7,7 +7,7 @@ sh /etc/init.d/4001_quad_x -if [ $DO_AUTOCONFIG == yes ] +if [ $AUTOCNF == yes ] then # TODO REVIEW param set MC_ROLL_P 7.0 diff --git a/ROMFS/px4fmu_common/init.d/4012_quad_x_can b/ROMFS/px4fmu_common/init.d/4012_quad_x_can index 5c4a6497a0..b1db1dd9aa 100644 --- a/ROMFS/px4fmu_common/init.d/4012_quad_x_can +++ b/ROMFS/px4fmu_common/init.d/4012_quad_x_can @@ -7,7 +7,7 @@ sh /etc/init.d/4001_quad_x -if [ $DO_AUTOCONFIG == yes ] +if [ $AUTOCNF == yes ] then # TODO REVIEW param set MC_ROLL_P 7.0 diff --git a/ROMFS/px4fmu_common/init.d/4020_hk_micro_pcb b/ROMFS/px4fmu_common/init.d/4020_hk_micro_pcb index 9fe310ddee..a1de19d5df 100644 --- a/ROMFS/px4fmu_common/init.d/4020_hk_micro_pcb +++ b/ROMFS/px4fmu_common/init.d/4020_hk_micro_pcb @@ -9,7 +9,7 @@ echo "HK Micro PCB Quad" sh /etc/init.d/4001_quad_x -if [ $DO_AUTOCONFIG == 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/rc.fw_defaults b/ROMFS/px4fmu_common/init.d/rc.fw_defaults index 3c336f295f..fab2a7f187 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 [ $DO_AUTOCONFIG == yes ] +if [ $AUTOCNF == yes ] then # # Default parameters for FW @@ -15,4 +15,4 @@ then param set FW_T_RLL2THR 15 param set FW_T_SRATE_P 0.01 param set FW_T_TIME_CONST 5 -fi \ No newline at end of file +fi diff --git a/ROMFS/px4fmu_common/init.d/rc.mc_defaults b/ROMFS/px4fmu_common/init.d/rc.mc_defaults index 0df320f49a..307a64c4d5 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 [ $DO_AUTOCONFIG == yes ] +if [ $AUTOCNF == yes ] then param set MC_ROLL_P 7.0 param set MC_ROLLRATE_P 0.1