From d717b6f940fdeca062d629c652c7dbcb1a42c62e Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 22 Sep 2013 14:26:43 +0200 Subject: Fixed in-air restart order for fixed wing --- ROMFS/px4fmu_common/init.d/100_mpx_easystar | 14 ++++++-------- ROMFS/px4fmu_common/init.d/101_hk_bixler | 12 +++++------- ROMFS/px4fmu_common/init.d/30_io_camflyer | 12 +++++------- ROMFS/px4fmu_common/init.d/31_io_phantom | 12 +++++------- 4 files changed, 21 insertions(+), 29 deletions(-) diff --git a/ROMFS/px4fmu_common/init.d/100_mpx_easystar b/ROMFS/px4fmu_common/init.d/100_mpx_easystar index 4ed73909e..1a05f5140 100644 --- a/ROMFS/px4fmu_common/init.d/100_mpx_easystar +++ b/ROMFS/px4fmu_common/init.d/100_mpx_easystar @@ -29,7 +29,8 @@ if px4io detect then # Start MAVLink (depends on orb) mavlink start - usleep 5000 + + commander start sh /etc/init.d/rc.io # Limit to 100 Hz updates and (implicit) 50 Hz PWM @@ -37,12 +38,14 @@ then else # Start MAVLink (on UART1 / ttyS0) mavlink start -d /dev/ttyS0 - usleep 5000 + + commander start + fmu mode_pwm param set BAT_V_SCALING 0.004593 set EXIT_ON_END yes fi - + # # Start the sensors and test them. # @@ -53,11 +56,6 @@ sh /etc/init.d/rc.sensors # sh /etc/init.d/rc.logging -# -# Start the commander. -# -commander start - # # Start GPS interface (depends on orb) # diff --git a/ROMFS/px4fmu_common/init.d/101_hk_bixler b/ROMFS/px4fmu_common/init.d/101_hk_bixler index b4daa8f5a..89b3185ad 100644 --- a/ROMFS/px4fmu_common/init.d/101_hk_bixler +++ b/ROMFS/px4fmu_common/init.d/101_hk_bixler @@ -29,7 +29,8 @@ if px4io detect then # Start MAVLink (depends on orb) mavlink start - usleep 5000 + + commander start sh /etc/init.d/rc.io # Limit to 100 Hz updates and (implicit) 50 Hz PWM @@ -37,7 +38,9 @@ then else # Start MAVLink (on UART1 / ttyS0) mavlink start -d /dev/ttyS0 - usleep 5000 + + commander start + fmu mode_pwm param set BAT_V_SCALING 0.004593 set EXIT_ON_END yes @@ -53,11 +56,6 @@ sh /etc/init.d/rc.sensors # sh /etc/init.d/rc.logging -# -# Start the commander. -# -commander start - # # Start GPS interface (depends on orb) # diff --git a/ROMFS/px4fmu_common/init.d/30_io_camflyer b/ROMFS/px4fmu_common/init.d/30_io_camflyer index ff740b6f2..191d8cd95 100644 --- a/ROMFS/px4fmu_common/init.d/30_io_camflyer +++ b/ROMFS/px4fmu_common/init.d/30_io_camflyer @@ -29,7 +29,8 @@ if px4io detect then # Start MAVLink (depends on orb) mavlink start - usleep 5000 + + commander start sh /etc/init.d/rc.io # Limit to 100 Hz updates and (implicit) 50 Hz PWM @@ -37,7 +38,9 @@ then else # Start MAVLink (on UART1 / ttyS0) mavlink start -d /dev/ttyS0 - usleep 5000 + + commander start + fmu mode_pwm param set BAT_V_SCALING 0.004593 set EXIT_ON_END yes @@ -53,11 +56,6 @@ sh /etc/init.d/rc.sensors # sh /etc/init.d/rc.logging -# -# Start the commander. -# -commander start - # # Start GPS interface (depends on orb) # diff --git a/ROMFS/px4fmu_common/init.d/31_io_phantom b/ROMFS/px4fmu_common/init.d/31_io_phantom index 838dcb369..7e0127e79 100644 --- a/ROMFS/px4fmu_common/init.d/31_io_phantom +++ b/ROMFS/px4fmu_common/init.d/31_io_phantom @@ -29,7 +29,8 @@ if px4io detect then # Start MAVLink (depends on orb) mavlink start - usleep 5000 + + commander start sh /etc/init.d/rc.io # Limit to 100 Hz updates and (implicit) 50 Hz PWM @@ -37,7 +38,9 @@ then else # Start MAVLink (on UART1 / ttyS0) mavlink start -d /dev/ttyS0 - usleep 5000 + + commander start + fmu mode_pwm param set BAT_V_SCALING 0.004593 set EXIT_ON_END yes @@ -53,11 +56,6 @@ sh /etc/init.d/rc.sensors # sh /etc/init.d/rc.logging -# -# Start the commander. -# -commander start - # # Start GPS interface (depends on orb) # -- cgit v1.2.3