2013-01-20 17:21:44 -04:00
|
|
|
#!nsh
|
|
|
|
|
|
|
|
# APM startup script for NuttX on PX4
|
|
|
|
|
2013-02-17 22:55:58 -04:00
|
|
|
# To disable APM startup add a /fs/microsd/APM/nostart file
|
2013-07-11 00:18:54 -03:00
|
|
|
# To enable mkblctrl startup add a /fs/microsd/APM/mkblctrl file
|
2014-03-28 15:01:09 -03:00
|
|
|
# To enable mkblctrl_+ startup add a /fs/microsd/APM/mkblctrl_+ file
|
|
|
|
# To enable mkblctrl_x startup add a /fs/microsd/APM/mkblctrl_x file
|
2013-12-30 20:54:42 -04:00
|
|
|
# To enable PWM on FMUv1 on ttyS1 add a /fs/microsd/APM/AUXPWM.en file
|
2013-02-17 22:55:58 -04:00
|
|
|
|
|
|
|
set deviceA /dev/ttyACM0
|
2013-07-11 00:18:54 -03:00
|
|
|
|
2013-03-17 22:25:45 -03:00
|
|
|
# check for an old file called APM, caused by
|
|
|
|
# a bug in an earlier firmware release
|
|
|
|
if [ -f /fs/microsd/APM ]
|
|
|
|
then
|
|
|
|
echo "APM file found - renaming"
|
|
|
|
mv /fs/microsd/APM /fs/microsd/APM.old
|
|
|
|
fi
|
|
|
|
|
2013-01-25 05:36:33 -04:00
|
|
|
if [ -f /fs/microsd/APM/nostart ]
|
|
|
|
then
|
2013-08-03 05:51:59 -03:00
|
|
|
echo "APM/nostart found - skipping APM startup"
|
|
|
|
sh /etc/init.d/rc.error
|
|
|
|
fi
|
2013-01-25 05:36:33 -04:00
|
|
|
|
2013-01-20 17:21:44 -04:00
|
|
|
# mount binfs so we can find the built-in apps
|
2013-02-17 22:55:58 -04:00
|
|
|
if [ -f /bin/reboot ]
|
|
|
|
then
|
|
|
|
echo "binfs already mounted"
|
|
|
|
else
|
|
|
|
echo "Mounting binfs"
|
2013-08-03 05:51:59 -03:00
|
|
|
if mount -t binfs /dev/null /bin
|
|
|
|
then
|
|
|
|
echo "binfs mounted OK"
|
|
|
|
else
|
|
|
|
sh /etc/init.d/rc.error
|
|
|
|
fi
|
2013-02-17 22:55:58 -04:00
|
|
|
fi
|
2013-01-20 17:21:44 -04:00
|
|
|
|
|
|
|
set sketch NONE
|
2014-01-13 21:41:07 -04:00
|
|
|
if rm /fs/microsd/APM/boot.log
|
|
|
|
then
|
|
|
|
echo "removed old boot.log"
|
|
|
|
fi
|
2014-01-13 00:04:42 -04:00
|
|
|
set logfile /fs/microsd/APM/BOOT.LOG
|
2013-01-20 17:21:44 -04:00
|
|
|
|
2013-08-03 05:51:59 -03:00
|
|
|
if [ ! -f /bin/ArduPilot ]
|
2013-01-20 17:21:44 -04:00
|
|
|
then
|
2013-08-03 05:51:59 -03:00
|
|
|
echo "/bin/ardupilot not found"
|
|
|
|
sh /etc/init.d/rc.error
|
2013-01-20 17:21:44 -04:00
|
|
|
fi
|
|
|
|
|
2013-08-05 22:27:34 -03:00
|
|
|
if mkdir /fs/microsd/APM > /dev/null
|
2013-01-20 17:21:44 -04:00
|
|
|
then
|
2013-08-03 05:51:59 -03:00
|
|
|
echo "Created APM directory"
|
|
|
|
fi
|
2013-03-21 00:59:58 -03:00
|
|
|
|
2013-10-30 01:33:42 -03:00
|
|
|
if [ -f /bin/lsm303d ]
|
2013-08-03 05:51:59 -03:00
|
|
|
then
|
|
|
|
echo "Detected FMUv2 board"
|
|
|
|
set BOARD FMUv2
|
2013-10-30 01:33:42 -03:00
|
|
|
else
|
|
|
|
echo "Detected FMUv1 board"
|
|
|
|
set BOARD FMUv1
|
2013-08-03 05:51:59 -03:00
|
|
|
fi
|
2013-07-25 22:12:37 -03:00
|
|
|
|
2013-11-22 06:54:37 -04:00
|
|
|
if [ $BOARD == FMUv1 ]
|
2013-08-03 05:51:59 -03:00
|
|
|
then
|
2013-11-22 06:54:37 -04:00
|
|
|
set deviceC /dev/ttyS2
|
2013-12-30 20:54:42 -04:00
|
|
|
if [ -f /fs/microsd/APM/AUXPWM.en ]
|
2013-08-03 05:51:59 -03:00
|
|
|
then
|
2013-11-22 06:54:37 -04:00
|
|
|
set deviceD /dev/null
|
2013-12-30 20:54:42 -04:00
|
|
|
else
|
|
|
|
set deviceD /dev/ttyS1
|
2013-08-03 05:51:59 -03:00
|
|
|
fi
|
2013-11-22 06:54:37 -04:00
|
|
|
else
|
|
|
|
set deviceC /dev/ttyS1
|
|
|
|
set deviceD /dev/ttyS2
|
2013-08-03 05:51:59 -03:00
|
|
|
fi
|
|
|
|
|
2013-10-30 01:33:42 -03:00
|
|
|
if uorb start
|
|
|
|
then
|
|
|
|
echo "uorb started OK"
|
|
|
|
else
|
|
|
|
sh /etc/init.d/rc.error
|
|
|
|
fi
|
|
|
|
|
2014-03-28 15:01:09 -03:00
|
|
|
# start mkblctrl driver if configured
|
|
|
|
if [ -f /fs/microsd/APM/mkblctrl ]
|
|
|
|
then
|
|
|
|
echo "Setting up mkblctrl driver"
|
|
|
|
echo "Setting up mkblctrl driver" >> $logfile
|
|
|
|
mkblctrl -d /dev/pwm_output
|
|
|
|
fi
|
|
|
|
|
|
|
|
if [ -f /fs/microsd/APM/mkblctrl_+ ]
|
|
|
|
then
|
|
|
|
echo "Setting up mkblctrl driver +"
|
|
|
|
echo "Setting up mkblctrl driver +" >> $logfile
|
|
|
|
mkblctrl -mkmode + -d /dev/pwm_output
|
|
|
|
fi
|
|
|
|
|
|
|
|
if [ -f /fs/microsd/APM/mkblctrl_x ]
|
|
|
|
then
|
|
|
|
echo "Setting up mkblctrl driver x"
|
|
|
|
echo "Setting up mkblctrl driver x" >> $logfile
|
|
|
|
mkblctrl -mkmode x -d /dev/pwm_output
|
|
|
|
fi
|
|
|
|
|
2013-10-30 01:33:42 -03:00
|
|
|
|
|
|
|
# try the px4io start twice. Some FMUv2 board don't
|
|
|
|
# come up the first time
|
|
|
|
set HAVE_PX4IO false
|
2014-06-30 16:38:33 -03:00
|
|
|
if px4io start norc
|
2013-10-30 01:33:42 -03:00
|
|
|
then
|
|
|
|
set HAVE_PX4IO true
|
|
|
|
else
|
2013-12-12 21:44:47 -04:00
|
|
|
# it may be in bootloader mode
|
|
|
|
echo Loading /etc/px4io/px4io.bin
|
|
|
|
tone_alarm MBABGP
|
|
|
|
if px4io update /etc/px4io/px4io.bin
|
|
|
|
then
|
|
|
|
echo "upgraded PX4IO firmware OK"
|
|
|
|
tone_alarm MSPAA
|
|
|
|
else
|
|
|
|
echo "Failed to upgrade PX4IO firmware"
|
|
|
|
tone_alarm MNGGG
|
|
|
|
fi
|
|
|
|
sleep 1
|
2014-06-30 16:38:33 -03:00
|
|
|
if px4io start norc
|
2013-10-30 01:33:42 -03:00
|
|
|
then
|
|
|
|
set HAVE_PX4IO true
|
|
|
|
# play happy tune again
|
|
|
|
tone_alarm start
|
|
|
|
fi
|
|
|
|
fi
|
|
|
|
|
|
|
|
if [ $HAVE_PX4IO == true ]
|
|
|
|
then
|
|
|
|
echo "PX4IO board OK"
|
2013-12-12 21:44:47 -04:00
|
|
|
if px4io checkcrc /etc/px4io/px4io.bin
|
|
|
|
then
|
|
|
|
echo "PX4IO CRC OK"
|
|
|
|
else
|
|
|
|
echo "PX4IO CRC failure"
|
|
|
|
echo "PX4IO CRC failure" >> $logfile
|
|
|
|
tone_alarm MBABGP
|
|
|
|
if px4io forceupdate 14662 /etc/px4io/px4io.bin
|
|
|
|
then
|
|
|
|
sleep 1
|
2014-06-30 16:38:33 -03:00
|
|
|
if px4io start norc
|
2013-12-12 21:44:47 -04:00
|
|
|
then
|
|
|
|
echo "PX4IO restart OK"
|
|
|
|
echo "PX4IO restart OK" >> $logfile
|
|
|
|
tone_alarm MSPAA
|
|
|
|
else
|
|
|
|
echo "PX4IO restart failed"
|
|
|
|
echo "PX4IO restart failed" >> $logfile
|
|
|
|
tone_alarm MNGGG
|
|
|
|
sh /etc/init.d/rc.error
|
|
|
|
fi
|
|
|
|
else
|
|
|
|
echo "PX4IO update failed"
|
|
|
|
echo "PX4IO update failed" >> $logfile
|
|
|
|
tone_alarm MNGGG
|
|
|
|
fi
|
|
|
|
fi
|
2013-10-30 01:33:42 -03:00
|
|
|
else
|
|
|
|
echo "No PX4IO board found"
|
|
|
|
echo "No PX4IO board found" >> $logfile
|
|
|
|
|
|
|
|
if [ $BOARD == FMUv2 ]
|
|
|
|
then
|
|
|
|
sh /etc/init.d/rc.error
|
|
|
|
fi
|
2013-11-22 06:54:37 -04:00
|
|
|
fi
|
2013-10-30 01:33:42 -03:00
|
|
|
|
2013-11-22 06:54:37 -04:00
|
|
|
if [ $BOARD == FMUv1 -a $deviceD == /dev/ttyS1 ]
|
|
|
|
then
|
|
|
|
echo "Setting FMU mode_serial"
|
|
|
|
fmu mode_serial
|
|
|
|
else
|
|
|
|
echo "Setting FMU mode_pwm"
|
|
|
|
fmu mode_pwm
|
2013-10-30 01:33:42 -03:00
|
|
|
fi
|
|
|
|
|
2013-08-05 22:39:00 -03:00
|
|
|
|
2013-08-03 05:51:59 -03:00
|
|
|
echo "Starting APM sensors"
|
|
|
|
if ms5611 start
|
|
|
|
then
|
|
|
|
echo "ms5611 started OK"
|
|
|
|
else
|
|
|
|
sh /etc/init.d/rc.error
|
|
|
|
fi
|
|
|
|
|
|
|
|
if adc start
|
|
|
|
then
|
|
|
|
echo "adc started OK"
|
|
|
|
else
|
|
|
|
sh /etc/init.d/rc.error
|
|
|
|
fi
|
|
|
|
|
|
|
|
if [ $BOARD == FMUv1 ]
|
|
|
|
then
|
|
|
|
echo "Starting FMUv1 sensors"
|
|
|
|
if hmc5883 start
|
|
|
|
then
|
|
|
|
echo "hmc5883 started OK"
|
2014-01-22 01:34:48 -04:00
|
|
|
if hmc5883 calibrate
|
|
|
|
then
|
|
|
|
echo "hmc5883 calibrate OK"
|
|
|
|
else
|
|
|
|
echo "hmc5883 calibrate failed"
|
|
|
|
echo "hmc5883 calibrate failed" >> $logfile
|
2014-03-10 23:32:47 -03:00
|
|
|
tone_alarm MSBBB
|
2014-01-22 01:34:48 -04:00
|
|
|
fi
|
2013-08-03 05:51:59 -03:00
|
|
|
else
|
2014-01-22 01:34:48 -04:00
|
|
|
echo "hmc5883 start failed"
|
|
|
|
echo "hmc5883 start failed" >> $logfile
|
2013-08-03 05:51:59 -03:00
|
|
|
sh /etc/init.d/rc.error
|
|
|
|
fi
|
2013-10-30 01:33:42 -03:00
|
|
|
if mpu6000 start
|
|
|
|
then
|
|
|
|
echo "mpu6000 started OK"
|
|
|
|
else
|
|
|
|
sh /etc/init.d/rc.error
|
|
|
|
fi
|
2013-12-08 05:45:32 -04:00
|
|
|
if l3gd20 start
|
|
|
|
then
|
|
|
|
echo "l3gd20 started OK"
|
|
|
|
else
|
|
|
|
echo "No l3gd20"
|
|
|
|
echo "No l3gd20" >> $logfile
|
|
|
|
fi
|
2013-08-03 05:51:59 -03:00
|
|
|
else
|
|
|
|
echo "Starting FMUv2 sensors"
|
|
|
|
if hmc5883 start
|
|
|
|
then
|
|
|
|
echo "Using external magnetometer"
|
2014-01-22 01:34:48 -04:00
|
|
|
if hmc5883 calibrate
|
|
|
|
then
|
|
|
|
echo "hmc5883 calibrate OK"
|
|
|
|
else
|
|
|
|
echo "hmc5883 calibrate failed"
|
|
|
|
echo "hmc5883 calibrate failed" >> $logfile
|
2014-03-10 23:32:47 -03:00
|
|
|
tone_alarm MSBBB
|
2014-01-22 01:34:48 -04:00
|
|
|
fi
|
2013-08-03 05:51:59 -03:00
|
|
|
fi
|
2014-01-22 01:34:48 -04:00
|
|
|
|
2014-07-03 01:21:45 -03:00
|
|
|
if mpu6000 -X -R 4 start
|
2013-10-30 01:33:42 -03:00
|
|
|
then
|
2014-07-03 01:21:45 -03:00
|
|
|
echo "Found MPU6000 external"
|
|
|
|
set HAVE_FMUV3 true
|
2013-12-08 05:45:32 -04:00
|
|
|
else
|
2014-07-03 01:21:45 -03:00
|
|
|
echo "No MPU6000 external"
|
2014-07-03 11:34:41 -03:00
|
|
|
set HAVE_FMUV3 false
|
2013-12-08 05:45:32 -04:00
|
|
|
fi
|
2014-07-03 01:21:45 -03:00
|
|
|
if [ $HAVE_FMUV3 == true ]
|
2014-07-03 11:34:41 -03:00
|
|
|
then
|
2014-07-03 01:21:45 -03:00
|
|
|
if mpu6000 -R 14 start
|
|
|
|
then
|
|
|
|
echo "Found MPU6000 internal"
|
|
|
|
else
|
|
|
|
echo "No MPU6000"
|
|
|
|
echo "No MPU6000" >> $logfile
|
|
|
|
sh /etc/init.d/rc.error
|
|
|
|
fi
|
|
|
|
if l3gd20 -X -R 6 start
|
2014-06-26 01:05:15 -03:00
|
|
|
then
|
|
|
|
echo "l3gd20 external started OK"
|
|
|
|
else
|
2014-07-03 01:21:45 -03:00
|
|
|
echo "No l3gd20"
|
2014-06-26 01:05:15 -03:00
|
|
|
sh /etc/init.d/rc.error
|
|
|
|
fi
|
2014-07-03 01:21:45 -03:00
|
|
|
if lsm303d -X -R 6 start
|
2014-06-26 01:05:15 -03:00
|
|
|
then
|
|
|
|
echo "lsm303d external started OK"
|
|
|
|
else
|
2014-07-03 01:21:45 -03:00
|
|
|
echo "No lsm303d"
|
2014-06-26 01:05:15 -03:00
|
|
|
sh /etc/init.d/rc.error
|
|
|
|
fi
|
|
|
|
else
|
2014-07-03 01:21:45 -03:00
|
|
|
if mpu6000 start
|
|
|
|
then
|
|
|
|
echo "Found MPU6000"
|
|
|
|
else
|
|
|
|
echo "No MPU6000"
|
|
|
|
echo "No MPU6000" >> $logfile
|
|
|
|
fi
|
|
|
|
if l3gd20 start
|
|
|
|
then
|
|
|
|
echo "l3gd20 started OK"
|
|
|
|
else
|
|
|
|
sh /etc/init.d/rc.error
|
|
|
|
fi
|
|
|
|
if lsm303d start
|
|
|
|
then
|
|
|
|
echo "lsm303d started OK"
|
|
|
|
else
|
|
|
|
sh /etc/init.d/rc.error
|
|
|
|
fi
|
2013-08-03 05:51:59 -03:00
|
|
|
fi
|
|
|
|
fi
|
|
|
|
|
|
|
|
# optional ETS airspeed sensor
|
|
|
|
if ets_airspeed start
|
|
|
|
then
|
2014-01-13 22:57:59 -04:00
|
|
|
echo "Found ETS airspeed sensor"
|
2013-08-03 05:51:59 -03:00
|
|
|
fi
|
|
|
|
|
2013-08-21 08:06:54 -03:00
|
|
|
if meas_airspeed start
|
|
|
|
then
|
2014-01-13 22:57:59 -04:00
|
|
|
echo "Found MEAS airspeed sensor"
|
2013-08-21 08:06:54 -03:00
|
|
|
fi
|
|
|
|
|
2013-08-03 05:51:59 -03:00
|
|
|
echo "Trying PX4IO board"
|
|
|
|
|
2014-01-15 04:32:49 -04:00
|
|
|
if mtd start /fs/mtd
|
2014-01-13 21:41:07 -04:00
|
|
|
then
|
2014-01-15 04:32:49 -04:00
|
|
|
echo "started mtd driver OK"
|
|
|
|
else
|
|
|
|
echo "failed to start mtd driver"
|
2014-01-15 21:47:48 -04:00
|
|
|
echo "failed to start mtd driver" >> $logfile
|
2014-01-15 04:32:49 -04:00
|
|
|
sh /etc/init.d/rc.error
|
2014-01-13 21:41:07 -04:00
|
|
|
fi
|
|
|
|
|
2014-01-15 21:47:48 -04:00
|
|
|
if mtd readtest /fs/mtd
|
|
|
|
then
|
|
|
|
echo "mtd readtest OK"
|
|
|
|
else
|
|
|
|
echo "failed to read mtd"
|
|
|
|
echo "failed to read mtd" >> $logfile
|
|
|
|
sh /etc/init.d/rc.error
|
|
|
|
fi
|
|
|
|
|
|
|
|
if [ $BOARD == FMUv2 ]
|
|
|
|
then
|
|
|
|
# the ramtron on FMUv2 is very fast and can handle trillions of
|
|
|
|
# writes. This full rw test on each boot ensures it is working
|
|
|
|
# properly. We have one board that failed this, so
|
|
|
|
# the test is arguably worth having
|
|
|
|
if mtd rwtest /fs/mtd
|
|
|
|
then
|
|
|
|
echo "mtd rwtest OK"
|
|
|
|
else
|
|
|
|
echo "failed to test mtd"
|
|
|
|
echo "failed to test mtd" >> $logfile
|
|
|
|
sh /etc/init.d/rc.error
|
|
|
|
fi
|
|
|
|
fi
|
|
|
|
|
2014-01-13 22:57:59 -04:00
|
|
|
echo Starting ArduPilot $deviceA $deviceC $deviceD
|
2013-11-22 06:54:37 -04:00
|
|
|
if ArduPilot -d $deviceA -d2 $deviceC -d3 $deviceD start
|
2013-08-03 05:51:59 -03:00
|
|
|
then
|
|
|
|
echo ArduPilot started OK
|
2013-01-20 17:21:44 -04:00
|
|
|
else
|
2013-08-03 05:51:59 -03:00
|
|
|
sh /etc/init.d/rc.error
|
|
|
|
fi
|
|
|
|
|
2013-02-17 22:55:58 -04:00
|
|
|
echo "rc.APM finished"
|
2013-08-05 23:11:18 -03:00
|
|
|
|