From fb9e98fb59ebe9db572dcdba6396a9c78021b857 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 7 Sep 2013 12:17:27 +0200 Subject: [PATCH] Cleanup of fixedwing startup code --- ROMFS/px4fmu_common/init.d/100_mpx_easystar | 54 +++++++++----- ROMFS/px4fmu_common/init.d/101_hk_bixler | 82 +++++++++++++++++++++ ROMFS/px4fmu_common/init.d/30_io_camflyer | 63 +++++++++------- ROMFS/px4fmu_common/init.d/31_io_phantom | 54 +++++++++----- ROMFS/px4fmu_common/init.d/rcS | 12 +++ 5 files changed, 198 insertions(+), 67 deletions(-) create mode 100644 ROMFS/px4fmu_common/init.d/101_hk_bixler diff --git a/ROMFS/px4fmu_common/init.d/100_mpx_easystar b/ROMFS/px4fmu_common/init.d/100_mpx_easystar index e1cefdb993..4ed73909e0 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 + 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 commander -# -commander start - -# -# 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 GPS interface +# Start the commander. +# +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 0000000000..b4daa8f5aa --- /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 f7e653362f..c4c4ea3da0 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) -# -px4io start - -# -# Allow PX4IO to recover from midair restarts. -# this is very unlikely, but quite safe and robust. -px4io recovery + +set EXIT_ON_END no # -# Set actuator limit to 100 Hz update (50 Hz PWM) -px4io limit 100 +# 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 (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 e1e6099270..8d4158a182 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 + 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 commander -# -commander start - -# -# 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 GPS interface +# Start the commander. +# +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/rcS b/ROMFS/px4fmu_common/init.d/rcS index 32fb67a454..c2ef375266 100755 --- a/ROMFS/px4fmu_common/init.d/rcS +++ b/ROMFS/px4fmu_common/init.d/rcS @@ -178,6 +178,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 ]