forked from Archive/PX4-Autopilot
Fixed in-air restart order for fixed wing
This commit is contained in:
parent
9424728af9
commit
d717b6f940
|
@ -29,7 +29,8 @@ if px4io detect
|
||||||
then
|
then
|
||||||
# Start MAVLink (depends on orb)
|
# Start MAVLink (depends on orb)
|
||||||
mavlink start
|
mavlink start
|
||||||
usleep 5000
|
|
||||||
|
commander start
|
||||||
|
|
||||||
sh /etc/init.d/rc.io
|
sh /etc/init.d/rc.io
|
||||||
# Limit to 100 Hz updates and (implicit) 50 Hz PWM
|
# Limit to 100 Hz updates and (implicit) 50 Hz PWM
|
||||||
|
@ -37,12 +38,14 @@ then
|
||||||
else
|
else
|
||||||
# Start MAVLink (on UART1 / ttyS0)
|
# Start MAVLink (on UART1 / ttyS0)
|
||||||
mavlink start -d /dev/ttyS0
|
mavlink start -d /dev/ttyS0
|
||||||
usleep 5000
|
|
||||||
|
commander start
|
||||||
|
|
||||||
fmu mode_pwm
|
fmu mode_pwm
|
||||||
param set BAT_V_SCALING 0.004593
|
param set BAT_V_SCALING 0.004593
|
||||||
set EXIT_ON_END yes
|
set EXIT_ON_END yes
|
||||||
fi
|
fi
|
||||||
|
|
||||||
#
|
#
|
||||||
# Start the sensors and test them.
|
# Start the sensors and test them.
|
||||||
#
|
#
|
||||||
|
@ -53,11 +56,6 @@ sh /etc/init.d/rc.sensors
|
||||||
#
|
#
|
||||||
sh /etc/init.d/rc.logging
|
sh /etc/init.d/rc.logging
|
||||||
|
|
||||||
#
|
|
||||||
# Start the commander.
|
|
||||||
#
|
|
||||||
commander start
|
|
||||||
|
|
||||||
#
|
#
|
||||||
# Start GPS interface (depends on orb)
|
# Start GPS interface (depends on orb)
|
||||||
#
|
#
|
||||||
|
|
|
@ -29,7 +29,8 @@ if px4io detect
|
||||||
then
|
then
|
||||||
# Start MAVLink (depends on orb)
|
# Start MAVLink (depends on orb)
|
||||||
mavlink start
|
mavlink start
|
||||||
usleep 5000
|
|
||||||
|
commander start
|
||||||
|
|
||||||
sh /etc/init.d/rc.io
|
sh /etc/init.d/rc.io
|
||||||
# Limit to 100 Hz updates and (implicit) 50 Hz PWM
|
# Limit to 100 Hz updates and (implicit) 50 Hz PWM
|
||||||
|
@ -37,7 +38,9 @@ then
|
||||||
else
|
else
|
||||||
# Start MAVLink (on UART1 / ttyS0)
|
# Start MAVLink (on UART1 / ttyS0)
|
||||||
mavlink start -d /dev/ttyS0
|
mavlink start -d /dev/ttyS0
|
||||||
usleep 5000
|
|
||||||
|
commander start
|
||||||
|
|
||||||
fmu mode_pwm
|
fmu mode_pwm
|
||||||
param set BAT_V_SCALING 0.004593
|
param set BAT_V_SCALING 0.004593
|
||||||
set EXIT_ON_END yes
|
set EXIT_ON_END yes
|
||||||
|
@ -53,11 +56,6 @@ sh /etc/init.d/rc.sensors
|
||||||
#
|
#
|
||||||
sh /etc/init.d/rc.logging
|
sh /etc/init.d/rc.logging
|
||||||
|
|
||||||
#
|
|
||||||
# Start the commander.
|
|
||||||
#
|
|
||||||
commander start
|
|
||||||
|
|
||||||
#
|
#
|
||||||
# Start GPS interface (depends on orb)
|
# Start GPS interface (depends on orb)
|
||||||
#
|
#
|
||||||
|
|
|
@ -29,7 +29,8 @@ if px4io detect
|
||||||
then
|
then
|
||||||
# Start MAVLink (depends on orb)
|
# Start MAVLink (depends on orb)
|
||||||
mavlink start
|
mavlink start
|
||||||
usleep 5000
|
|
||||||
|
commander start
|
||||||
|
|
||||||
sh /etc/init.d/rc.io
|
sh /etc/init.d/rc.io
|
||||||
# Limit to 100 Hz updates and (implicit) 50 Hz PWM
|
# Limit to 100 Hz updates and (implicit) 50 Hz PWM
|
||||||
|
@ -37,7 +38,9 @@ then
|
||||||
else
|
else
|
||||||
# Start MAVLink (on UART1 / ttyS0)
|
# Start MAVLink (on UART1 / ttyS0)
|
||||||
mavlink start -d /dev/ttyS0
|
mavlink start -d /dev/ttyS0
|
||||||
usleep 5000
|
|
||||||
|
commander start
|
||||||
|
|
||||||
fmu mode_pwm
|
fmu mode_pwm
|
||||||
param set BAT_V_SCALING 0.004593
|
param set BAT_V_SCALING 0.004593
|
||||||
set EXIT_ON_END yes
|
set EXIT_ON_END yes
|
||||||
|
@ -53,11 +56,6 @@ sh /etc/init.d/rc.sensors
|
||||||
#
|
#
|
||||||
sh /etc/init.d/rc.logging
|
sh /etc/init.d/rc.logging
|
||||||
|
|
||||||
#
|
|
||||||
# Start the commander.
|
|
||||||
#
|
|
||||||
commander start
|
|
||||||
|
|
||||||
#
|
#
|
||||||
# Start GPS interface (depends on orb)
|
# Start GPS interface (depends on orb)
|
||||||
#
|
#
|
||||||
|
|
|
@ -29,7 +29,8 @@ if px4io detect
|
||||||
then
|
then
|
||||||
# Start MAVLink (depends on orb)
|
# Start MAVLink (depends on orb)
|
||||||
mavlink start
|
mavlink start
|
||||||
usleep 5000
|
|
||||||
|
commander start
|
||||||
|
|
||||||
sh /etc/init.d/rc.io
|
sh /etc/init.d/rc.io
|
||||||
# Limit to 100 Hz updates and (implicit) 50 Hz PWM
|
# Limit to 100 Hz updates and (implicit) 50 Hz PWM
|
||||||
|
@ -37,7 +38,9 @@ then
|
||||||
else
|
else
|
||||||
# Start MAVLink (on UART1 / ttyS0)
|
# Start MAVLink (on UART1 / ttyS0)
|
||||||
mavlink start -d /dev/ttyS0
|
mavlink start -d /dev/ttyS0
|
||||||
usleep 5000
|
|
||||||
|
commander start
|
||||||
|
|
||||||
fmu mode_pwm
|
fmu mode_pwm
|
||||||
param set BAT_V_SCALING 0.004593
|
param set BAT_V_SCALING 0.004593
|
||||||
set EXIT_ON_END yes
|
set EXIT_ON_END yes
|
||||||
|
@ -53,11 +56,6 @@ sh /etc/init.d/rc.sensors
|
||||||
#
|
#
|
||||||
sh /etc/init.d/rc.logging
|
sh /etc/init.d/rc.logging
|
||||||
|
|
||||||
#
|
|
||||||
# Start the commander.
|
|
||||||
#
|
|
||||||
commander start
|
|
||||||
|
|
||||||
#
|
#
|
||||||
# Start GPS interface (depends on orb)
|
# Start GPS interface (depends on orb)
|
||||||
#
|
#
|
||||||
|
|
Loading…
Reference in New Issue