mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-06-04 21:23:57 +08:00
Save some flash for much too verbose output
This commit is contained in:
@@ -195,7 +195,6 @@ then
|
|||||||
#
|
#
|
||||||
if param compare SYS_AUTOSTART 0
|
if param compare SYS_AUTOSTART 0
|
||||||
then
|
then
|
||||||
echo "INFO [init] No autostart"
|
|
||||||
else
|
else
|
||||||
sh /etc/init.d/rc.autostart
|
sh /etc/init.d/rc.autostart
|
||||||
fi
|
fi
|
||||||
@@ -214,7 +213,7 @@ then
|
|||||||
set FCONFIG /fs/microsd/etc/config.txt
|
set FCONFIG /fs/microsd/etc/config.txt
|
||||||
if [ -f $FCONFIG ]
|
if [ -f $FCONFIG ]
|
||||||
then
|
then
|
||||||
echo "INFO [init] Custom: $FCONFIG"
|
echo "Custom: $FCONFIG"
|
||||||
sh $FCONFIG
|
sh $FCONFIG
|
||||||
fi
|
fi
|
||||||
unset FCONFIG
|
unset FCONFIG
|
||||||
@@ -245,7 +244,7 @@ then
|
|||||||
|
|
||||||
if px4io checkcrc ${IO_FILE}
|
if px4io checkcrc ${IO_FILE}
|
||||||
then
|
then
|
||||||
echo "INFO [init] PX4IO CRC OK" >> $LOG_FILE
|
echo "[init] PX4IO CRC OK" >> $LOG_FILE
|
||||||
|
|
||||||
set IO_PRESENT yes
|
set IO_PRESENT yes
|
||||||
else
|
else
|
||||||
@@ -268,16 +267,16 @@ then
|
|||||||
usleep 500000
|
usleep 500000
|
||||||
if px4io checkcrc $IO_FILE
|
if px4io checkcrc $IO_FILE
|
||||||
then
|
then
|
||||||
echo "INFO [init] PX4IO CRC OK after updating" >> $LOG_FILE
|
echo "PX4IO CRC OK after updating" >> $LOG_FILE
|
||||||
tone_alarm MLL8CDE
|
tone_alarm MLL8CDE
|
||||||
|
|
||||||
set IO_PRESENT yes
|
set IO_PRESENT yes
|
||||||
else
|
else
|
||||||
echo "ERROR [init] PX4IO update failed" >> $LOG_FILE
|
echo "PX4IO update failed" >> $LOG_FILE
|
||||||
tone_alarm $TUNE_ERR
|
tone_alarm $TUNE_ERR
|
||||||
fi
|
fi
|
||||||
else
|
else
|
||||||
echo "ERROR [init] PX4IO update failed" >> $LOG_FILE
|
echo "PX4IO update failed" >> $LOG_FILE
|
||||||
tone_alarm $TUNE_ERR
|
tone_alarm $TUNE_ERR
|
||||||
fi
|
fi
|
||||||
fi
|
fi
|
||||||
@@ -285,7 +284,7 @@ then
|
|||||||
|
|
||||||
if [ $IO_PRESENT == no ]
|
if [ $IO_PRESENT == no ]
|
||||||
then
|
then
|
||||||
echo "ERROR [init] PX4IO not found" >> $LOG_FILE
|
echo "PX4IO not found" >> $LOG_FILE
|
||||||
tone_alarm $TUNE_ERR
|
tone_alarm $TUNE_ERR
|
||||||
fi
|
fi
|
||||||
fi
|
fi
|
||||||
@@ -377,7 +376,7 @@ then
|
|||||||
then
|
then
|
||||||
if param compare UAVCAN_ENABLE 0
|
if param compare UAVCAN_ENABLE 0
|
||||||
then
|
then
|
||||||
echo "INFO [init] OVERRIDING UAVCAN_ENABLE = 1" >> $LOG_FILE
|
echo "OVERRIDING UAVCAN_ENABLE = 1" >> $LOG_FILE
|
||||||
param set UAVCAN_ENABLE 1
|
param set UAVCAN_ENABLE 1
|
||||||
fi
|
fi
|
||||||
fi
|
fi
|
||||||
@@ -388,7 +387,7 @@ then
|
|||||||
then
|
then
|
||||||
sh /etc/init.d/rc.io
|
sh /etc/init.d/rc.io
|
||||||
else
|
else
|
||||||
echo "INFO [init] PX4IO start failed" >> $LOG_FILE
|
echo "PX4IO start failed" >> $LOG_FILE
|
||||||
tone_alarm $TUNE_ERR
|
tone_alarm $TUNE_ERR
|
||||||
fi
|
fi
|
||||||
fi
|
fi
|
||||||
@@ -398,7 +397,7 @@ then
|
|||||||
if fmu mode_$FMU_MODE
|
if fmu mode_$FMU_MODE
|
||||||
then
|
then
|
||||||
else
|
else
|
||||||
echo "ERR [init] FMU start failed" >> $LOG_FILE
|
echo "FMU start failed" >> $LOG_FILE
|
||||||
tone_alarm $TUNE_ERR
|
tone_alarm $TUNE_ERR
|
||||||
fi
|
fi
|
||||||
|
|
||||||
@@ -430,7 +429,7 @@ then
|
|||||||
if mkblctrl $MKBLCTRL_ARG
|
if mkblctrl $MKBLCTRL_ARG
|
||||||
then
|
then
|
||||||
else
|
else
|
||||||
echo "ERROR [init] MK start failed" >> $LOG_FILE
|
echo "MK start failed" >> $LOG_FILE
|
||||||
tone_alarm $TUNE_ERR
|
tone_alarm $TUNE_ERR
|
||||||
fi
|
fi
|
||||||
unset MKBLCTRL_ARG
|
unset MKBLCTRL_ARG
|
||||||
@@ -442,7 +441,6 @@ then
|
|||||||
if pwm_out_sim mode_port2_pwm8
|
if pwm_out_sim mode_port2_pwm8
|
||||||
then
|
then
|
||||||
else
|
else
|
||||||
echo "ERROR [init] PWM SIM start failed" >> $LOG_FILE
|
|
||||||
tone_alarm $TUNE_ERR
|
tone_alarm $TUNE_ERR
|
||||||
fi
|
fi
|
||||||
fi
|
fi
|
||||||
@@ -458,7 +456,7 @@ then
|
|||||||
then
|
then
|
||||||
sh /etc/init.d/rc.io
|
sh /etc/init.d/rc.io
|
||||||
else
|
else
|
||||||
echo "ERROR [init] PX4IO start failed" >> $LOG_FILE
|
echo "PX4IO start failed" >> $LOG_FILE
|
||||||
tone_alarm $TUNE_ERR
|
tone_alarm $TUNE_ERR
|
||||||
fi
|
fi
|
||||||
fi
|
fi
|
||||||
@@ -468,7 +466,7 @@ then
|
|||||||
if fmu mode_$FMU_MODE
|
if fmu mode_$FMU_MODE
|
||||||
then
|
then
|
||||||
else
|
else
|
||||||
echo "ERROR [init] FMU mode_$FMU_MODE start failed" >> $LOG_FILE
|
echo "FMU mode_$FMU_MODE start failed" >> $LOG_FILE
|
||||||
tone_alarm $TUNE_ERR
|
tone_alarm $TUNE_ERR
|
||||||
fi
|
fi
|
||||||
|
|
||||||
@@ -711,8 +709,6 @@ then
|
|||||||
#
|
#
|
||||||
if [ $VEHICLE_TYPE == fw ]
|
if [ $VEHICLE_TYPE == fw ]
|
||||||
then
|
then
|
||||||
echo "INFO [init] Fixedwing"
|
|
||||||
|
|
||||||
if [ $MIXER == none ]
|
if [ $MIXER == none ]
|
||||||
then
|
then
|
||||||
# Set default mixer for fixed wing if not defined
|
# Set default mixer for fixed wing if not defined
|
||||||
@@ -739,11 +735,9 @@ then
|
|||||||
#
|
#
|
||||||
if [ $VEHICLE_TYPE == mc ]
|
if [ $VEHICLE_TYPE == mc ]
|
||||||
then
|
then
|
||||||
echo "INFO [init] Multicopter"
|
|
||||||
|
|
||||||
if [ $MIXER == none ]
|
if [ $MIXER == none ]
|
||||||
then
|
then
|
||||||
echo "INFO [init] Mixer undefined"
|
echo "Mixer undefined"
|
||||||
fi
|
fi
|
||||||
|
|
||||||
if [ $MAV_TYPE == none ]
|
if [ $MAV_TYPE == none ]
|
||||||
@@ -790,7 +784,7 @@ then
|
|||||||
# Still no MAV_TYPE found
|
# Still no MAV_TYPE found
|
||||||
if [ $MAV_TYPE == none ]
|
if [ $MAV_TYPE == none ]
|
||||||
then
|
then
|
||||||
echo "WARN [init] Unknown MAV_TYPE"
|
echo "Unknown MAV_TYPE"
|
||||||
param set MAV_TYPE 2
|
param set MAV_TYPE 2
|
||||||
else
|
else
|
||||||
param set MAV_TYPE $MAV_TYPE
|
param set MAV_TYPE $MAV_TYPE
|
||||||
@@ -808,11 +802,9 @@ then
|
|||||||
#
|
#
|
||||||
if [ $VEHICLE_TYPE == vtol ]
|
if [ $VEHICLE_TYPE == vtol ]
|
||||||
then
|
then
|
||||||
echo "INFO [init] VTOL"
|
|
||||||
|
|
||||||
if [ $MIXER == none ]
|
if [ $MIXER == none ]
|
||||||
then
|
then
|
||||||
echo "WARN [init] VTOL mixer undefined"
|
echo "VTOL mixer undefined"
|
||||||
fi
|
fi
|
||||||
|
|
||||||
if [ $MAV_TYPE == none ]
|
if [ $MAV_TYPE == none ]
|
||||||
@@ -835,7 +827,7 @@ then
|
|||||||
# Still no MAV_TYPE found
|
# Still no MAV_TYPE found
|
||||||
if [ $MAV_TYPE == none ]
|
if [ $MAV_TYPE == none ]
|
||||||
then
|
then
|
||||||
echo "WARN [init] Unknown MAV_TYPE"
|
echo "Unknown MAV_TYPE"
|
||||||
param set MAV_TYPE 19
|
param set MAV_TYPE 19
|
||||||
else
|
else
|
||||||
param set MAV_TYPE $MAV_TYPE
|
param set MAV_TYPE $MAV_TYPE
|
||||||
@@ -919,14 +911,14 @@ then
|
|||||||
#
|
#
|
||||||
if [ $VEHICLE_TYPE == none ]
|
if [ $VEHICLE_TYPE == none ]
|
||||||
then
|
then
|
||||||
echo "WARN [init] No autostart ID found"
|
echo "No autostart ID found"
|
||||||
fi
|
fi
|
||||||
|
|
||||||
# Start any custom addons
|
# Start any custom addons
|
||||||
set FEXTRAS /fs/microsd/etc/extras.txt
|
set FEXTRAS /fs/microsd/etc/extras.txt
|
||||||
if [ -f $FEXTRAS ]
|
if [ -f $FEXTRAS ]
|
||||||
then
|
then
|
||||||
echo "INFO [init] Addons script: $FEXTRAS"
|
echo "Addons script: $FEXTRAS"
|
||||||
sh $FEXTRAS
|
sh $FEXTRAS
|
||||||
fi
|
fi
|
||||||
unset FEXTRAS
|
unset FEXTRAS
|
||||||
@@ -950,7 +942,7 @@ mavlink boot_complete
|
|||||||
|
|
||||||
if [ $EXIT_ON_END == yes ]
|
if [ $EXIT_ON_END == yes ]
|
||||||
then
|
then
|
||||||
echo "INFO [init] NSH exit"
|
echo "NSH exit"
|
||||||
exit
|
exit
|
||||||
fi
|
fi
|
||||||
unset EXIT_ON_END
|
unset EXIT_ON_END
|
||||||
|
|||||||
Reference in New Issue
Block a user