aboutsummaryrefslogtreecommitdiff
path: root/ROMFS/px4fmu_common
diff options
context:
space:
mode:
Diffstat (limited to 'ROMFS/px4fmu_common')
-rw-r--r--ROMFS/px4fmu_common/init.d/02_io_quad_x101
-rw-r--r--ROMFS/px4fmu_common/init.d/08_ardrone86
-rw-r--r--ROMFS/px4fmu_common/init.d/09_ardrone_flow62
-rw-r--r--ROMFS/px4fmu_common/init.d/100_mpx_easystar68
-rw-r--r--ROMFS/px4fmu_common/init.d/10_dji_f33093
-rw-r--r--ROMFS/px4fmu_common/init.d/10_io_f330116
-rw-r--r--ROMFS/px4fmu_common/init.d/11_dji_f45077
-rw-r--r--ROMFS/px4fmu_common/init.d/15_tbs_discovery77
-rw-r--r--ROMFS/px4fmu_common/init.d/16_3dr_iris77
-rw-r--r--ROMFS/px4fmu_common/init.d/30_io_camflyer78
-rw-r--r--ROMFS/px4fmu_common/init.d/31_io_phantom103
-rw-r--r--ROMFS/px4fmu_common/init.d/40_io_segway84
-rw-r--r--ROMFS/px4fmu_common/init.d/666_fmu_q_x550 (renamed from ROMFS/px4fmu_common/init.d/01_fmu_quad_x)73
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.boarddetect66
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.hil22
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.io23
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.logging7
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.multirotor44
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.sensors22
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.usb22
-rwxr-xr-xROMFS/px4fmu_common/init.d/rcS221
21 files changed, 752 insertions, 770 deletions
diff --git a/ROMFS/px4fmu_common/init.d/02_io_quad_x b/ROMFS/px4fmu_common/init.d/02_io_quad_x
deleted file mode 100644
index c63e92f6d..000000000
--- a/ROMFS/px4fmu_common/init.d/02_io_quad_x
+++ /dev/null
@@ -1,101 +0,0 @@
-#!nsh
-#
-# Flight startup script for PX4FMU+PX4IO
-#
-
-# disable USB and autostart
-set USB no
-set MODE custom
-
-#
-# Start the ORB (first app to start)
-#
-uorb start
-
-#
-# Load microSD params
-#
-echo "[init] loading microSD params"
-param select /fs/microsd/params
-if [ -f /fs/microsd/params ]
-then
- param load /fs/microsd/params
-fi
-
-#
-# Load default params for this platform
-#
-if param compare SYS_AUTOCONFIG 1
-then
- # Set all params here, then disable autoconfig
- param set SYS_AUTOCONFIG 0
- param save /fs/microsd/params
-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
-
-#
-# 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)
-#
-px4io start
-
-#
-# Allow PX4IO to recover from midair restarts.
-# this is very unlikely, but quite safe and robust.
-px4io recovery
-
-#
-# Disable px4io topic limiting
-#
-px4io limit 200
-
-#
-# Start the sensors (depends on orb, px4io)
-#
-sh /etc/init.d/rc.sensors
-
-#
-# Start GPS interface (depends on orb)
-#
-gps start
-
-#
-# Start the attitude estimator (depends on orb)
-#
-attitude_estimator_ekf start
-
-#
-# Load mixer and start controllers (depends on px4io)
-#
-mixer load /dev/pwm_output /etc/mixers/FMU_quad_x.mix
-pwm -u 400 -m 0xff
-multirotor_att_control start
-
-#
-# Start logging
-#
-sdlog2 start -r 50 -a -b 14
-
-#
-# Start system state
-#
-if blinkm start
-then
- blinkm systemstate
-fi
diff --git a/ROMFS/px4fmu_common/init.d/08_ardrone b/ROMFS/px4fmu_common/init.d/08_ardrone
index f55ac2ae3..f6d82a5ec 100644
--- a/ROMFS/px4fmu_common/init.d/08_ardrone
+++ b/ROMFS/px4fmu_common/init.d/08_ardrone
@@ -1,99 +1,45 @@
#!nsh
-#
-# Flight startup script for PX4FMU on PX4IOAR carrier board.
-#
-
-# Disable the USB interface
-set USB no
-# Disable autostarting other apps
-set MODE ardrone
-
-echo "[init] doing PX4IOAR startup..."
-
-#
-# Start the ORB
-#
-uorb start
+echo "[init] 08_ardrone: PX4FMU on PX4IOAR carrier board"
#
-# Load microSD params
+# Load default params for this platform
#
-echo "[init] loading microSD params"
-param select /fs/microsd/params
-if [ -f /fs/microsd/params ]
+if param compare SYS_AUTOCONFIG 1
then
- param load /fs/microsd/params
+ # 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, 2 = quadrotor, 13 = hexarotor
-# see https://pixhawk.ethz.ch/mavlink/
+# MAV_TYPE 2 = quadrotor
#
param set MAV_TYPE 2
#
-# Configure PX4FMU for operation with PX4IOAR
-#
-fmu mode_gpio_serial
-
-#
-# Start the sensors.
-#
-sh /etc/init.d/rc.sensors
-
-#
# Start MAVLink
#
mavlink start -d /dev/ttyS0 -b 57600
usleep 5000
-
-#
-# Start the commander.
-#
-commander start
-
-#
-# Start the attitude estimator
-#
-attitude_estimator_ekf start
-
+
#
-# Fire up the multi rotor attitude controller
+# Configure PX4FMU for operation with PX4IOAR
#
-multirotor_att_control start
+fmu mode_gpio_serial
#
# Fire up the AR.Drone interface.
#
ardrone_interface start -d /dev/ttyS1
-
-#
-# Start logging
-#
-sdlog start -s 10
-
-#
-# Start GPS capture
-#
-gps start
-
-#
-# Start system state
-#
-if blinkm start
-then
- echo "using BlinkM for state indication"
- blinkm systemstate
-else
- echo "no BlinkM found, OK."
-fi
#
-# startup is done; we don't want the shell because we
-# use the same UART for telemetry
+# Start common for all multirotors apps
#
-echo "[init] startup done"
-
+sh /etc/init.d/rc.multirotor
+
+# Exit, because /dev/ttyS0 is needed for MAVLink
exit
diff --git a/ROMFS/px4fmu_common/init.d/09_ardrone_flow b/ROMFS/px4fmu_common/init.d/09_ardrone_flow
index e7173f6e6..794342a0b 100644
--- a/ROMFS/px4fmu_common/init.d/09_ardrone_flow
+++ b/ROMFS/px4fmu_common/init.d/09_ardrone_flow
@@ -1,42 +1,41 @@
#!nsh
-#
-# Flight startup script for PX4FMU on PX4IOAR carrier board.
-#
-# Disable the USB interface
-set USB no
+echo "[init] 09_ardrone_flow: PX4FMU on PX4IOAR carrier board with PX4FLOW"
-# Disable autostarting other apps
-set MODE ardrone
-
-echo "[init] doing PX4IOAR startup..."
-
#
-# Start the ORB
+# Load default params for this platform
#
-uorb start
-
-#
-# Load microSD params
-#
-echo "[init] loading microSD params"
-param select /fs/microsd/params
-if [ -f /fs/microsd/params ]
+if param compare SYS_AUTOCONFIG 1
then
- param load /fs/microsd/params
+ # 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, 2 = quadrotor, 13 = hexarotor
-# see https://pixhawk.ethz.ch/mavlink/
+# MAV_TYPE 2 = quadrotor
#
param set MAV_TYPE 2
#
+# Start MAVLink and MAVLink Onboard (PX4FLOW Sensor)
+#
+mavlink start -d /dev/ttyS0 -b 57600
+mavlink_onboard start -d /dev/ttyS3 -b 115200
+usleep 5000
+
+#
# Configure PX4FMU for operation with PX4IOAR
#
fmu mode_gpio_serial
+
+#
+# Fire up the AR.Drone interface.
+#
+ardrone_interface start -d /dev/ttyS1
#
# Start the sensors.
@@ -44,13 +43,6 @@ fmu mode_gpio_serial
sh /etc/init.d/rc.sensors
#
-# Start MAVLink and MAVLink Onboard (Flow Sensor)
-#
-mavlink start -d /dev/ttyS0 -b 57600
-mavlink_onboard start -d /dev/ttyS3 -b 115200
-usleep 5000
-
-#
# Start the commander.
#
commander start
@@ -79,16 +71,6 @@ flow_position_control start
# Fire up the flow speed controller
#
flow_speed_control start
-
-#
-# Fire up the AR.Drone interface.
-#
-ardrone_interface start -d /dev/ttyS1
-#
-# startup is done; we don't want the shell because we
-# use the same UART for telemetry
-#
-echo "[init] startup done"
-
+# Exit, because /dev/ttyS0 is needed for MAVLink
exit
diff --git a/ROMFS/px4fmu_common/init.d/100_mpx_easystar b/ROMFS/px4fmu_common/init.d/100_mpx_easystar
new file mode 100644
index 000000000..e1cefdb99
--- /dev/null
+++ b/ROMFS/px4fmu_common/init.d/100_mpx_easystar
@@ -0,0 +1,68 @@
+#!nsh
+
+echo "[init] Multiplex Easystar"
+
+#
+# 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
+
+#
+# Start MAVLink (depends on orb)
+#
+mavlink start -d /dev/ttyS1 -b 57600
+usleep 5000
+
+#
+# Start and configure PX4IO interface
+#
+sh /etc/init.d/rc.io
+
+#
+# Set actuator limit to 100 Hz update (50 Hz PWM)
+px4io limit 100
+
+#
+# Start the commander
+#
+commander start
+
+#
+# Start the sensors
+#
+sh /etc/init.d/rc.sensors
+
+#
+# Start logging (depends on sensors)
+#
+sh /etc/init.d/rc.logging
+
+#
+# Start GPS interface
+#
+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_RET.mix
+fw_att_control start
+fw_pos_control_l1 start
diff --git a/ROMFS/px4fmu_common/init.d/10_dji_f330 b/ROMFS/px4fmu_common/init.d/10_dji_f330
new file mode 100644
index 000000000..743dce9ef
--- /dev/null
+++ b/ROMFS/px4fmu_common/init.d/10_dji_f330
@@ -0,0 +1,93 @@
+#!nsh
+
+echo "[init] PX4FMU v1, v2 with or without IO on DJI F330"
+
+#
+# Load default params for this platform
+#
+if param compare SYS_AUTOCONFIG 1
+then
+ # Set all params here, then disable autoconfig
+ param set SYS_AUTOCONFIG 0
+
+ param set MC_ATTRATE_D 0.004
+ param set MC_ATTRATE_I 0.0
+ param set MC_ATTRATE_P 0.12
+ param set MC_ATT_D 0.0
+ param set MC_ATT_I 0.0
+ param set MC_ATT_P 7.0
+ param set MC_YAWPOS_D 0.0
+ param set MC_YAWPOS_I 0.0
+ param set MC_YAWPOS_P 2.0
+ param set MC_YAWRATE_D 0.005
+ param set MC_YAWRATE_I 0.2
+ param set MC_YAWRATE_P 0.3
+ param set NAV_TAKEOFF_ALT 1.0
+ param set MPC_TILT_MAX 0.5
+ param set MPC_THR_MAX 0.7
+ param set MPC_THR_MIN 0.3
+ param set MPC_XY_D 0
+ param set MPC_XY_P 0.5
+ param set MPC_XY_VEL_D 0
+ param set MPC_XY_VEL_I 0
+ param set MPC_XY_VEL_MAX 2
+ param set MPC_XY_VEL_P 0.2
+ param set MPC_Z_D 0
+ param set MPC_Z_P 1
+ param set MPC_Z_VEL_D 0
+ param set MPC_Z_VEL_I 0.10
+ param set MPC_Z_VEL_MAX 2
+ param set MPC_Z_VEL_P 0.20
+
+ param save
+fi
+
+#
+# Force some key parameters to sane values
+# MAV_TYPE 2 = quadrotor
+#
+param set MAV_TYPE 2
+
+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
+ # Set PWM values for DJI ESCs
+ px4io idle 900 900 900 900
+ px4io min 1200 1200 1200 1200
+ px4io max 1800 1800 1800 1800
+else
+ # Start MAVLink (on UART1 / ttyS0)
+ mavlink start -d /dev/ttyS0
+ usleep 5000
+ fmu mode_pwm
+ set EXIT_ON_END yes
+fi
+
+#
+# Load mixer
+#
+mixer load /dev/pwm_output /etc/mixers/FMU_quad_x.mix
+
+#
+# Set PWM output frequency
+#
+pwm -u 400 -m 0xff
+
+#
+# Start common for all multirotors apps
+#
+sh /etc/init.d/rc.multirotor
+
+if [ $EXIT_ON_END == yes ]
+then
+ exit
+fi
diff --git a/ROMFS/px4fmu_common/init.d/10_io_f330 b/ROMFS/px4fmu_common/init.d/10_io_f330
deleted file mode 100644
index 4450eb50d..000000000
--- a/ROMFS/px4fmu_common/init.d/10_io_f330
+++ /dev/null
@@ -1,116 +0,0 @@
-#!nsh
-#
-# Flight startup script for PX4FMU+PX4IO
-#
-
-# disable USB and autostart
-set USB no
-set MODE custom
-
-#
-# Load default params for this platform
-#
-if param compare SYS_AUTOCONFIG 1
-then
- # Set all params here, then disable autoconfig
- param set SYS_AUTOCONFIG 0
-
- param set MC_ATTRATE_D 0.005
- param set MC_ATTRATE_I 0.0
- param set MC_ATTRATE_P 0.1
- param set MC_ATT_D 0.0
- param set MC_ATT_I 0.0
- param set MC_ATT_P 4.5
- param set MC_RCLOSS_THR 0.0
- param set MC_YAWPOS_D 0.0
- param set MC_YAWPOS_I 0.3
- param set MC_YAWPOS_P 0.6
- param set MC_YAWRATE_D 0.0
- param set MC_YAWRATE_I 0.0
- param set MC_YAWRATE_P 0.1
-
- param save /fs/microsd/params
-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
-
-#
-# Start MAVLink (depends on orb)
-#
-mavlink start
-usleep 5000
-
-#
-# Start PX4IO interface (depends on orb, commander)
-#
-px4io start
-pwm -u 400 -m 0xff
-
-#
-# Allow PX4IO to recover from midair restarts.
-# this is very unlikely, but quite safe and robust.
-px4io recovery
-
-#
-# Disable px4io topic limiting
-#
-px4io limit 200
-
-#
-# This sets a PWM right after startup (regardless of safety button)
-#
-px4io idle 900 900 900 900
-
-#
-# The values are for spinning motors when armed using DJI ESCs
-#
-px4io min 1200 1200 1200 1200
-
-#
-# Upper limits could be higher, this is on the safe side
-#
-px4io max 1800 1800 1800 1800
-
-#
-# Start the sensors (depends on orb, px4io)
-#
-sh /etc/init.d/rc.sensors
-
-#
-# Start the commander (depends on orb, mavlink)
-#
-commander start
-
-#
-# Start GPS interface (depends on orb)
-#
-gps start
-
-#
-# Start the attitude estimator (depends on orb)
-#
-attitude_estimator_ekf start
-
-#
-# Load mixer and start controllers (depends on px4io)
-#
-mixer load /dev/pwm_output /etc/mixers/FMU_quad_x.mix
-multirotor_att_control start
-
-#
-# Start logging
-#
-sdlog2 start -r 20 -a -b 16
-
-#
-# Start system state
-#
-if blinkm start
-then
- blinkm systemstate
-fi
diff --git a/ROMFS/px4fmu_common/init.d/11_dji_f450 b/ROMFS/px4fmu_common/init.d/11_dji_f450
new file mode 100644
index 000000000..1827a2c11
--- /dev/null
+++ b/ROMFS/px4fmu_common/init.d/11_dji_f450
@@ -0,0 +1,77 @@
+#!nsh
+
+echo "[init] PX4FMU v1, v2 with or without IO on DJI F450"
+
+#
+# Load default params for this platform
+#
+if param compare SYS_AUTOCONFIG 1
+then
+ # Set all params here, then disable autoconfig
+ param set SYS_AUTOCONFIG 0
+
+ param set MC_ATTRATE_D 0.004
+ param set MC_ATTRATE_I 0.0
+ param set MC_ATTRATE_P 0.12
+ param set MC_ATT_D 0.0
+ param set MC_ATT_I 0.0
+ param set MC_ATT_P 7.0
+ param set MC_YAWPOS_D 0.0
+ param set MC_YAWPOS_I 0.0
+ param set MC_YAWPOS_P 2.0
+ param set MC_YAWRATE_D 0.005
+ param set MC_YAWRATE_I 0.2
+ param set MC_YAWRATE_P 0.3
+
+ param save
+fi
+
+#
+# Force some key parameters to sane values
+# MAV_TYPE 2 = quadrotor
+#
+param set MAV_TYPE 2
+
+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
+ # Set PWM values for DJI ESCs
+ px4io idle 900 900 900 900
+ px4io min 1200 1200 1200 1200
+ px4io max 1800 1800 1800 1800
+else
+ # Start MAVLink (on UART1 / ttyS0)
+ mavlink start -d /dev/ttyS0
+ usleep 5000
+ fmu mode_pwm
+ set EXIT_ON_END yes
+fi
+
+#
+# Load mixer
+#
+mixer load /dev/pwm_output /etc/mixers/FMU_quad_x.mix
+
+#
+# Set PWM output frequency
+#
+pwm -u 400 -m 0xff
+
+#
+# Start common for all multirotors apps
+#
+sh /etc/init.d/rc.multirotor
+
+if [ $EXIT_ON_END == yes ]
+then
+ exit
+fi
diff --git a/ROMFS/px4fmu_common/init.d/15_tbs_discovery b/ROMFS/px4fmu_common/init.d/15_tbs_discovery
new file mode 100644
index 000000000..1fcde3e27
--- /dev/null
+++ b/ROMFS/px4fmu_common/init.d/15_tbs_discovery
@@ -0,0 +1,77 @@
+#!nsh
+
+echo "[init] Team Blacksheep Discovery Quad"
+
+#
+# Load default params for this platform
+#
+if param compare SYS_AUTOCONFIG 1
+then
+ # Set all params here, then disable autoconfig
+ param set SYS_AUTOCONFIG 0
+
+ param set MC_ATTRATE_D 0.006
+ param set MC_ATTRATE_I 0.0
+ param set MC_ATTRATE_P 0.17
+ param set MC_ATT_D 0.0
+ param set MC_ATT_I 0.0
+ param set MC_ATT_P 5.0
+ param set MC_YAWPOS_D 0.0
+ param set MC_YAWPOS_I 0.15
+ param set MC_YAWPOS_P 0.5
+ param set MC_YAWRATE_D 0.0
+ param set MC_YAWRATE_I 0.0
+ param set MC_YAWRATE_P 0.2
+
+ param save
+fi
+
+#
+# Force some key parameters to sane values
+# MAV_TYPE 2 = quadrotor
+#
+param set MAV_TYPE 2
+
+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
+ # Set PWM values for DJI ESCs
+ px4io idle 900 900 900 900
+ px4io min 1200 1200 1200 1200
+ px4io max 1800 1800 1800 1800
+else
+ # Start MAVLink (on UART1 / ttyS0)
+ mavlink start -d /dev/ttyS0
+ usleep 5000
+ fmu mode_pwm
+ set EXIT_ON_END yes
+fi
+
+#
+# Load the mixer for a quad with wide arms
+#
+mixer load /dev/pwm_output /etc/mixers/FMU_quad_w.mix
+
+#
+# Set PWM output frequency
+#
+pwm -u 400 -m 0xff
+
+#
+# Start common for all multirotors apps
+#
+sh /etc/init.d/rc.multirotor
+
+if [ $EXIT_ON_END == yes ]
+then
+ exit
+fi
diff --git a/ROMFS/px4fmu_common/init.d/16_3dr_iris b/ROMFS/px4fmu_common/init.d/16_3dr_iris
new file mode 100644
index 000000000..fa2cb1feb
--- /dev/null
+++ b/ROMFS/px4fmu_common/init.d/16_3dr_iris
@@ -0,0 +1,77 @@
+#!nsh
+
+echo "[init] 3DR Iris Quad"
+
+#
+# Load default params for this platform
+#
+if param compare SYS_AUTOCONFIG 1
+then
+ # Set all params here, then disable autoconfig
+ param set SYS_AUTOCONFIG 0
+
+ param set MC_ATTRATE_D 0.006
+ param set MC_ATTRATE_I 0.0
+ param set MC_ATTRATE_P 0.17
+ param set MC_ATT_D 0.0
+ param set MC_ATT_I 0.0
+ param set MC_ATT_P 5.0
+ param set MC_YAWPOS_D 0.0
+ param set MC_YAWPOS_I 0.15
+ param set MC_YAWPOS_P 0.5
+ param set MC_YAWRATE_D 0.0
+ param set MC_YAWRATE_I 0.0
+ param set MC_YAWRATE_P 0.2
+
+ param save
+fi
+
+#
+# Force some key parameters to sane values
+# MAV_TYPE 2 = quadrotor
+#
+param set MAV_TYPE 2
+
+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
+ # Set PWM values for DJI ESCs
+ px4io idle 900 900 900 900
+ px4io min 1200 1200 1200 1200
+ px4io max 1800 1800 1800 1800
+else
+ # Start MAVLink (on UART1 / ttyS0)
+ mavlink start -d /dev/ttyS0
+ usleep 5000
+ fmu mode_pwm
+ set EXIT_ON_END yes
+fi
+
+#
+# Load the mixer for a quad with wide arms
+#
+mixer load /dev/pwm_output /etc/mixers/FMU_quad_w.mix
+
+#
+# Set PWM output frequency
+#
+pwm -u 400 -m 0xff
+
+#
+# Start common for all multirotors apps
+#
+sh /etc/init.d/rc.multirotor
+
+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 5090b98a4..f7e653362 100644
--- a/ROMFS/px4fmu_common/init.d/30_io_camflyer
+++ b/ROMFS/px4fmu_common/init.d/30_io_camflyer
@@ -1,26 +1,6 @@
#!nsh
-#
-# Flight startup script for PX4FMU+PX4IO
-#
-
-# disable USB and autostart
-set USB no
-set MODE custom
-
-#
-# Start the ORB (first app to start)
-#
-uorb start
-
-#
-# Load microSD params
-#
-echo "[init] loading microSD params"
-param select /fs/microsd/params
-if [ -f /fs/microsd/params ]
-then
- param load /fs/microsd/params
-fi
+
+echo "[init] 30_io_camflyer: PX4FMU+PX4IO on Camflyer"
#
# Load default params for this platform
@@ -28,40 +8,19 @@ fi
if param compare SYS_AUTOCONFIG 1
then
# Set all params here, then disable autoconfig
+ # TODO
+
param set SYS_AUTOCONFIG 0
- param save /fs/microsd/params
+ param save
fi
#
# Force some key parameters to sane values
-# MAV_TYPE 1 = fixed wing, 2 = quadrotor, 13 = hexarotor
-# see https://pixhawk.ethz.ch/mavlink/
+# MAV_TYPE 1 = fixed wing
#
param set MAV_TYPE 1
#
-# Check if PX4IO Firmware should be upgraded (from Andrew Tridgell)
-#
-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 (depends on orb)
#
mavlink start -d /dev/ttyS1 -b 57600
@@ -90,6 +49,11 @@ px4io limit 100
# Start the sensors (depends on orb, px4io)
#
sh /etc/init.d/rc.sensors
+
+#
+# Start logging (depends on sensors)
+#
+sh /etc/init.d/rc.logging
#
# Start GPS interface (depends on orb)
@@ -97,25 +61,13 @@ sh /etc/init.d/rc.sensors
gps start
#
-# Start the attitude estimator (depends on orb)
+# Start the attitude and position estimator
#
-kalman_demo start
+att_pos_estimator_ekf start
#
# Load mixer and start controllers (depends on px4io)
#
mixer load /dev/pwm_output /etc/mixers/FMU_Q.mix
-control_demo start
-
-#
-# Start logging
-#
-sdlog2 start -r 50 -a -b 14
-
-#
-# Start system state
-#
-if blinkm start
-then
- blinkm systemstate
-fi
+fw_att_control start
+fw_pos_control_l1 start
diff --git a/ROMFS/px4fmu_common/init.d/31_io_phantom b/ROMFS/px4fmu_common/init.d/31_io_phantom
index 5090b98a4..e1e609927 100644
--- a/ROMFS/px4fmu_common/init.d/31_io_phantom
+++ b/ROMFS/px4fmu_common/init.d/31_io_phantom
@@ -1,26 +1,6 @@
#!nsh
-#
-# Flight startup script for PX4FMU+PX4IO
-#
-
-# disable USB and autostart
-set USB no
-set MODE custom
-
-#
-# Start the ORB (first app to start)
-#
-uorb start
-
-#
-# Load microSD params
-#
-echo "[init] loading microSD params"
-param select /fs/microsd/params
-if [ -f /fs/microsd/params ]
-then
- param load /fs/microsd/params
-fi
+
+echo "[init] 31_io_phantom: PX4FMU+PX4IO on Phantom"
#
# Load default params for this platform
@@ -28,94 +8,61 @@ fi
if param compare SYS_AUTOCONFIG 1
then
# Set all params here, then disable autoconfig
+ # TODO
+
param set SYS_AUTOCONFIG 0
- param save /fs/microsd/params
+ param save
fi
#
# Force some key parameters to sane values
-# MAV_TYPE 1 = fixed wing, 2 = quadrotor, 13 = hexarotor
-# see https://pixhawk.ethz.ch/mavlink/
+# MAV_TYPE 1 = fixed wing
#
param set MAV_TYPE 1
-
-#
-# Check if PX4IO Firmware should be upgraded (from Andrew Tridgell)
-#
-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 (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)
+
#
-px4io start
-
+# Start and configure PX4IO interface
#
-# Allow PX4IO to recover from midair restarts.
-# this is very unlikely, but quite safe and robust.
-px4io recovery
+sh /etc/init.d/rc.io
#
# Set actuator limit to 100 Hz update (50 Hz PWM)
px4io limit 100
#
-# Start the sensors (depends on orb, px4io)
+# Start the commander
#
-sh /etc/init.d/rc.sensors
+commander start
#
-# Start GPS interface (depends on orb)
+# Start the sensors
#
-gps start
-
+sh /etc/init.d/rc.sensors
+
#
-# Start the attitude estimator (depends on orb)
+# Start logging (depends on sensors)
#
-kalman_demo start
+sh /etc/init.d/rc.logging
#
-# Load mixer and start controllers (depends on px4io)
+# Start GPS interface
#
-mixer load /dev/pwm_output /etc/mixers/FMU_Q.mix
-control_demo start
+gps start
#
-# Start logging
+# Start the attitude and position estimator
#
-sdlog2 start -r 50 -a -b 14
+att_pos_estimator_ekf start
#
-# Start system state
+# Load mixer and start controllers (depends on px4io)
#
-if blinkm start
-then
- blinkm systemstate
-fi
+mixer load /dev/pwm_output /etc/mixers/FMU_Q.mix
+fw_att_control start
+fw_pos_control_l1 start
diff --git a/ROMFS/px4fmu_common/init.d/40_io_segway b/ROMFS/px4fmu_common/init.d/40_io_segway
index 5742d685a..4b7ed5286 100644
--- a/ROMFS/px4fmu_common/init.d/40_io_segway
+++ b/ROMFS/px4fmu_common/init.d/40_io_segway
@@ -1,26 +1,4 @@
#!nsh
-#
-# Flight startup script for PX4FMU+PX4IO
-#
-
-# disable USB and autostart
-set USB no
-set MODE custom
-
-#
-# Start the ORB (first app to start)
-#
-uorb start
-
-#
-# Load microSD params
-#
-echo "[init] loading microSD params"
-param select /fs/microsd/params
-if [ -f /fs/microsd/params ]
-then
- param load /fs/microsd/params
-fi
#
# Load default params for this platform
@@ -28,39 +6,18 @@ fi
if param compare SYS_AUTOCONFIG 1
then
# Set all params here, then disable autoconfig
+ # TODO
+
param set SYS_AUTOCONFIG 0
- param save /fs/microsd/params
+ param save
fi
#
# Force some key parameters to sane values
-# MAV_TYPE 1 = fixed wing, 2 = quadrotor, 13 = hexarotor
-# see https://pixhawk.ethz.ch/mavlink/
+# MAV_TYPE 10 = ground rover
#
param set MAV_TYPE 10
-
-#
-# Check if PX4IO Firmware should be upgraded (from Andrew Tridgell)
-#
-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 (depends on orb)
#
@@ -68,26 +25,16 @@ mavlink start -d /dev/ttyS1 -b 57600
usleep 5000
#
-# Start the commander (depends on orb, mavlink)
+# Start and configure PX4IO interface
#
-commander start
+sh /etc/init.d/rc.io
#
-# Start PX4IO interface (depends on orb, commander)
-#
-px4io start
-
+# Start the commander (depends on orb, mavlink)
#
-# Allow PX4IO to recover from midair restarts.
-# this is very unlikely, but quite safe and robust.
-px4io recovery
+commander start
#
-# Disable px4io topic limiting
-#
-px4io limit 200
-
-#
# Start the sensors (depends on orb, px4io)
#
sh /etc/init.d/rc.sensors
@@ -107,16 +54,3 @@ attitude_estimator_ekf start
#
md25 start 3 0x58
segway start
-
-#
-# Start logging
-#
-sdlog2 start -r 50 -a -b 14
-
-#
-# Start system state
-#
-if blinkm start
-then
- blinkm systemstate
-fi
diff --git a/ROMFS/px4fmu_common/init.d/01_fmu_quad_x b/ROMFS/px4fmu_common/init.d/666_fmu_q_x550
index 58a970eba..938663f0c 100644
--- a/ROMFS/px4fmu_common/init.d/01_fmu_quad_x
+++ b/ROMFS/px4fmu_common/init.d/666_fmu_q_x550
@@ -1,28 +1,6 @@
#!nsh
-#
-# Flight startup script for PX4FMU with PWM outputs.
-#
-
-# disable USB and autostart
-set USB no
-set MODE custom
-
-echo "[init] doing PX4FMU Quad startup..."
-
-#
-# Start the ORB
-#
-uorb start
-
-#
-# Load microSD params
-#
-echo "[init] loading microSD params"
-param select /fs/microsd/params
-if [ -f /fs/microsd/params ]
-then
- param load /fs/microsd/params
-fi
+
+echo "[init] 666_fmu_q_x550: PX4FMU Quad X550 with PWM outputs"
#
# Load default params for this platform
@@ -47,13 +25,12 @@ then
param set RC_SCALE_YAW 3
param set SYS_AUTOCONFIG 0
- param save /fs/microsd/params
+ param save
fi
#
# Force some key parameters to sane values
-# MAV_TYPE 1 = fixed wing, 2 = quadrotor, 13 = hexarotor
-# see https://pixhawk.ethz.ch/mavlink/
+# MAV_TYPE 2 = quadrotor
#
param set MAV_TYPE 2
@@ -62,46 +39,26 @@ param set MAV_TYPE 2
#
mavlink start -d /dev/ttyS0 -b 57600
usleep 5000
-
-#
-# Start the sensors and test them.
-#
-sh /etc/init.d/rc.sensors
-
-#
-# Start the commander.
-#
-commander start
#
-# Start GPS interface (depends on orb)
+# Start PWM output
#
-gps start
-
+fmu mode_pwm
+
#
-# Start the attitude estimator
+# Load mixer
#
-attitude_estimator_ekf start
-
-echo "[init] starting PWM output"
-fmu mode_pwm
mixer load /dev/pwm_output /etc/mixers/FMU_quad_x.mix
-pwm -u 400 -m 0xff
-
+
#
-# Start attitude control
+# Set PWM output frequency
#
-multirotor_att_control start
+pwm -u 400 -m 0xff
#
-# Start logging
+# Start common for all multirotors apps
#
-sdlog2 start -r 50 -a -b 14
+sh /etc/init.d/rc.multirotor
-#
-# Start system state
-#
-if blinkm start
-then
- blinkm systemstate
-fi
+# Exit, because /dev/ttyS0 is needed for MAVLink
+exit
diff --git a/ROMFS/px4fmu_common/init.d/rc.boarddetect b/ROMFS/px4fmu_common/init.d/rc.boarddetect
deleted file mode 100644
index f233e51df..000000000
--- a/ROMFS/px4fmu_common/init.d/rc.boarddetect
+++ /dev/null
@@ -1,66 +0,0 @@
-#!nsh
-#
-# If we are still in flight mode, work out what airframe
-# configuration we have and start up accordingly.
-#
-if [ $MODE != autostart ]
-then
- echo "[init] automatic startup cancelled by user script"
-else
- echo "[init] detecting attached hardware..."
-
- #
- # Assume that we are PX4FMU in standalone mode
- #
- set BOARD PX4FMU
-
- #
- # Are we attached to a PX4IOAR (AR.Drone carrier board)?
- #
- if boardinfo test name PX4IOAR
- then
- set BOARD PX4IOAR
- if [ -f /etc/init.d/rc.PX4IOAR ]
- then
- echo "[init] reading /etc/init.d/rc.PX4IOAR"
- usleep 500
- sh /etc/init.d/rc.PX4IOAR
- fi
- else
- echo "[init] PX4IOAR not detected"
- fi
-
- #
- # Are we attached to a PX4IO?
- #
- if boardinfo test name PX4IO
- then
- set BOARD PX4IO
- if [ -f /etc/init.d/rc.PX4IO ]
- then
- echo "[init] reading /etc/init.d/rc.PX4IO"
- usleep 500
- sh /etc/init.d/rc.PX4IO
- fi
- else
- echo "[init] PX4IO not detected"
- fi
-
- #
- # Looks like we are stand-alone
- #
- if [ $BOARD == PX4FMU ]
- then
- echo "[init] no expansion board detected"
- if [ -f /etc/init.d/rc.standalone ]
- then
- echo "[init] reading /etc/init.d/rc.standalone"
- sh /etc/init.d/rc.standalone
- fi
- fi
-
- #
- # We may not reach here if the airframe-specific script exits the shell.
- #
- echo "[init] startup done."
-fi \ No newline at end of file
diff --git a/ROMFS/px4fmu_common/init.d/rc.hil b/ROMFS/px4fmu_common/init.d/rc.hil
index 3517a5bd8..eccb2b767 100644
--- a/ROMFS/px4fmu_common/init.d/rc.hil
+++ b/ROMFS/px4fmu_common/init.d/rc.hil
@@ -8,22 +8,12 @@ echo "[HIL] starting.."
uorb start
# Tell MAVLink that this link is "fast"
-mavlink start -b 230400 -d /dev/console
+mavlink start -b 230400 -d /dev/ttyS1
# Create a fake HIL /dev/pwm_output interface
hil mode_pwm
#
-# Load microSD params
-#
-echo "[init] loading microSD params"
-param select /fs/microsd/params
-if [ -f /fs/microsd/params ]
-then
- param load /fs/microsd/params
-fi
-
-#
# Force some key parameters to sane values
# MAV_TYPE 1 = fixed wing, 2 = quadrotor, 13 = hexarotor
# see https://pixhawk.ethz.ch/mavlink/
@@ -38,13 +28,13 @@ commander start
#
# Check if we got an IO
#
-if [ px4io start ]
+if px4io start
then
echo "IO started"
else
fmu mode_serial
echo "FMU started"
-end
+fi
#
# Start the sensors (depends on orb, px4io)
@@ -60,9 +50,7 @@ att_pos_estimator_ekf start
# Load mixer and start controllers (depends on px4io)
#
mixer load /dev/pwm_output /etc/mixers/FMU_AET.mix
-fixedwing_backside start
+fw_pos_control_l1 start
+fw_att_control start
echo "[HIL] setup done, running"
-
-# Exit shell to make it available to MAVLink
-exit
diff --git a/ROMFS/px4fmu_common/init.d/rc.io b/ROMFS/px4fmu_common/init.d/rc.io
new file mode 100644
index 000000000..aaf91b316
--- /dev/null
+++ b/ROMFS/px4fmu_common/init.d/rc.io
@@ -0,0 +1,23 @@
+#
+# Start PX4IO interface (depends on orb, commander)
+#
+if px4io start
+then
+ #
+ # Allow PX4IO to recover from midair restarts.
+ # this is very unlikely, but quite safe and robust.
+ px4io recovery
+
+ #
+ # Disable px4io topic limiting
+ #
+ if [ $BOARD == fmuv1 ]
+ then
+ px4io limit 200
+ else
+ px4io limit 400
+ fi
+else
+ # SOS
+ tone_alarm error
+fi
diff --git a/ROMFS/px4fmu_common/init.d/rc.logging b/ROMFS/px4fmu_common/init.d/rc.logging
index 09c2d00d1..dc4be8055 100644
--- a/ROMFS/px4fmu_common/init.d/rc.logging
+++ b/ROMFS/px4fmu_common/init.d/rc.logging
@@ -5,5 +5,10 @@
if [ -d /fs/microsd ]
then
- sdlog start
+ if [ $BOARD == fmuv1 ]
+ then
+ sdlog2 start -r 50 -a -b 16
+ else
+ sdlog2 start -r 200 -a -b 16
+ fi
fi
diff --git a/ROMFS/px4fmu_common/init.d/rc.multirotor b/ROMFS/px4fmu_common/init.d/rc.multirotor
new file mode 100644
index 000000000..e3638e3d1
--- /dev/null
+++ b/ROMFS/px4fmu_common/init.d/rc.multirotor
@@ -0,0 +1,44 @@
+#!nsh
+#
+# Standard everything needed for multirotors except mixer, output and mavlink
+#
+
+#
+# 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 estimator
+#
+attitude_estimator_ekf start
+
+#
+# Start position estimator
+#
+position_estimator_inav start
+
+#
+# Start attitude control
+#
+multirotor_att_control start
+
+#
+# Start position control
+#
+multirotor_pos_control start
diff --git a/ROMFS/px4fmu_common/init.d/rc.sensors b/ROMFS/px4fmu_common/init.d/rc.sensors
index 5e80ddc2f..2828a108b 100644
--- a/ROMFS/px4fmu_common/init.d/rc.sensors
+++ b/ROMFS/px4fmu_common/init.d/rc.sensors
@@ -7,25 +7,24 @@
# Start sensor drivers here.
#
-#
-# Check for UORB
-#
-if uorb start
-then
- echo "uORB started"
-fi
-
ms5611 start
adc start
+# mag might be external
+if hmc5883 start
+then
+ echo "using HMC5883"
+fi
+
if mpu6000 start
then
- echo "using MPU6000 and HMC5883L"
- hmc5883 start
+ echo "using MPU6000"
+ set BOARD fmuv1
else
echo "using L3GD20 and LSM303D"
l3gd20 start
lsm303d start
+ set BOARD fmuv2
fi
#
@@ -36,8 +35,5 @@ fi
#
if sensors start
then
- #
- # Check sensors - run AFTER 'sensors start'
- #
preflight_check &
fi
diff --git a/ROMFS/px4fmu_common/init.d/rc.usb b/ROMFS/px4fmu_common/init.d/rc.usb
index 5b1bd272e..9264985d6 100644
--- a/ROMFS/px4fmu_common/init.d/rc.usb
+++ b/ROMFS/px4fmu_common/init.d/rc.usb
@@ -8,6 +8,14 @@ echo "Starting MAVLink on this USB console"
# Stop tone alarm
tone_alarm stop
+#
+# Check for UORB
+#
+if uorb start
+then
+ echo "uORB started"
+fi
+
# Tell MAVLink that this link is "fast"
if mavlink stop
then
@@ -16,12 +24,26 @@ fi
sleep 2
mavlink start -b 230400 -d /dev/ttyACM0
+# Stop commander
+if commander stop
+then
+ echo "Commander stopped"
+fi
+sleep 1
+
# Start the commander
if commander start
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 f0ee1a0c6..8c79a035a 100755
--- a/ROMFS/px4fmu_common/init.d/rcS
+++ b/ROMFS/px4fmu_common/init.d/rcS
@@ -20,7 +20,7 @@ then
else
echo "[init] no microSD card found"
# Play SOS
- tone_alarm 2
+ tone_alarm error
fi
#
@@ -57,90 +57,167 @@ fi
if [ $MODE == autostart ]
then
-
-#
-# Start the ORB (first app to start)
-#
-uorb start
-
-#
-# Load microSD params
-#
-if ramtron start
-then
- param select /ramtron/params
- if [ -f /ramtron/params ]
+ #
+ # Start terminal
+ #
+ if sercon
then
- param load /ramtron/params
+ echo "USB connected"
+ sleep 3
+ mavlink start -d /dev/ttyACM0 -b 230400
fi
-else
- param select /fs/microsd/params
- if [ -f /fs/microsd/params ]
+
+ #
+ # Start the ORB (first app to start)
+ #
+ uorb start
+
+ #
+ # Load microSD params
+ #
+ if ramtron start
then
- param load /fs/microsd/params
+ param select /ramtron/params
+ if [ -f /ramtron/params ]
+ then
+ param load /ramtron/params
+ fi
+ else
+ param select /fs/microsd/params
+ if [ -f /fs/microsd/params ]
+ then
+ param load /fs/microsd/params
+ fi
fi
-fi
-
-#
-# Check if PX4IO Firmware should be upgraded (from Andrew Tridgell)
-#
-if [ -f /fs/microsd/px4io.bin ]
-then
- echo "PX4IO Firmware found. Checking Upgrade.."
- if cmp /fs/microsd/px4io.bin /fs/microsd/px4io.cur
+
+ #
+ # Start system state indicator
+ #
+ if rgbled start
then
- echo "No newer version, skipping upgrade."
+ echo "Using external RGB Led"
else
- echo "Loading /fs/microsd/px4io.bin"
- if px4io update /fs/microsd/px4io.bin > /fs/microsd/px4io.log
+ if blinkm start
then
- cp /fs/microsd/px4io.bin /fs/microsd/px4io.cur
- echo "Flashed /fs/microsd/px4io.bin OK" >> /fs/microsd/px4io.log
- else
- echo "Failed flashing /fs/microsd/px4io.bin" >> /fs/microsd/px4io.log
- echo "Failed to upgrade px4io firmware - check if px4io is in bootloader mode"
+ blinkm systemstate
fi
fi
-fi
-#
-# Check if auto-setup from one of the standard scripts is wanted
-# SYS_AUTOSTART = 0 means no autostart (default)
-#
-if param compare SYS_AUTOSTART 1
-then
- sh /etc/init.d/01_fmu_quad_x
-fi
-
-if param compare SYS_AUTOSTART 2
-then
- sh /etc/init.d/02_io_quad_x
-fi
-
-if param compare SYS_AUTOSTART 8
-then
- sh /etc/init.d/08_ardrone
-fi
-
-if param compare SYS_AUTOSTART 9
-then
- sh /etc/init.d/09_ardrone_flow
-fi
+ # Try to get an USB console
+ #nshterm /dev/ttyACM0 &
+
+ #
+ # Upgrade PX4IO firmware
+ #
+ if px4io detect
+ then
+ echo "PX4IO running, not upgrading"
+ else
+ echo "Attempting to upgrade PX4IO"
+ if px4io update
+ then
+ if [ -d /fs/microsd ]
+ then
+ echo "Flashed PX4IO Firmware OK" > /fs/microsd/px4io.log
+ fi
-if param compare SYS_AUTOSTART 10
-then
- sh /etc/init.d/10_io_f330
-fi
+ # Allow IO to safely kick back to app
+ usleep 200000
+ else
+ echo "No PX4IO to upgrade here"
+ fi
+ fi
+
+ #
+ # Check if auto-setup from one of the standard scripts is wanted
+ # SYS_AUTOSTART = 0 means no autostart (default)
+ #
+
+ if param compare SYS_AUTOSTART 8
+ then
+ sh /etc/init.d/08_ardrone
+ set MODE custom
+ fi
+
+ if param compare SYS_AUTOSTART 9
+ then
+ sh /etc/init.d/09_ardrone_flow
+ set MODE custom
+ fi
+
+ if param compare SYS_AUTOSTART 10
+ then
+ sh /etc/init.d/10_dji_f330
+ set MODE custom
+ fi
-if param compare SYS_AUTOSTART 30
-then
- sh /etc/init.d/30_io_camflyer
-fi
+ if param compare SYS_AUTOSTART 11
+ then
+ sh /etc/init.d/11_dji_f450
+ set MODE custom
+ fi
+
+ if param compare SYS_AUTOSTART 15
+ then
+ sh /etc/init.d/15_tbs_discovery
+ set MODE custom
+ fi
-if param compare SYS_AUTOSTART 31
-then
- sh /etc/init.d/31_io_phantom
-fi
+ if param compare SYS_AUTOSTART 16
+ then
+ sh /etc/init.d/16_3dr_iris
+ set MODE custom
+ fi
+
+ if param compare SYS_AUTOSTART 30
+ then
+ sh /etc/init.d/30_io_camflyer
+ set MODE custom
+ fi
+
+ if param compare SYS_AUTOSTART 31
+ then
+ sh /etc/init.d/31_io_phantom
+ set MODE custom
+ fi
+
+ # Start any custom extensions that might be missing
+ if [ -f /fs/microsd/etc/rc.local ]
+ then
+ sh /fs/microsd/etc/rc.local
+ fi
+
+ # If none of the autostart scripts triggered, get a minimal setup
+ if [ $MODE == autostart ]
+ then
+ # Telemetry port is on both FMU boards ttyS1
+ mavlink start -b 57600 -d /dev/ttyS1
+ usleep 5000
+
+ # Start commander
+ commander start
+
+ # Start px4io if present
+ if px4io detect
+ then
+ px4io start
+ else
+ if fmu mode_serial
+ then
+ echo "FMU driver (no PWM) started"
+ fi
+ fi
+
+ # Start sensors
+ sh /etc/init.d/rc.sensors
+
+ # Start one of the estimators
+ attitude_estimator_ekf start
+
+ # Start GPS
+ gps start
+
+ fi
# End of autostart
fi