Startup scripts major cleanup

This commit is contained in:
Anton Babushkin 2013-08-25 19:27:11 +02:00
parent 41dfdfb1a4
commit 557d3f22de
14 changed files with 338 additions and 803 deletions

View File

@ -1,28 +1,6 @@
#!nsh
#
# Flight startup script for PX4FMU with PWM outputs.
#
# disable USB and autostart
set USB no
set MODE custom
echo "[init] doing PX4FMU Quad startup..."
#
# Start the ORB
#
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] 01_fmu_quad_x: PX4FMU Quad X with PWM outputs"
#
# Load default params for this platform
@ -52,8 +30,7 @@ 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
@ -63,20 +40,25 @@ param set MAV_TYPE 2
mavlink start -d /dev/ttyS0 -b 57600
usleep 5000
#
# Start PWM output
#
fmu mode_pwm
#
# Load mixer
#
mixer load /dev/pwm_output /etc/mixers/FMU_quad_x.mix
#
# Set PWM output frequency
#
pwm -u 400 -m 0xff
#
# Start common for all multirotors apps
#
sh /etc/init.d/rc.multirotor
#
# Start PWM output
#
fmu mode_pwm
mixer load /dev/pwm_output /etc/mixers/FMU_quad_x.mix
pwm -u 400 -m 0xff
# Try to get an USB console
nshterm /dev/ttyACM0 &
# Exit, because /dev/ttyS0 is needed for MAVLink
#exit
exit

View File

@ -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)
# Start and configure PX4IO interface
#
commander start
sh /etc/init.d/rc.io
#
# 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)
#
attitude_estimator_ekf start
#
# Load mixer and start controllers (depends on px4io)
# Load mixer
#
mixer load /dev/pwm_output /etc/mixers/FMU_quad_x.mix
#
# Set PWM output frequency
#
pwm -u 400 -m 0xff
multirotor_att_control start
#
# Start logging once armed
# Start common for all multirotors apps
#
sdlog2 start -r 50 -a -b 14
#
# Start system state
#
if blinkm start
then
blinkm systemstate
fi
sh /etc/init.d/rc.multirotor

View File

@ -1,42 +1,25 @@
#!nsh
#
# Flight startup script for PX4FMU on PX4IOAR carrier board.
#
echo "[init] doing PX4IOAR startup..."
echo "[init] 08_ardrone: PX4FMU on PX4IOAR carrier board"
#
# Start the ORB
# Load default params for this platform
#
uorb start
#
# Load microSD params
#
echo "[init] loading microSD params"
param select /fs/microsd/params
if [ -f /fs/microsd/params ]
if param compare SYS_AUTOCONFIG 1
then
param load /fs/microsd/params
# 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
#
# Configure PX4FMU for operation with PX4IOAR
#
fmu mode_gpio_serial
#
# Start the sensors.
#
sh /etc/init.d/rc.sensors
#
# Start MAVLink
#
@ -44,19 +27,9 @@ mavlink start -d /dev/ttyS0 -b 57600
usleep 5000
#
# Start the commander.
# Configure PX4FMU for operation with PX4IOAR
#
commander start
#
# Start the attitude estimator
#
attitude_estimator_ekf start
#
# Fire up the multi rotor attitude controller
#
multirotor_att_control start
fmu mode_gpio_serial
#
# Fire up the AR.Drone interface.
@ -64,23 +37,9 @@ multirotor_att_control start
ardrone_interface start -d /dev/ttyS1
#
# Start logging once armed
# Start common for all multirotors apps
#
sdlog2 start -r 50 -a -b 14
#
# Start GPS capture
#
gps start
#
# startup is done; we don't want the shell because we
# use the same UART for telemetry
#
echo "[init] startup done"
# Try to get an USB console
nshterm /dev/ttyACM0 &
sh /etc/init.d/rc.multirotor
# Exit, because /dev/ttyS0 is needed for MAVLink
exit

View File

@ -1,49 +1,47 @@
#!nsh
#
# Flight startup script for PX4FMU on PX4IOAR carrier board.
#
echo "[init] doing PX4IOAR startup..."
echo "[init] 09_ardrone_flow: PX4FMU on PX4IOAR carrier board with PX4FLOW"
#
# Start the ORB
# Load default params for this platform
#
uorb start
#
# Load microSD params
#
echo "[init] loading microSD params"
param select /fs/microsd/params
if [ -f /fs/microsd/params ]
if param compare SYS_AUTOCONFIG 1
then
param load /fs/microsd/params
# 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 and MAVLink Onboard (PX4FLOW Sensor)
#
mavlink start -d /dev/ttyS0 -b 57600
mavlink_onboard start -d /dev/ttyS3 -b 115200
usleep 5000
#
# Configure PX4FMU for operation with PX4IOAR
#
fmu mode_gpio_serial
#
# Fire up the AR.Drone interface.
#
ardrone_interface start -d /dev/ttyS1
#
# Start the sensors.
#
sh /etc/init.d/rc.sensors
#
# Start MAVLink and MAVLink Onboard (Flow Sensor)
#
mavlink start -d /dev/ttyS0 -b 57600
mavlink_onboard start -d /dev/ttyS3 -b 115200
usleep 5000
#
# Start the commander.
#
@ -74,24 +72,5 @@ flow_position_control start
#
flow_speed_control start
#
# Fire up the AR.Drone interface.
#
ardrone_interface start -d /dev/ttyS1
#
# Start logging once armed
#
sdlog2 start -r 50 -a -b 14
#
# startup is done; we don't want the shell because we
# use the same UART for telemetry
#
echo "[init] startup done"
# Try to get an USB console
nshterm /dev/ttyACM0 &
# Exit, because /dev/ttyS0 is needed for MAVLink
exit

View File

@ -1,12 +1,6 @@
#!nsh
#
# Flight startup script for PX4FMU+PX4IO on an F330 quad.
#
#
# Start the ORB (first app to start)
#
uorb start
echo "[init] 10_io_f330: PX4FMU+PX4IO on a DJI F330 quad frame"
#
# Load default params for this platform
@ -35,8 +29,7 @@ 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
@ -47,71 +40,28 @@ mavlink start
usleep 5000
#
# Start the commander (depends on orb, mavlink)
# Start and configure PX4IO interface
#
commander start
sh /etc/init.d/rc.io
#
# Start PX4IO interface (depends on orb, commander)
#
if px4io start
then
#
# This sets a PWM right after startup (regardless of safety button)
# Set PWM values for DJI ESCs
#
px4io idle 900 900 900 900
px4io min 1200 1200 1200 1200
px4io max 1800 1800 1800 1800
#
# Load mixer
#
mixer load /dev/pwm_output /etc/mixers/FMU_quad_x.mix
#
# Set PWM output frequency
#
pwm -u 400 -m 0xff
#
# Allow PX4IO to recover from midair restarts.
# this is very unlikely, but quite safe and robust.
px4io recovery
# Start common for all multirotors apps
#
# The values are for spinning motors when armed using DJI ESCs
#
px4io min 1200 1200 1200 1200
#
# Upper limits could be higher, this is on the safe side
#
px4io max 1800 1800 1800 1800
mixer load /dev/pwm_output /etc/mixers/FMU_quad_x.mix
else
# SOS
tone_alarm 6
fi
#
# 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)
#
attitude_estimator_ekf start
multirotor_att_control start
#
# Disable px4io topic limiting and start logging
#
if [ $BOARD == fmuv1 ]
then
px4io limit 200
sdlog2 start -r 50 -a -b 16
else
px4io limit 400
sdlog2 start -r 200 -a -b 16
fi
sh /etc/init.d/rc.multirotor

View File

@ -1,27 +1,6 @@
#!nsh
#
# Flight startup script for PX4FMU+PX4IO on a Team Blacksheep Discovery quad
# with stock DJI ESCs, motors and props.
#
# 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] 15_io_tbs: PX4FMU+PX4IO on a Team Blacksheep Discovery quad"
#
# Load default params for this platform
@ -50,8 +29,7 @@ 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
@ -62,34 +40,15 @@ mavlink start
usleep 5000
#
# Start the commander (depends on orb, mavlink)
# Start and configure PX4IO interface
#
commander start
sh /etc/init.d/rc.io
#
# Start PX4IO interface (depends on orb, commander)
#
px4io start
pwm -u 400 -m 0xff
#
# Allow PX4IO to recover from midair restarts.
# This is very unlikely, but quite safe and robust.
px4io recovery
#
# This sets a PWM right after startup (regardless of safety button)
# Set PWM values for DJI ESCs
#
px4io idle 900 900 900 900
#
# The values are for spinning motors when armed using DJI ESCs
#
px4io min 1180 1180 1180 1180
#
# Upper limits could be higher, this is on the safe side
#
px4io max 1800 1800 1800 1800
#
@ -98,41 +57,11 @@ px4io max 1800 1800 1800 1800
mixer load /dev/pwm_output /etc/mixers/FMU_quad_w.mix
#
# Start the sensors (depends on orb, px4io)
# Set PWM output frequency
#
sh /etc/init.d/rc.sensors
pwm -u 400 -m 0xff
#
# Start GPS interface (depends on orb)
# Start common for all multirotors apps
#
gps start
#
# Start the attitude estimator (depends on orb)
#
attitude_estimator_ekf start
#
# Start the controllers (depends on orb)
#
multirotor_att_control start
#
# Disable px4io topic limiting and start logging
#
if [ $BOARD == fmuv1 ]
then
px4io limit 200
sdlog2 start -r 50 -a -b 16
if blinkm start
then
blinkm systemstate
fi
else
px4io limit 400
sdlog2 start -r 200 -a -b 16
if rgbled start
then
#rgbled systemstate
fi
fi
sh /etc/init.d/rc.multirotor

View File

@ -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
cho "[init] 30_io_camflyer: PX4FMU+PX4IO on Camflyer"
#
# Load default params for this platform
@ -28,39 +8,18 @@ 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 1 = fixed wing
#
param set MAV_TYPE 1
#
# Check if PX4IO Firmware should be upgraded (from Andrew Tridgell)
#
if [ -f /fs/microsd/px4io.bin ]
then
echo "PX4IO Firmware found. Checking Upgrade.."
if cmp /fs/microsd/px4io.bin /fs/microsd/px4io.bin.current
then
echo "No newer version, skipping upgrade."
else
echo "Loading /fs/microsd/px4io.bin"
if px4io update /fs/microsd/px4io.bin > /fs/microsd/px4io_update.log
then
cp /fs/microsd/px4io.bin /fs/microsd/px4io.bin.current
echo "Flashed /fs/microsd/px4io.bin OK" >> /fs/microsd/px4io_update.log
else
echo "Failed flashing /fs/microsd/px4io.bin" >> /fs/microsd/px4io_update.log
echo "Failed to upgrade PX4IO firmware - check if PX4IO is in bootloader mode"
fi
fi
fi
#
# Start MAVLink (depends on orb)
#
@ -106,16 +65,3 @@ kalman_demo start
#
mixer load /dev/pwm_output /etc/mixers/FMU_Q.mix
control_demo start
#
# Start logging
#
sdlog2 start -r 50 -a -b 14
#
# Start system state
#
if blinkm start
then
blinkm systemstate
fi

View File

@ -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] 31_io_phantom: PX4FMU+PX4IO on Phantom"
#
# Load default params for this platform
@ -28,39 +8,18 @@ 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 1 = fixed wing
#
param set MAV_TYPE 1
#
# Check if PX4IO Firmware should be upgraded (from Andrew Tridgell)
#
if [ -f /fs/microsd/px4io.bin ]
then
echo "PX4IO Firmware found. Checking Upgrade.."
if cmp /fs/microsd/px4io.bin /fs/microsd/px4io.bin.current
then
echo "No newer version, skipping upgrade."
else
echo "Loading /fs/microsd/px4io.bin"
if px4io update /fs/microsd/px4io.bin > /fs/microsd/px4io_update.log
then
cp /fs/microsd/px4io.bin /fs/microsd/px4io.bin.current
echo "Flashed /fs/microsd/px4io.bin OK" >> /fs/microsd/px4io_update.log
else
echo "Failed flashing /fs/microsd/px4io.bin" >> /fs/microsd/px4io_update.log
echo "Failed to upgrade PX4IO firmware - check if PX4IO is in bootloader mode"
fi
fi
fi
#
# Start MAVLink (depends on orb)
#
@ -68,36 +27,31 @@ mavlink start -d /dev/ttyS1 -b 57600
usleep 5000
#
# Start the commander (depends on orb, mavlink)
# Start and configure PX4IO interface
#
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
sh /etc/init.d/rc.io
#
# Set actuator limit to 100 Hz update (50 Hz PWM)
px4io limit 100
#
# Start the sensors (depends on orb, px4io)
# Start the commander
#
commander start
#
# Start the sensors
#
sh /etc/init.d/rc.sensors
#
# Start GPS interface (depends on orb)
# Start GPS interface
#
gps start
#
# Start the attitude estimator (depends on orb)
# Start the attitude estimator
#
kalman_demo start
@ -106,16 +60,3 @@ kalman_demo start
#
mixer load /dev/pwm_output /etc/mixers/FMU_Q.mix
control_demo start
#
# Start logging
#
sdlog2 start -r 50 -a -b 14
#
# Start system state
#
if blinkm start
then
blinkm systemstate
fi

View File

@ -1,26 +1,4 @@
#!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
#
# Load default params for this platform
@ -28,65 +6,34 @@ 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 10 = ground rover
#
param set MAV_TYPE 10
#
# Check if PX4IO Firmware should be upgraded (from Andrew Tridgell)
#
if [ -f /fs/microsd/px4io.bin ]
then
echo "PX4IO Firmware found. Checking Upgrade.."
if cmp /fs/microsd/px4io.bin /fs/microsd/px4io.bin.current
then
echo "No newer version, skipping upgrade."
else
echo "Loading /fs/microsd/px4io.bin"
if px4io update /fs/microsd/px4io.bin > /fs/microsd/px4io_update.log
then
cp /fs/microsd/px4io.bin /fs/microsd/px4io.bin.current
echo "Flashed /fs/microsd/px4io.bin OK" >> /fs/microsd/px4io_update.log
else
echo "Failed flashing /fs/microsd/px4io.bin" >> /fs/microsd/px4io_update.log
echo "Failed to upgrade PX4IO firmware - check if PX4IO is in bootloader mode"
fi
fi
fi
#
# Start MAVLink (depends on orb)
#
mavlink start -d /dev/ttyS1 -b 57600
usleep 5000
#
# Start and configure PX4IO interface
#
sh /etc/init.d/rc.io
#
# 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)
#
@ -107,16 +54,3 @@ attitude_estimator_ekf start
#
md25 start 3 0x58
segway start
#
# Start logging
#
sdlog2 start -r 50 -a -b 14
#
# Start system state
#
if blinkm start
then
blinkm systemstate
fi

View File

@ -1,28 +1,6 @@
#!nsh
#
# Flight startup script for PX4FMU with PWM outputs.
#
# disable USB and autostart
set USB no
set MODE custom
echo "[init] doing PX4FMU Quad startup 666_fmu_quad_X550..."
#
# Start the ORB
#
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] 666_fmu_q_x550: PX4FMU Quad X550 with PWM outputs"
#
# Load default params for this platform
@ -52,8 +30,7 @@ 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
@ -64,53 +41,24 @@ mavlink start -d /dev/ttyS0 -b 57600
usleep 5000
#
# Start the sensors and test them.
# Start PWM output
#
sh /etc/init.d/rc.sensors
#
# Start the commander.
#
commander start
#
# Start GPS interface (depends on orb)
#
gps start
#
# Start the attitude estimator
#
attitude_estimator_ekf start
#
# Start the position estimator
#
position_estimator_inav start
echo "[init] starting PWM output"
fmu mode_pwm
#
# Load mixer
#
mixer load /dev/pwm_output /etc/mixers/FMU_quad_x.mix
#
# Set PWM output frequency
#
pwm -u 400 -m 0xff
#
# Start attitude control
# Start common for all multirotors apps
#
multirotor_att_control start
sh /etc/init.d/rc.multirotor
#
# Start position control
#
multirotor_pos_control start
#
# Start logging
#
sdlog2 start -r 50 -a -b 14
#
# Start system state
#
if blinkm start
then
blinkm systemstate
fi
# Exit, because /dev/ttyS0 is needed for MAVLink
exit

View File

@ -0,0 +1,23 @@
#
# Start PX4IO interface (depends on orb, commander)
#
if px4io start
then
#
# Allow PX4IO to recover from midair restarts.
# this is very unlikely, but quite safe and robust.
px4io recovery
#
# Disable px4io topic limiting
#
if [ $BOARD == fmuv1 ]
then
px4io limit 200
else
px4io limit 400
fi
else
# SOS
tone_alarm 6
fi

View File

@ -5,5 +5,10 @@
if [ -d /fs/microsd ]
then
sdlog start
if [ $BOARD == fmuv1 ]
then
sdlog2 start -r 50 -a -b 16
else
sdlog2 start -r 200 -a -b 16
fi
fi

View File

@ -37,13 +37,3 @@ multirotor_att_control start
# Start position control
#
multirotor_pos_control start
#
# Start logging
#
if [ $BOARD == fmuv1 ]
then
sdlog2 start -r 50 -a -b 16
else
sdlog2 start -r 200 -a -b 16
fi

View File

@ -57,7 +57,6 @@ fi
if [ $MODE == autostart ]
then
#
# Start terminal
#
@ -105,6 +104,11 @@ else
fi
fi
#
# Start logging
#
sh /etc/init.d/rc.logging
#
# Check if PX4IO Firmware should be upgraded (from Andrew Tridgell)
#
@ -213,6 +217,5 @@ then
gps start
fi
# End of autostart
fi