Merge pull request #1461 from PX4/romfs_clean

Romfs clean
This commit is contained in:
Thomas Gubler
2014-12-13 15:09:47 +01:00
27 changed files with 127 additions and 116 deletions
@@ -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
@@ -26,5 +26,5 @@ fi
set MIXER FMU_quad_w
set PWM_OUTPUTS 1234
set PWM_OUT 1234
set PWM_MIN 1200
+2 -2
View File
@@ -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
@@ -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
@@ -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
@@ -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
@@ -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
+1 -1
View File
@@ -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
+1 -1
View File
@@ -9,4 +9,4 @@ sh /etc/init.d/rc.mc_defaults
set MIXER FMU_octo_cox
set PWM_OUTPUTS 12345678
set PWM_OUT 12345678
+1 -1
View File
@@ -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
+2 -2
View File
@@ -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
@@ -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
+1 -1
View File
@@ -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
+2 -2
View File
@@ -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
@@ -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
@@ -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
+1 -1
View File
@@ -9,4 +9,4 @@ sh /etc/init.d/rc.mc_defaults
set MIXER FMU_quad_x
set PWM_OUTPUTS 1234
set PWM_OUT 1234
+2 -2
View File
@@ -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
+1 -1
View File
@@ -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
+1 -1
View File
@@ -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
+1 -1
View File
@@ -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
+1 -1
View File
@@ -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
+1 -1
View File
@@ -9,4 +9,4 @@ sh /etc/init.d/rc.mc_defaults
set MIXER FMU_quad_+
set PWM_OUTPUTS 1234
set PWM_OUT 1234
+1 -1
View File
@@ -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
+1 -1
View File
@@ -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
+1 -1
View File
@@ -9,4 +9,4 @@ sh /etc/init.d/rc.mc_defaults
set MIXER FMU_octo_x
set PWM_OUTPUTS 12345678
set PWM_OUT 12345678
+1 -1
View File
@@ -9,4 +9,4 @@ sh /etc/init.d/rc.mc_defaults
set MIXER FMU_octo_+
set PWM_OUTPUTS 12345678
set PWM_OUT 12345678
+2 -2
View File
@@ -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
fi
+19 -14
View File
@@ -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 ]
#Use the mixer file from the SD-card if it exists
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
@@ -32,29 +31,32 @@ 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"
tone_alarm $TUNE_OUT_ERROR
echo "[i] Error loading mixer: $MIXER_FILE"
tone_alarm $TUNE_ERR
fi
unset MIXER_FILE
else
if [ $MIXER != skip ]
then
echo "[init] Mixer not defined"
tone_alarm $TUNE_OUT_ERROR
echo "[i] Mixer not defined"
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
#
if [ $PWM_RATE != none ]
then
pwm rate -c $PWM_OUTPUTS -r $PWM_RATE
echo "[i] PWM rate: $PWM_RATE"
pwm rate -c $PWM_OUT -r $PWM_RATE
fi
#
@@ -62,15 +64,18 @@ then
#
if [ $PWM_DISARMED != none ]
then
pwm disarmed -c $PWM_OUTPUTS -p $PWM_DISARMED
echo "[i] PWM disarmed: $PWM_DISARMED"
pwm disarmed -c $PWM_OUT -p $PWM_DISARMED
fi
if [ $PWM_MIN != none ]
then
pwm min -c $PWM_OUTPUTS -p $PWM_MIN
echo "[i] PWM min: $PWM_MIN"
pwm min -c $PWM_OUT -p $PWM_MIN
fi
if [ $PWM_MAX != none ]
then
pwm max -c $PWM_OUTPUTS -p $PWM_MAX
echo "[i] PWM max: $PWM_MAX"
pwm max -c $PWM_OUT -p $PWM_MAX
fi
fi
+1 -1
View File
@@ -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
+1 -1
View File
@@ -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
+75 -69
View File
@@ -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<<CP4CP4CP4CP4CP4
set TUNE_ERR ML<<CP4CP4CP4CP4CP4
#
# Try to mount the microSD card.
#
echo "[init] Looking for microSD..."
echo "[i] Looking for microSD..."
if mount -t vfat /dev/mmcsd0 /fs/microsd
then
set LOG_FILE /fs/microsd/bootlog.txt
echo "[init] microSD mounted: /fs/microsd"
echo "[i] microSD mounted: /fs/microsd"
# Start playing the startup tune
tone_alarm start
else
set LOG_FILE /dev/null
echo "[init] No microSD card found"
echo "[i] No microSD card found"
# Play SOS
tone_alarm error
fi
@@ -34,13 +34,13 @@ fi
# Look for an init script on the microSD card.
# Disable autostart if the script found.
#
if [ -f $RC_FILE ]
if [ -f $FRC ]
then
echo "[init] Executing init script: $RC_FILE"
sh $RC_FILE
echo "[i] Executing init script: $FRC"
sh $FRC
set MODE custom
else
echo "[init] Init script not found: $RC_FILE"
echo "[i] Init script not found: $FRC"
fi
# if this is an APM build then there will be a rc.APM script
@@ -49,17 +49,17 @@ if [ -f /etc/init.d/rc.APM ]
then
if sercon
then
echo "[init] USB interface connected"
echo "[i] USB interface connected"
fi
echo "[init] Running rc.APM"
echo "[i] Running rc.APM"
# if APM startup is successful then nsh will exit
sh /etc/init.d/rc.APM
fi
if [ $MODE == autostart ]
then
echo "[init] AUTOSTART mode"
echo "[i] AUTOSTART mode"
#
# Start CDC/ACM serial driver
@@ -117,31 +117,31 @@ then
set VEHICLE_TYPE none
set MIXER none
set OUTPUT_MODE none
set PWM_OUTPUTS none
set PWM_OUT none
set PWM_RATE none
set PWM_DISARMED none
set PWM_MIN none
set PWM_MAX none
set MKBLCTRL_MODE none
set MK_MODE none
set FMU_MODE pwm
set MAVLINK_FLAGS default
set MAVLINK_F default
set EXIT_ON_END no
set MAV_TYPE none
set LOAD_DEFAULT_APPS yes
set LOAD_DAPPS yes
set GPS yes
set GPS_FAKE no
set FAILSAFE none
#
# Set DO_AUTOCONFIG flag to use it in AUTOSTART scripts
# Set AUTOCNF flag to use it in AUTOSTART scripts
#
if param compare SYS_AUTOCONFIG 1
then
# Wipe out params
param reset_nostart
set DO_AUTOCONFIG yes
set AUTOCNF yes
else
set DO_AUTOCONFIG no
set AUTOCNF no
fi
#
@@ -159,7 +159,7 @@ then
#
if param compare SYS_AUTOSTART 0
then
echo "[init] No autostart"
echo "[i] No autostart"
else
sh /etc/init.d/rc.autostart
fi
@@ -167,18 +167,19 @@ then
#
# Override parameters from user configuration file
#
if [ -f $CONFIG_FILE ]
if [ -f $FCONFIG ]
then
echo "[init] Config: $CONFIG_FILE"
sh $CONFIG_FILE
echo "[i] Config: $FCONFIG"
sh $FCONFIG
else
echo "[init] Config not found: $CONFIG_FILE"
echo "[i] Config not found: $FCONFIG"
fi
unset FCONFIG
#
# If autoconfig parameter was set, reset it and save parameters
#
if [ $DO_AUTOCONFIG == yes ]
if [ $AUTOCNF == yes ]
then
param set SYS_AUTOCONFIG 0
param save
@@ -219,18 +220,18 @@ then
set IO_PRESENT yes
else
echo "PX4IO update failed" >> $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,7 +295,7 @@ 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
@@ -303,11 +304,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
@@ -315,10 +316,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
@@ -337,21 +338,21 @@ then
if [ $OUTPUT_MODE == mkblctrl ]
then
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
@@ -360,10 +361,10 @@ then
then
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
@@ -376,10 +377,11 @@ then
then
if px4io start
then
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
@@ -387,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
@@ -408,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
@@ -439,14 +442,16 @@ then
if [ $GPS == yes ]
then
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
@@ -461,7 +466,7 @@ then
#
if [ $VEHICLE_TYPE == fw ]
then
echo "[init] Vehicle type: FIXED WING"
echo "[i] FIXED WING"
if [ $MIXER == none ]
then
@@ -475,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
@@ -492,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 ]
@@ -540,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
@@ -556,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