aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2013-04-21 13:43:42 +0200
committerLorenz Meier <lm@inf.ethz.ch>2013-04-21 13:43:42 +0200
commit462064ec899f29bda72f544e84d9416e07179f31 (patch)
tree6812cd39b851b057dde151cfc3cd474b4c46e3bf
parentedc8e9aa5dc858d8177adacb64e1d7843017fac4 (diff)
parent3edd38c5dbc78bed50787d23a5b56eca088dbd42 (diff)
downloadpx4-firmware-462064ec899f29bda72f544e84d9416e07179f31.tar.gz
px4-firmware-462064ec899f29bda72f544e84d9416e07179f31.tar.bz2
px4-firmware-462064ec899f29bda72f544e84d9416e07179f31.zip
Merge branch 'master' of github.com:PX4/Firmware
-rw-r--r--ROMFS/scripts/rc.PX4IO57
-rw-r--r--ROMFS/scripts/rc.PX4IOAR27
-rwxr-xr-xROMFS/scripts/rcS8
3 files changed, 62 insertions, 30 deletions
diff --git a/ROMFS/scripts/rc.PX4IO b/ROMFS/scripts/rc.PX4IO
index 1e3963b9a..625f23bdd 100644
--- a/ROMFS/scripts/rc.PX4IO
+++ b/ROMFS/scripts/rc.PX4IO
@@ -5,7 +5,7 @@ set USB no
set MODE camflyer
#
-# Start the ORB
+# Start the ORB (first app to start)
#
uorb start
@@ -27,38 +27,65 @@ fi
param set MAV_TYPE 1
#
-# Start the sensors.
+# Check if PX4IO Firmware should be upgraded (from Andrew Tridgell)
#
-sh /etc/init.d/rc.sensors
+if [ -f /fs/microsd/px4io.bin ]
+then
+ echo "PX4IO Firmware found. Checking Upgrade.."
+ if cmp /fs/microsd/px4io.bin /fs/microsd/px4io.bin.current
+ then
+ echo "No newer version, skipping upgrade."
+ else
+ echo "Loading /fs/microsd/px4io.bin"
+ if px4io update /fs/microsd/px4io.bin > /fs/microsd/px4io_update.log
+ then
+ cp /fs/microsd/px4io.bin /fs/microsd/px4io.bin.current
+ echo "Flashed /fs/microsd/px4io.bin OK" >> /fs/microsd/px4io_update.log
+ else
+ echo "Failed flashing /fs/microsd/px4io.bin" >> /fs/microsd/px4io_update.log
+ echo "Failed to upgrade PX4IO firmware - check if PX4IO is in bootloader mode"
+ fi
+ fi
+fi
#
-# Start MAVLink
+# Start MAVLink (depends on orb)
#
mavlink start -d /dev/ttyS1 -b 57600
usleep 5000
#
-# Start the commander.
+# Start the commander (depends on orb, mavlink)
#
commander start
#
-# Start GPS interface
+# Start PX4IO interface (depends on orb, commander)
#
-gps start
+px4io start
#
-# Start the attitude estimator
+# Allow PX4IO to recover from midair restarts.
+# this is very unlikely, but quite safe and robust.
+px4io recovery
+
#
-kalman_demo start
+# Start the sensors (depends on orb, px4io)
+#
+sh /etc/init.d/rc.sensors
#
-# Start PX4IO interface
+# Start GPS interface (depends on orb)
#
-px4io start
+gps start
+
+#
+# Start the attitude estimator (depends on orb)
+#
+kalman_demo start
#
-# Load mixer and start controllers
+# Load mixer and start controllers (depends on px4io)
#
mixer load /dev/pwm_output /etc/mixers/FMU_Q.mix
control_demo start
@@ -66,8 +93,8 @@ control_demo start
#
# Start logging
#
-sdlog start -s 10
-
+#sdlog start -s 4
+
#
# Start system state
#
@@ -77,4 +104,4 @@ then
blinkm systemstate
else
echo "no BlinkM found, OK."
-fi
+fi \ No newline at end of file
diff --git a/ROMFS/scripts/rc.PX4IOAR b/ROMFS/scripts/rc.PX4IOAR
index 72df68e35..6af91992e 100644
--- a/ROMFS/scripts/rc.PX4IOAR
+++ b/ROMFS/scripts/rc.PX4IOAR
@@ -2,10 +2,10 @@
#
# Flight startup script for PX4FMU on PX4IOAR carrier board.
#
-
+
# Disable the USB interface
set USB no
-
+
# Disable autostarting other apps
set MODE ardrone
@@ -25,13 +25,18 @@ if [ -f /fs/microsd/parameters ]
then
param load /fs/microsd/parameters
fi
-
+
#
# Force some key parameters to sane values
# MAV_TYPE 1 = fixed wing, 2 = quadrotor, 13 = hexarotor
# see https://pixhawk.ethz.ch/mavlink/
#
param set MAV_TYPE 2
+
+#
+# Configure PX4FMU for operation with PX4IOAR
+#
+fmu mode_gpio_serial
#
# Start the sensors.
@@ -55,11 +60,6 @@ commander start
attitude_estimator_ekf start
#
-# Configure PX4FMU for operation with PX4IOAR
-#
-fmu mode_gpio_serial
-
-#
# Fire up the multi rotor attitude controller
#
multirotor_att_control start
@@ -68,11 +68,6 @@ multirotor_att_control start
# Fire up the AR.Drone interface.
#
ardrone_interface start -d /dev/ttyS1
-
-#
-# Start GPS capture
-#
-gps start
#
# Start logging
@@ -80,6 +75,11 @@ gps start
sdlog start -s 10
#
+# Start GPS capture
+#
+gps start
+
+#
# Start system state
#
if blinkm start
@@ -95,4 +95,5 @@ fi
# use the same UART for telemetry
#
echo "[init] startup done"
+
exit \ No newline at end of file
diff --git a/ROMFS/scripts/rcS b/ROMFS/scripts/rcS
index 89a767879..c0a70f7dd 100755
--- a/ROMFS/scripts/rcS
+++ b/ROMFS/scripts/rcS
@@ -21,9 +21,9 @@ set MODE autostart
set USB autoconnect
#
-# Start playing the startup tune
+
#
-tone_alarm start
+
#
# Try to mount the microSD card.
@@ -32,8 +32,12 @@ echo "[init] looking for microSD..."
if mount -t vfat /dev/mmcsd0 /fs/microsd
then
echo "[init] card mounted at /fs/microsd"
+ # Start playing the startup tune
+ tone_alarm start
else
echo "[init] no microSD card found"
+ # Play SOS
+ tone_alarm 2
fi
#