aboutsummaryrefslogtreecommitdiff
path: root/ROMFS
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2013-09-12 10:15:09 +0200
committerLorenz Meier <lm@inf.ethz.ch>2013-09-12 10:15:09 +0200
commit5c0ec659b6a6ff75dce799da8504ecabdf442f28 (patch)
tree72bf65ef298a8c002cce6ea5f312882c4f205ed9 /ROMFS
parenta7dddc4dfd3cf8920a162a78db0516c8b8633222 (diff)
parent5ece19f66aeb299206c1e1e585df2b43d0ed2160 (diff)
downloadpx4-firmware-5c0ec659b6a6ff75dce799da8504ecabdf442f28.tar.gz
px4-firmware-5c0ec659b6a6ff75dce799da8504ecabdf442f28.tar.bz2
px4-firmware-5c0ec659b6a6ff75dce799da8504ecabdf442f28.zip
Merged
Diffstat (limited to 'ROMFS')
-rw-r--r--ROMFS/px4fmu_common/init.d/100_mpx_easystar54
-rw-r--r--ROMFS/px4fmu_common/init.d/101_hk_bixler82
-rw-r--r--ROMFS/px4fmu_common/init.d/30_io_camflyer61
-rw-r--r--ROMFS/px4fmu_common/init.d/31_io_phantom54
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.hil8
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.usb8
-rwxr-xr-xROMFS/px4fmu_common/init.d/rcS22
7 files changed, 209 insertions, 80 deletions
diff --git a/ROMFS/px4fmu_common/init.d/100_mpx_easystar b/ROMFS/px4fmu_common/init.d/100_mpx_easystar
index e1cefdb99..4ed73909e 100644
--- a/ROMFS/px4fmu_common/init.d/100_mpx_easystar
+++ b/ROMFS/px4fmu_common/init.d/100_mpx_easystar
@@ -1,6 +1,6 @@
#!nsh
-echo "[init] Multiplex Easystar"
+echo "[init] PX4FMU v1, v2 with or without IO on EasyStar"
#
# Load default params for this platform
@@ -20,28 +20,31 @@ fi
#
param set MAV_TYPE 1
-#
-# Start MAVLink (depends on orb)
-#
-mavlink start -d /dev/ttyS1 -b 57600
-usleep 5000
+set EXIT_ON_END no
#
-# Start and configure PX4IO interface
+# Start and configure PX4IO or FMU interface
#
-sh /etc/init.d/rc.io
+if px4io detect
+then
+ # Start MAVLink (depends on orb)
+ mavlink start
+ usleep 5000
-#
-# Set actuator limit to 100 Hz update (50 Hz PWM)
-px4io limit 100
-
-#
-# Start the commander
-#
-commander start
+ sh /etc/init.d/rc.io
+ # Limit to 100 Hz updates and (implicit) 50 Hz PWM
+ px4io limit 100
+else
+ # Start MAVLink (on UART1 / ttyS0)
+ mavlink start -d /dev/ttyS0
+ usleep 5000
+ fmu mode_pwm
+ param set BAT_V_SCALING 0.004593
+ set EXIT_ON_END yes
+fi
#
-# Start the sensors
+# Start the sensors and test them.
#
sh /etc/init.d/rc.sensors
@@ -49,9 +52,14 @@ sh /etc/init.d/rc.sensors
# Start logging (depends on sensors)
#
sh /etc/init.d/rc.logging
-
+
+#
+# Start the commander.
#
-# Start GPS interface
+commander start
+
+#
+# Start GPS interface (depends on orb)
#
gps start
@@ -65,4 +73,10 @@ att_pos_estimator_ekf start
#
mixer load /dev/pwm_output /etc/mixers/FMU_RET.mix
fw_att_control start
-fw_pos_control_l1 start
+# Not ready yet for prime-time
+#fw_pos_control_l1 start
+
+if [ $EXIT_ON_END == yes ]
+then
+ exit
+fi
diff --git a/ROMFS/px4fmu_common/init.d/101_hk_bixler b/ROMFS/px4fmu_common/init.d/101_hk_bixler
new file mode 100644
index 000000000..b4daa8f5a
--- /dev/null
+++ b/ROMFS/px4fmu_common/init.d/101_hk_bixler
@@ -0,0 +1,82 @@
+#!nsh
+
+echo "[init] PX4FMU v1, v2 with or without IO on HK Bixler"
+
+#
+# Load default params for this platform
+#
+if param compare SYS_AUTOCONFIG 1
+then
+ # Set all params here, then disable autoconfig
+ # TODO
+
+ param set SYS_AUTOCONFIG 0
+ param save
+fi
+
+#
+# Force some key parameters to sane values
+# MAV_TYPE 1 = fixed wing
+#
+param set MAV_TYPE 1
+
+set EXIT_ON_END no
+
+#
+# Start and configure PX4IO or FMU interface
+#
+if px4io detect
+then
+ # Start MAVLink (depends on orb)
+ mavlink start
+ usleep 5000
+
+ sh /etc/init.d/rc.io
+ # Limit to 100 Hz updates and (implicit) 50 Hz PWM
+ px4io limit 100
+else
+ # Start MAVLink (on UART1 / ttyS0)
+ mavlink start -d /dev/ttyS0
+ usleep 5000
+ fmu mode_pwm
+ param set BAT_V_SCALING 0.004593
+ set EXIT_ON_END yes
+fi
+
+#
+# Start the sensors and test them.
+#
+sh /etc/init.d/rc.sensors
+
+#
+# Start logging (depends on sensors)
+#
+sh /etc/init.d/rc.logging
+
+#
+# Start the commander.
+#
+commander start
+
+#
+# Start GPS interface (depends on orb)
+#
+gps start
+
+#
+# Start the attitude and position estimator
+#
+att_pos_estimator_ekf start
+
+#
+# Load mixer and start controllers (depends on px4io)
+#
+mixer load /dev/pwm_output /etc/mixers/FMU_AERT.mix
+fw_att_control start
+# Not ready yet for prime-time
+#fw_pos_control_l1 start
+
+if [ $EXIT_ON_END == yes ]
+then
+ exit
+fi
diff --git a/ROMFS/px4fmu_common/init.d/30_io_camflyer b/ROMFS/px4fmu_common/init.d/30_io_camflyer
index f7e653362..c4c4ea3da 100644
--- a/ROMFS/px4fmu_common/init.d/30_io_camflyer
+++ b/ROMFS/px4fmu_common/init.d/30_io_camflyer
@@ -1,6 +1,6 @@
#!nsh
-echo "[init] 30_io_camflyer: PX4FMU+PX4IO on Camflyer"
+echo "[init] PX4FMU v1, v2 with or without IO on Camflyer"
#
# Load default params for this platform
@@ -19,34 +19,32 @@ fi
# MAV_TYPE 1 = fixed wing
#
param set MAV_TYPE 1
-
-#
-# Start MAVLink (depends on orb)
-#
-mavlink start -d /dev/ttyS1 -b 57600
-usleep 5000
-
-#
-# Start the commander (depends on orb, mavlink)
-#
-commander start
-
-#
-# Start PX4IO interface (depends on orb, commander)
+
+set EXIT_ON_END no
+
#
-px4io start
-
+# Start and configure PX4IO or FMU interface
#
-# Allow PX4IO to recover from midair restarts.
-# this is very unlikely, but quite safe and robust.
-px4io recovery
+if px4io detect
+then
+ # Start MAVLink (depends on orb)
+ mavlink start
+ usleep 5000
-#
-# Set actuator limit to 100 Hz update (50 Hz PWM)
-px4io limit 100
+ sh /etc/init.d/rc.io
+ # Limit to 100 Hz updates and (implicit) 50 Hz PWM
+ px4io limit 100
+else
+ # Start MAVLink (on UART1 / ttyS0)
+ mavlink start -d /dev/ttyS0
+ usleep 5000
+ fmu mode_pwm
+ param set BAT_V_SCALING 0.004593
+ set EXIT_ON_END yes
+fi
#
-# Start the sensors (depends on orb, px4io)
+# Start the sensors and test them.
#
sh /etc/init.d/rc.sensors
@@ -54,7 +52,12 @@ sh /etc/init.d/rc.sensors
# Start logging (depends on sensors)
#
sh /etc/init.d/rc.logging
-
+
+#
+# Start the commander.
+#
+commander start
+
#
# Start GPS interface (depends on orb)
#
@@ -70,4 +73,10 @@ att_pos_estimator_ekf start
#
mixer load /dev/pwm_output /etc/mixers/FMU_Q.mix
fw_att_control start
-fw_pos_control_l1 start
+# Not ready yet for prime-time
+#fw_pos_control_l1 start
+
+if [ $EXIT_ON_END == yes ]
+then
+ exit
+fi
diff --git a/ROMFS/px4fmu_common/init.d/31_io_phantom b/ROMFS/px4fmu_common/init.d/31_io_phantom
index e1e609927..8d4158a18 100644
--- a/ROMFS/px4fmu_common/init.d/31_io_phantom
+++ b/ROMFS/px4fmu_common/init.d/31_io_phantom
@@ -1,6 +1,6 @@
#!nsh
-echo "[init] 31_io_phantom: PX4FMU+PX4IO on Phantom"
+echo "[init] PX4FMU v1, v2 with or without IO on Phantom FPV"
#
# Load default params for this platform
@@ -20,28 +20,31 @@ fi
#
param set MAV_TYPE 1
-#
-# Start MAVLink (depends on orb)
-#
-mavlink start -d /dev/ttyS1 -b 57600
-usleep 5000
+set EXIT_ON_END no
#
-# Start and configure PX4IO interface
+# Start and configure PX4IO or FMU interface
#
-sh /etc/init.d/rc.io
+if px4io detect
+then
+ # Start MAVLink (depends on orb)
+ mavlink start
+ usleep 5000
-#
-# Set actuator limit to 100 Hz update (50 Hz PWM)
-px4io limit 100
-
-#
-# Start the commander
-#
-commander start
+ sh /etc/init.d/rc.io
+ # Limit to 100 Hz updates and (implicit) 50 Hz PWM
+ px4io limit 100
+else
+ # Start MAVLink (on UART1 / ttyS0)
+ mavlink start -d /dev/ttyS0
+ usleep 5000
+ fmu mode_pwm
+ param set BAT_V_SCALING 0.004593
+ set EXIT_ON_END yes
+fi
#
-# Start the sensors
+# Start the sensors and test them.
#
sh /etc/init.d/rc.sensors
@@ -49,9 +52,14 @@ sh /etc/init.d/rc.sensors
# Start logging (depends on sensors)
#
sh /etc/init.d/rc.logging
-
+
+#
+# Start the commander.
#
-# Start GPS interface
+commander start
+
+#
+# Start GPS interface (depends on orb)
#
gps start
@@ -65,4 +73,10 @@ att_pos_estimator_ekf start
#
mixer load /dev/pwm_output /etc/mixers/FMU_Q.mix
fw_att_control start
-fw_pos_control_l1 start
+# Not ready yet for prime-time
+#fw_pos_control_l1 start
+
+if [ $EXIT_ON_END == yes ]
+then
+ exit
+fi
diff --git a/ROMFS/px4fmu_common/init.d/rc.hil b/ROMFS/px4fmu_common/init.d/rc.hil
index eccb2b767..b924d62bc 100644
--- a/ROMFS/px4fmu_common/init.d/rc.hil
+++ b/ROMFS/px4fmu_common/init.d/rc.hil
@@ -5,10 +5,9 @@
echo "[HIL] starting.."
-uorb start
-
# Tell MAVLink that this link is "fast"
-mavlink start -b 230400 -d /dev/ttyS1
+sleep 2
+mavlink start -b 230400 -d /dev/ttyACM0
# Create a fake HIL /dev/pwm_output interface
hil mode_pwm
@@ -50,7 +49,8 @@ att_pos_estimator_ekf start
# Load mixer and start controllers (depends on px4io)
#
mixer load /dev/pwm_output /etc/mixers/FMU_AET.mix
-fw_pos_control_l1 start
+#fw_pos_control_l1 start
fw_att_control start
echo "[HIL] setup done, running"
+
diff --git a/ROMFS/px4fmu_common/init.d/rc.usb b/ROMFS/px4fmu_common/init.d/rc.usb
index 9264985d6..ccf2cd47e 100644
--- a/ROMFS/px4fmu_common/init.d/rc.usb
+++ b/ROMFS/px4fmu_common/init.d/rc.usb
@@ -21,7 +21,6 @@ if mavlink stop
then
echo "stopped other MAVLink instance"
fi
-sleep 2
mavlink start -b 230400 -d /dev/ttyACM0
# Stop commander
@@ -37,13 +36,6 @@ then
echo "Commander started"
fi
-# Stop px4io
-if px4io stop
-then
- echo "PX4IO stopped"
-fi
-sleep 1
-
# Start px4io if present
if px4io start
then
diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS
index c8590425e..4c4b0129e 100755
--- a/ROMFS/px4fmu_common/init.d/rcS
+++ b/ROMFS/px4fmu_common/init.d/rcS
@@ -101,8 +101,14 @@ then
fi
fi
- # Try to get an USB console
- nshterm /dev/ttyACM0 &
+ if param compare SYS_AUTOSTART 1000
+ then
+ sh /etc/init.d/rc.hil
+ set MODE custom
+ else
+ # Try to get an USB console
+ nshterm /dev/ttyACM0 &
+ fi
#
# Upgrade PX4IO firmware
@@ -178,6 +184,18 @@ then
sh /etc/init.d/31_io_phantom
set MODE custom
fi
+
+ if param compare SYS_AUTOSTART 100
+ then
+ sh /etc/init.d/100_mpx_easystar
+ set MODE custom
+ fi
+
+ if param compare SYS_AUTOSTART 101
+ then
+ sh /etc/init.d/101_hk_bixler
+ set MODE custom
+ fi
# Start any custom extensions that might be missing
if [ -f /fs/microsd/etc/rc.local ]