aboutsummaryrefslogtreecommitdiff
path: root/ROMFS/px4fmu_common/init.d/02_io_quad_x
diff options
context:
space:
mode:
Diffstat (limited to 'ROMFS/px4fmu_common/init.d/02_io_quad_x')
-rw-r--r--ROMFS/px4fmu_common/init.d/02_io_quad_x88
1 files changed, 17 insertions, 71 deletions
diff --git a/ROMFS/px4fmu_common/init.d/02_io_quad_x b/ROMFS/px4fmu_common/init.d/02_io_quad_x
index c63e92f6d..a37c26ad1 100644
--- a/ROMFS/px4fmu_common/init.d/02_io_quad_x
+++ b/ROMFS/px4fmu_common/init.d/02_io_quad_x
@@ -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] 02_io_quad_x: PX4FMU+PX4IO Quad X with PWM outputs"
#
# Load default params for this platform
@@ -28,74 +8,40 @@ 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
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 (depends on orb)
+# Start MAVLink
#
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)
+# Start and configure PX4IO interface
#
-attitude_estimator_ekf start
-
+sh /etc/init.d/rc.io
+
#
-# Load mixer and start controllers (depends on px4io)
+# Load mixer
#
mixer load /dev/pwm_output /etc/mixers/FMU_quad_x.mix
-pwm -u 400 -m 0xff
-multirotor_att_control start
-
+
#
-# Start logging
+# Set PWM output frequency
#
-sdlog2 start -r 50 -a -b 14
-
+pwm -u 400 -m 0xff
+
#
-# Start system state
+# Start common for all multirotors apps
#
-if blinkm start
-then
- blinkm systemstate
-fi
+sh /etc/init.d/rc.multirotor