diff options
author | Lorenz Meier <lm@inf.ethz.ch> | 2013-09-22 14:26:43 +0200 |
---|---|---|
committer | Lorenz Meier <lm@inf.ethz.ch> | 2013-09-22 14:26:43 +0200 |
commit | d717b6f940fdeca062d629c652c7dbcb1a42c62e (patch) | |
tree | 3633a83769fe5bc19efbab569dbb6dbc7bb77b97 /ROMFS | |
parent | 9424728af9ca0c78890845052589a9a5751ff084 (diff) | |
download | px4-firmware-d717b6f940fdeca062d629c652c7dbcb1a42c62e.tar.gz px4-firmware-d717b6f940fdeca062d629c652c7dbcb1a42c62e.tar.bz2 px4-firmware-d717b6f940fdeca062d629c652c7dbcb1a42c62e.zip |
Fixed in-air restart order for fixed wing
Diffstat (limited to 'ROMFS')
-rw-r--r-- | ROMFS/px4fmu_common/init.d/100_mpx_easystar | 14 | ||||
-rw-r--r-- | ROMFS/px4fmu_common/init.d/101_hk_bixler | 12 | ||||
-rw-r--r-- | ROMFS/px4fmu_common/init.d/30_io_camflyer | 12 | ||||
-rw-r--r-- | 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. # @@ -54,11 +57,6 @@ sh /etc/init.d/rc.sensors sh /etc/init.d/rc.logging # -# Start the commander. -# -commander start - -# # Start GPS interface (depends on orb) # gps start 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 @@ -54,11 +57,6 @@ sh /etc/init.d/rc.sensors sh /etc/init.d/rc.logging # -# Start the commander. -# -commander start - -# # Start GPS interface (depends on orb) # gps start 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 @@ -54,11 +57,6 @@ sh /etc/init.d/rc.sensors sh /etc/init.d/rc.logging # -# Start the commander. -# -commander start - -# # Start GPS interface (depends on orb) # gps start 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 @@ -54,11 +57,6 @@ sh /etc/init.d/rc.sensors sh /etc/init.d/rc.logging # -# Start the commander. -# -commander start - -# # Start GPS interface (depends on orb) # gps start |