Commit 557d3f22 authored by Anton Babushkin's avatar Anton Babushkin
Browse files

Startup scripts major cleanup

parent 41dfdfb1
#!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,11 +30,10 @@ 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
#
......@@ -64,19 +41,24 @@ mavlink start -d /dev/ttyS0 -b 57600
usleep 5000
#
# Start common for all multirotors apps
# Start PWM output
#
sh /etc/init.d/rc.multirotor
fmu mode_pwm
#
# Start PWM output
# Load mixer
#
fmu mode_pwm
mixer load /dev/pwm_output /etc/mixers/FMU_quad_x.mix
#
# Set PWM output frequency
#
pwm -u 400 -m 0xff
# Try to get an USB console
nshterm /dev/ttyACM0 &
#
# Start common for all multirotors apps
#
sh /etc/init.d/rc.multirotor
# Exit, because /dev/ttyS0 is needed for MAVLink
#exit
exit
#!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)
#
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)
#
sh /etc/init.d/rc.sensors
#
# Start GPS interface (depends on orb)
#
gps start
#
# Start the attitude estimator (depends on orb)
# Start and configure PX4IO interface
#
attitude_estimator_ekf start
sh /etc/init.d/rc.io
#
# Load mixer and start controllers (depends on px4io)
# Load mixer
#
mixer load /dev/pwm_output /etc/mixers/FMU_quad_x.mix
pwm -u 400 -m 0xff
multirotor_att_control start
#
# Start logging once armed
# Set PWM output frequency
#
sdlog2 start -r 50 -a -b 14
pwm -u 400 -m 0xff
#
# Start system state
# Start common for all multirotors apps
#
if blinkm start
then
blinkm systemstate
fi
sh /etc/init.d/rc.multirotor
#!nsh
#
# Flight startup script for PX4FMU on PX4IOAR carrier board.
#
echo "[init] doing PX4IOAR startup..."
#
# Start the ORB
#
uorb start
echo "[init] 08_ardrone: PX4FMU on PX4IOAR carrier board"
#
# Load microSD params
# Load default params for this platform
#
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
#
mavlink start -d /dev/ttyS0 -b 57600
usleep 5000
#
# Start the commander.
#
commander start
#
# Start the attitude estimator
#
attitude_estimator_ekf start
#
# Fire up the multi rotor attitude controller
# Configure PX4FMU for operation with PX4IOAR
#
multirotor_att_control start
fmu mode_gpio_serial
#
# Fire up the AR.Drone interface.
#
ardrone_interface start -d /dev/ttyS1
#
# Start logging once armed
#
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
# Start common for all multirotors apps
#
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
#!nsh
echo "[init] 09_ardrone_flow: PX4FMU on PX4IOAR carrier board with PX4FLOW"
#
# Flight startup script for PX4FMU on PX4IOAR carrier board.
#
echo "[init] doing PX4IOAR startup..."
#
# Start the ORB
#
uorb start
#
# Load microSD params
# Load default params for this platform
#
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.
#
......@@ -73,25 +71,6 @@ flow_position_control start
# Fire up the flow speed controller
#
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
#!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)
# Set PWM values for DJI ESCs
#
if px4io start
then
#
# This sets a PWM right after startup (regardless of safety button)
#
px4io idle 900 900 900 900
pwm -u 400 -m 0xff
#
# Allow PX4IO to recover from midair restarts.
# this is very unlikely, but quite safe and robust.
px4io recovery
#
# 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
px4io idle 900 900 900 900
px4io min 1200 1200 1200 1200
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)
# Load mixer
#
gps start
mixer load /dev/pwm_output /etc/mixers/FMU_quad_x.mix
#
# Start the attitude estimator (depends on orb)
# Set PWM output frequency
#
attitude_estimator_ekf start
multirotor_att_control start
pwm -u 400 -m 0xff
#
# Disable px4io topic limiting and start logging
# Start common for all multirotors apps
#
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
#!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
......@@ -47,11 +26,10 @@ then
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
......@@ -62,77 +40,28 @@ mavlink start
usleep 5000
#
# Start the commander (depends on orb, mavlink)
#
commander start
#
# Start PX4IO interface (depends on orb, commander)
#
px4io start
pwm -u 400 -m 0xff
# Start and configure PX4IO interface
#
# Allow PX4IO to recover from midair restarts.
# This is very unlikely, but quite safe and robust.
px4io recovery
sh /etc/init.d/rc.io
#
# 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
#
# Load the mixer for a quad with wide arms
#
mixer load /dev/pwm_output /etc/mixers/FMU_quad_w.mix
#
# 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
#
# Start the controllers (depends on orb)
# Set PWM output frequency
#
multirotor_att_control start
pwm -u 400 -m 0xff
#
# Disable px4io topic limiting and start logging
# Start common for all multirotors apps
#
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
#!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