forked from Archive/PX4-Autopilot
Reduce too chatty content, de-allocate non-needed string buffers
This commit is contained in:
parent
b06f7f4f2e
commit
489b4c4839
|
@ -31,9 +31,9 @@ then
|
||||||
|
|
||||||
if mixer load $OUTPUT_DEV $MIXER_FILE
|
if mixer load $OUTPUT_DEV $MIXER_FILE
|
||||||
then
|
then
|
||||||
echo "[init] Mixer loaded: $MIXER_FILE"
|
echo "[i] Mixer: $MIXER_FILE"
|
||||||
else
|
else
|
||||||
echo "[init] Error loading mixer: $MIXER_FILE"
|
echo "[i] Error loading mixer: $MIXER_FILE"
|
||||||
tone_alarm $TUNE_ERR
|
tone_alarm $TUNE_ERR
|
||||||
fi
|
fi
|
||||||
|
|
||||||
|
@ -41,7 +41,7 @@ then
|
||||||
else
|
else
|
||||||
if [ $MIXER != skip ]
|
if [ $MIXER != skip ]
|
||||||
then
|
then
|
||||||
echo "[init] Mixer not defined"
|
echo "[i] Mixer not defined"
|
||||||
tone_alarm $TUNE_ERR
|
tone_alarm $TUNE_ERR
|
||||||
fi
|
fi
|
||||||
fi
|
fi
|
||||||
|
@ -55,7 +55,7 @@ then
|
||||||
#
|
#
|
||||||
if [ $PWM_RATE != none ]
|
if [ $PWM_RATE != none ]
|
||||||
then
|
then
|
||||||
echo "[init] Set PWM rate: $PWM_RATE"
|
echo "[i] PWM rate: $PWM_RATE"
|
||||||
pwm rate -c $PWM_OUT -r $PWM_RATE
|
pwm rate -c $PWM_OUT -r $PWM_RATE
|
||||||
fi
|
fi
|
||||||
|
|
||||||
|
@ -64,17 +64,17 @@ then
|
||||||
#
|
#
|
||||||
if [ $PWM_DISARMED != none ]
|
if [ $PWM_DISARMED != none ]
|
||||||
then
|
then
|
||||||
echo "[init] Set PWM disarmed: $PWM_DISARMED"
|
echo "[i] PWM disarmed: $PWM_DISARMED"
|
||||||
pwm disarmed -c $PWM_OUT -p $PWM_DISARMED
|
pwm disarmed -c $PWM_OUT -p $PWM_DISARMED
|
||||||
fi
|
fi
|
||||||
if [ $PWM_MIN != none ]
|
if [ $PWM_MIN != none ]
|
||||||
then
|
then
|
||||||
echo "[init] Set PWM min: $PWM_MIN"
|
echo "[i] PWM min: $PWM_MIN"
|
||||||
pwm min -c $PWM_OUT -p $PWM_MIN
|
pwm min -c $PWM_OUT -p $PWM_MIN
|
||||||
fi
|
fi
|
||||||
if [ $PWM_MAX != none ]
|
if [ $PWM_MAX != none ]
|
||||||
then
|
then
|
||||||
echo "[init] Set PWM max: $PWM_MAX"
|
echo "[i] PWM max: $PWM_MAX"
|
||||||
pwm max -c $PWM_OUT -p $PWM_MAX
|
pwm max -c $PWM_OUT -p $PWM_MAX
|
||||||
fi
|
fi
|
||||||
fi
|
fi
|
||||||
|
|
|
@ -7,25 +7,25 @@
|
||||||
#
|
#
|
||||||
set MODE autostart
|
set MODE autostart
|
||||||
|
|
||||||
set RC_FILE /fs/microsd/etc/rc.txt
|
set FRC /fs/microsd/etc/rc.txt
|
||||||
set CONFIG_FILE /fs/microsd/etc/config.txt
|
set FCONFIG /fs/microsd/etc/config.txt
|
||||||
set EXTRAS_FILE /fs/microsd/etc/extras.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.
|
# Try to mount the microSD card.
|
||||||
#
|
#
|
||||||
echo "[init] Looking for microSD..."
|
echo "[i] Looking for microSD..."
|
||||||
if mount -t vfat /dev/mmcsd0 /fs/microsd
|
if mount -t vfat /dev/mmcsd0 /fs/microsd
|
||||||
then
|
then
|
||||||
set LOG_FILE /fs/microsd/bootlog.txt
|
set LOG_FILE /fs/microsd/bootlog.txt
|
||||||
echo "[init] microSD mounted: /fs/microsd"
|
echo "[i] microSD mounted: /fs/microsd"
|
||||||
# Start playing the startup tune
|
# Start playing the startup tune
|
||||||
tone_alarm start
|
tone_alarm start
|
||||||
else
|
else
|
||||||
set LOG_FILE /dev/null
|
set LOG_FILE /dev/null
|
||||||
echo "[init] No microSD card found"
|
echo "[i] No microSD card found"
|
||||||
# Play SOS
|
# Play SOS
|
||||||
tone_alarm error
|
tone_alarm error
|
||||||
fi
|
fi
|
||||||
|
@ -34,13 +34,13 @@ fi
|
||||||
# Look for an init script on the microSD card.
|
# Look for an init script on the microSD card.
|
||||||
# Disable autostart if the script found.
|
# Disable autostart if the script found.
|
||||||
#
|
#
|
||||||
if [ -f $RC_FILE ]
|
if [ -f $FRC ]
|
||||||
then
|
then
|
||||||
echo "[init] Executing init script: $RC_FILE"
|
echo "[i] Executing init script: $FRC"
|
||||||
sh $RC_FILE
|
sh $FRC
|
||||||
set MODE custom
|
set MODE custom
|
||||||
else
|
else
|
||||||
echo "[init] Init script not found: $RC_FILE"
|
echo "[i] Init script not found: $FRC"
|
||||||
fi
|
fi
|
||||||
|
|
||||||
# if this is an APM build then there will be a rc.APM script
|
# 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
|
then
|
||||||
if sercon
|
if sercon
|
||||||
then
|
then
|
||||||
echo "[init] USB interface connected"
|
echo "[i] USB interface connected"
|
||||||
fi
|
fi
|
||||||
|
|
||||||
echo "[init] Running rc.APM"
|
echo "[i] Running rc.APM"
|
||||||
# if APM startup is successful then nsh will exit
|
# if APM startup is successful then nsh will exit
|
||||||
sh /etc/init.d/rc.APM
|
sh /etc/init.d/rc.APM
|
||||||
fi
|
fi
|
||||||
|
|
||||||
if [ $MODE == autostart ]
|
if [ $MODE == autostart ]
|
||||||
then
|
then
|
||||||
echo "[init] AUTOSTART mode"
|
echo "[i] AUTOSTART mode"
|
||||||
|
|
||||||
#
|
#
|
||||||
# Start CDC/ACM serial driver
|
# Start CDC/ACM serial driver
|
||||||
|
@ -117,31 +117,31 @@ then
|
||||||
set VEHICLE_TYPE none
|
set VEHICLE_TYPE none
|
||||||
set MIXER none
|
set MIXER none
|
||||||
set OUTPUT_MODE none
|
set OUTPUT_MODE none
|
||||||
set PWM_OUTPUTS none
|
set PWM_OUT none
|
||||||
set PWM_RATE none
|
set PWM_RATE none
|
||||||
set PWM_DISARMED none
|
set PWM_DISARMED none
|
||||||
set PWM_MIN none
|
set PWM_MIN none
|
||||||
set PWM_MAX none
|
set PWM_MAX none
|
||||||
set MKBLCTRL_MODE none
|
set MK_MODE none
|
||||||
set FMU_MODE pwm
|
set FMU_MODE pwm
|
||||||
set MAVLINK_FLAGS default
|
set MAVLINK_F default
|
||||||
set EXIT_ON_END no
|
set EXIT_ON_END no
|
||||||
set MAV_TYPE none
|
set MAV_TYPE none
|
||||||
set LOAD_DEFAULT_APPS yes
|
set LOAD_DAPPS yes
|
||||||
set GPS yes
|
set GPS yes
|
||||||
set GPS_FAKE no
|
set GPS_FAKE no
|
||||||
set FAILSAFE none
|
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
|
if param compare SYS_AUTOCONFIG 1
|
||||||
then
|
then
|
||||||
# Wipe out params
|
# Wipe out params
|
||||||
param reset_nostart
|
param reset_nostart
|
||||||
set DO_AUTOCONFIG yes
|
set AUTOCNF yes
|
||||||
else
|
else
|
||||||
set DO_AUTOCONFIG no
|
set AUTOCNF no
|
||||||
fi
|
fi
|
||||||
|
|
||||||
#
|
#
|
||||||
|
@ -159,7 +159,7 @@ then
|
||||||
#
|
#
|
||||||
if param compare SYS_AUTOSTART 0
|
if param compare SYS_AUTOSTART 0
|
||||||
then
|
then
|
||||||
echo "[init] No autostart"
|
echo "[i] No autostart"
|
||||||
else
|
else
|
||||||
sh /etc/init.d/rc.autostart
|
sh /etc/init.d/rc.autostart
|
||||||
fi
|
fi
|
||||||
|
@ -167,18 +167,19 @@ then
|
||||||
#
|
#
|
||||||
# Override parameters from user configuration file
|
# Override parameters from user configuration file
|
||||||
#
|
#
|
||||||
if [ -f $CONFIG_FILE ]
|
if [ -f $FCONFIG ]
|
||||||
then
|
then
|
||||||
echo "[init] Config: $CONFIG_FILE"
|
echo "[i] Config: $FCONFIG"
|
||||||
sh $CONFIG_FILE
|
sh $FCONFIG
|
||||||
else
|
else
|
||||||
echo "[init] Config not found: $CONFIG_FILE"
|
echo "[i] Config not found: $FCONFIG"
|
||||||
fi
|
fi
|
||||||
|
unset FCONFIG
|
||||||
|
|
||||||
#
|
#
|
||||||
# If autoconfig parameter was set, reset it and save parameters
|
# If autoconfig parameter was set, reset it and save parameters
|
||||||
#
|
#
|
||||||
if [ $DO_AUTOCONFIG == yes ]
|
if [ $AUTOCNF == yes ]
|
||||||
then
|
then
|
||||||
param set SYS_AUTOCONFIG 0
|
param set SYS_AUTOCONFIG 0
|
||||||
param save
|
param save
|
||||||
|
@ -219,18 +220,18 @@ then
|
||||||
set IO_PRESENT yes
|
set IO_PRESENT yes
|
||||||
else
|
else
|
||||||
echo "PX4IO update failed" >> $LOG_FILE
|
echo "PX4IO update failed" >> $LOG_FILE
|
||||||
tone_alarm $TUNE_OUT_ERROR
|
tone_alarm $TUNE_ERR
|
||||||
fi
|
fi
|
||||||
else
|
else
|
||||||
echo "PX4IO update failed" >> $LOG_FILE
|
echo "PX4IO update failed" >> $LOG_FILE
|
||||||
tone_alarm $TUNE_OUT_ERROR
|
tone_alarm $TUNE_ERR
|
||||||
fi
|
fi
|
||||||
fi
|
fi
|
||||||
|
|
||||||
if [ $IO_PRESENT == no ]
|
if [ $IO_PRESENT == no ]
|
||||||
then
|
then
|
||||||
echo "[init] ERROR: PX4IO not found"
|
echo "[i] ERROR: PX4IO not found"
|
||||||
tone_alarm $TUNE_OUT_ERROR
|
tone_alarm $TUNE_ERR
|
||||||
fi
|
fi
|
||||||
fi
|
fi
|
||||||
|
|
||||||
|
@ -251,7 +252,7 @@ then
|
||||||
then
|
then
|
||||||
# Need IO for output but it not present, disable output
|
# Need IO for output but it not present, disable output
|
||||||
set OUTPUT_MODE none
|
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
|
# Avoid using ttyS0 for MAVLink on FMUv1
|
||||||
if ver hwcmp PX4FMU_V1
|
if ver hwcmp PX4FMU_V1
|
||||||
|
@ -294,33 +295,31 @@ then
|
||||||
then
|
then
|
||||||
if param compare UAVCAN_ENABLE 0
|
if param compare UAVCAN_ENABLE 0
|
||||||
then
|
then
|
||||||
echo "[init] OVERRIDING UAVCAN_ENABLE = 1"
|
echo "[i] OVERRIDING UAVCAN_ENABLE = 1"
|
||||||
param set UAVCAN_ENABLE 1
|
param set UAVCAN_ENABLE 1
|
||||||
fi
|
fi
|
||||||
fi
|
fi
|
||||||
|
|
||||||
if [ $OUTPUT_MODE == io -o $OUTPUT_MODE == uavcan_esc ]
|
if [ $OUTPUT_MODE == io -o $OUTPUT_MODE == uavcan_esc ]
|
||||||
then
|
then
|
||||||
echo "[init] Use PX4IO PWM as primary output"
|
|
||||||
if px4io start
|
if px4io start
|
||||||
then
|
then
|
||||||
echo "[init] PX4IO started"
|
echo "[i] PX4IO started"
|
||||||
sh /etc/init.d/rc.io
|
sh /etc/init.d/rc.io
|
||||||
else
|
else
|
||||||
echo "[init] ERROR: PX4IO start failed"
|
echo "[i] ERROR: PX4IO start failed"
|
||||||
tone_alarm $TUNE_OUT_ERROR
|
tone_alarm $TUNE_ERR
|
||||||
fi
|
fi
|
||||||
fi
|
fi
|
||||||
|
|
||||||
if [ $OUTPUT_MODE == fmu -o $OUTPUT_MODE == ardrone ]
|
if [ $OUTPUT_MODE == fmu -o $OUTPUT_MODE == ardrone ]
|
||||||
then
|
then
|
||||||
echo "[init] Use FMU as primary output"
|
|
||||||
if fmu mode_$FMU_MODE
|
if fmu mode_$FMU_MODE
|
||||||
then
|
then
|
||||||
echo "[init] FMU mode_$FMU_MODE started"
|
echo "[i] FMU mode_$FMU_MODE started"
|
||||||
else
|
else
|
||||||
echo "[init] ERROR: FMU mode_$FMU_MODE start failed"
|
echo "[i] ERROR: FMU mode_$FMU_MODE start failed"
|
||||||
tone_alarm $TUNE_OUT_ERROR
|
tone_alarm $TUNE_ERR
|
||||||
fi
|
fi
|
||||||
|
|
||||||
if ver hwcmp PX4FMU_V1
|
if ver hwcmp PX4FMU_V1
|
||||||
|
@ -338,36 +337,34 @@ then
|
||||||
|
|
||||||
if [ $OUTPUT_MODE == mkblctrl ]
|
if [ $OUTPUT_MODE == mkblctrl ]
|
||||||
then
|
then
|
||||||
echo "[init] Use MKBLCTRL as primary output"
|
|
||||||
set MKBLCTRL_ARG ""
|
set MKBLCTRL_ARG ""
|
||||||
if [ $MKBLCTRL_MODE == x ]
|
if [ $MK_MODE == x ]
|
||||||
then
|
then
|
||||||
set MKBLCTRL_ARG "-mkmode x"
|
set MKBLCTRL_ARG "-mkmode x"
|
||||||
fi
|
fi
|
||||||
if [ $MKBLCTRL_MODE == + ]
|
if [ $MK_MODE == + ]
|
||||||
then
|
then
|
||||||
set MKBLCTRL_ARG "-mkmode +"
|
set MKBLCTRL_ARG "-mkmode +"
|
||||||
fi
|
fi
|
||||||
|
|
||||||
if mkblctrl $MKBLCTRL_ARG
|
if mkblctrl $MKBLCTRL_ARG
|
||||||
then
|
then
|
||||||
echo "[init] MKBLCTRL started"
|
echo "[i] MK started"
|
||||||
else
|
else
|
||||||
echo "[init] ERROR: MKBLCTRL start failed"
|
echo "[i] ERROR: MK start failed"
|
||||||
tone_alarm $TUNE_OUT_ERROR
|
tone_alarm $TUNE_ERR
|
||||||
fi
|
fi
|
||||||
|
|
||||||
fi
|
fi
|
||||||
|
|
||||||
if [ $OUTPUT_MODE == hil ]
|
if [ $OUTPUT_MODE == hil ]
|
||||||
then
|
then
|
||||||
echo "[init] Use HIL as primary output"
|
|
||||||
if hil mode_port2_pwm8
|
if hil mode_port2_pwm8
|
||||||
then
|
then
|
||||||
echo "[init] HIL output started"
|
echo "[i] HIL output started"
|
||||||
else
|
else
|
||||||
echo "[init] ERROR: HIL output start failed"
|
echo "[i] ERROR: HIL output start failed"
|
||||||
tone_alarm $TUNE_OUT_ERROR
|
tone_alarm $TUNE_ERR
|
||||||
fi
|
fi
|
||||||
fi
|
fi
|
||||||
|
|
||||||
|
@ -380,11 +377,11 @@ then
|
||||||
then
|
then
|
||||||
if px4io start
|
if px4io start
|
||||||
then
|
then
|
||||||
echo "[init] PX4IO started"
|
echo "[i] PX4IO started"
|
||||||
sh /etc/init.d/rc.io
|
sh /etc/init.d/rc.io
|
||||||
else
|
else
|
||||||
echo "[init] ERROR: PX4IO start failed"
|
echo "[i] ERROR: PX4IO start failed"
|
||||||
tone_alarm $TUNE_OUT_ERROR
|
tone_alarm $TUNE_ERR
|
||||||
fi
|
fi
|
||||||
fi
|
fi
|
||||||
else
|
else
|
||||||
|
@ -392,10 +389,10 @@ then
|
||||||
then
|
then
|
||||||
if fmu mode_$FMU_MODE
|
if fmu mode_$FMU_MODE
|
||||||
then
|
then
|
||||||
echo "[init] FMU mode_$FMU_MODE started"
|
echo "[i] FMU mode_$FMU_MODE started"
|
||||||
else
|
else
|
||||||
echo "[init] ERROR: FMU mode_$FMU_MODE start failed"
|
echo "[i] ERROR: FMU mode_$FMU_MODE start failed"
|
||||||
tone_alarm $TUNE_OUT_ERROR
|
tone_alarm $TUNE_ERR
|
||||||
fi
|
fi
|
||||||
|
|
||||||
if ver hwcmp PX4FMU_V1
|
if ver hwcmp PX4FMU_V1
|
||||||
|
@ -413,23 +410,24 @@ then
|
||||||
fi
|
fi
|
||||||
fi
|
fi
|
||||||
|
|
||||||
if [ $MAVLINK_FLAGS == default ]
|
if [ $MAVLINK_F == default ]
|
||||||
then
|
then
|
||||||
# Normal mode, use baudrate 57600 (default) and data rate 1000 bytes/s
|
# Normal mode, use baudrate 57600 (default) and data rate 1000 bytes/s
|
||||||
if [ $TTYS1_BUSY == yes ]
|
if [ $TTYS1_BUSY == yes ]
|
||||||
then
|
then
|
||||||
# Start MAVLink on ttyS0, because FMU ttyS1 pins configured as something else
|
# 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
|
# Exit from nsh to free port for mavlink
|
||||||
set EXIT_ON_END yes
|
set EXIT_ON_END yes
|
||||||
else
|
else
|
||||||
# Start MAVLink on default port: ttyS1
|
# Start MAVLink on default port: ttyS1
|
||||||
set MAVLINK_FLAGS "-r 1000"
|
set MAVLINK_F "-r 1000"
|
||||||
fi
|
fi
|
||||||
fi
|
fi
|
||||||
|
|
||||||
mavlink start $MAVLINK_FLAGS
|
mavlink start $MAVLINK_F
|
||||||
|
unset MAVLINK_F
|
||||||
|
|
||||||
#
|
#
|
||||||
# UAVCAN
|
# UAVCAN
|
||||||
|
@ -444,15 +442,16 @@ then
|
||||||
|
|
||||||
if [ $GPS == yes ]
|
if [ $GPS == yes ]
|
||||||
then
|
then
|
||||||
echo "[init] Start GPS"
|
echo "[i] Start GPS"
|
||||||
if [ $GPS_FAKE == yes ]
|
if [ $GPS_FAKE == yes ]
|
||||||
then
|
then
|
||||||
echo "[init] Faking GPS"
|
echo "[i] Faking GPS"
|
||||||
gps start -f
|
gps start -f
|
||||||
else
|
else
|
||||||
gps start
|
gps start
|
||||||
fi
|
fi
|
||||||
fi
|
fi
|
||||||
|
unset GPS_FAKE
|
||||||
|
|
||||||
#
|
#
|
||||||
# Start up ARDrone Motor interface
|
# Start up ARDrone Motor interface
|
||||||
|
@ -467,7 +466,7 @@ then
|
||||||
#
|
#
|
||||||
if [ $VEHICLE_TYPE == fw ]
|
if [ $VEHICLE_TYPE == fw ]
|
||||||
then
|
then
|
||||||
echo "[init] Vehicle type: FIXED WING"
|
echo "[i] FIXED WING"
|
||||||
|
|
||||||
if [ $MIXER == none ]
|
if [ $MIXER == none ]
|
||||||
then
|
then
|
||||||
|
@ -481,13 +480,13 @@ then
|
||||||
set MAV_TYPE 1
|
set MAV_TYPE 1
|
||||||
fi
|
fi
|
||||||
|
|
||||||
param set MAV_TYPE $MAV_TYPE
|
#param set MAV_TYPE $MAV_TYPE
|
||||||
|
|
||||||
# Load mixer and configure outputs
|
# Load mixer and configure outputs
|
||||||
sh /etc/init.d/rc.interface
|
sh /etc/init.d/rc.interface
|
||||||
|
|
||||||
# Start standard fixedwing apps
|
# Start standard fixedwing apps
|
||||||
if [ $LOAD_DEFAULT_APPS == yes ]
|
if [ $LOAD_DAPPS == yes ]
|
||||||
then
|
then
|
||||||
sh /etc/init.d/rc.fw_apps
|
sh /etc/init.d/rc.fw_apps
|
||||||
fi
|
fi
|
||||||
|
@ -498,11 +497,11 @@ then
|
||||||
#
|
#
|
||||||
if [ $VEHICLE_TYPE == mc ]
|
if [ $VEHICLE_TYPE == mc ]
|
||||||
then
|
then
|
||||||
echo "[init] Vehicle type: MULTICOPTER"
|
echo "[i] MULTICOPTER"
|
||||||
|
|
||||||
if [ $MIXER == none ]
|
if [ $MIXER == none ]
|
||||||
then
|
then
|
||||||
echo "Default mixer for multicopter not defined"
|
echo "Mixer undefined"
|
||||||
fi
|
fi
|
||||||
|
|
||||||
if [ $MAV_TYPE == none ]
|
if [ $MAV_TYPE == none ]
|
||||||
|
@ -546,7 +545,7 @@ then
|
||||||
sh /etc/init.d/rc.interface
|
sh /etc/init.d/rc.interface
|
||||||
|
|
||||||
# Start standard multicopter apps
|
# Start standard multicopter apps
|
||||||
if [ $LOAD_DEFAULT_APPS == yes ]
|
if [ $LOAD_DAPPS == yes ]
|
||||||
then
|
then
|
||||||
sh /etc/init.d/rc.mc_apps
|
sh /etc/init.d/rc.mc_apps
|
||||||
fi
|
fi
|
||||||
|
@ -562,22 +561,23 @@ then
|
||||||
#
|
#
|
||||||
if [ $VEHICLE_TYPE == none ]
|
if [ $VEHICLE_TYPE == none ]
|
||||||
then
|
then
|
||||||
echo "[init] Vehicle type: No autostart ID found"
|
echo "[i] No autostart ID found"
|
||||||
|
|
||||||
fi
|
fi
|
||||||
|
|
||||||
# Start any custom addons
|
# Start any custom addons
|
||||||
if [ -f $EXTRAS_FILE ]
|
if [ -f $FEXTRAS ]
|
||||||
then
|
then
|
||||||
echo "[init] Starting addons script: $EXTRAS_FILE"
|
echo "[i] Addons script: $FEXTRAS"
|
||||||
sh $EXTRAS_FILE
|
sh $FEXTRAS
|
||||||
else
|
else
|
||||||
echo "[init] No addons script: $EXTRAS_FILE"
|
echo "[i] No addons script: $FEXTRAS"
|
||||||
fi
|
fi
|
||||||
|
unset FEXTRAS
|
||||||
|
|
||||||
if [ $EXIT_ON_END == yes ]
|
if [ $EXIT_ON_END == yes ]
|
||||||
then
|
then
|
||||||
echo "[init] Exit from nsh"
|
echo "Exit from nsh"
|
||||||
exit
|
exit
|
||||||
fi
|
fi
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue