14 changed files with 315 additions and 780 deletions
@ -1,86 +1,45 @@
@@ -1,86 +1,45 @@
|
||||
#!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 |
||||
|
@ -0,0 +1,23 @@
@@ -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 |
Loading…
Reference in new issue