forked from Archive/PX4-Autopilot
76 lines
1.0 KiB
Plaintext
76 lines
1.0 KiB
Plaintext
#!nsh
|
|
#
|
|
# USB MAVLink start
|
|
#
|
|
|
|
echo "Starting MAVLink on this USB console"
|
|
|
|
# Stop tone alarm
|
|
tone_alarm stop
|
|
|
|
# Tell MAVLink that this link is "fast"
|
|
if mavlink stop
|
|
then
|
|
echo "stopped other MAVLink instance"
|
|
fi
|
|
sleep 2
|
|
mavlink start -b 230400 -d /dev/ttyACM0
|
|
|
|
# Stop commander
|
|
if commander stop
|
|
then
|
|
echo "Commander stopped"
|
|
fi
|
|
sleep 1
|
|
|
|
# Start the commander
|
|
if commander start
|
|
then
|
|
echo "Commander started"
|
|
fi
|
|
|
|
# Stop px4io
|
|
if px4io stop
|
|
then
|
|
echo "PX4IO stopped"
|
|
fi
|
|
sleep 1
|
|
|
|
# Start px4io if present
|
|
if px4io start
|
|
then
|
|
echo "PX4IO driver started"
|
|
else
|
|
if fmu mode_serial
|
|
then
|
|
echo "FMU driver started"
|
|
fi
|
|
fi
|
|
|
|
# Start sensors
|
|
sh /etc/init.d/rc.sensors
|
|
|
|
# Start one of the estimators
|
|
if attitude_estimator_ekf status
|
|
then
|
|
echo "multicopter att filter running"
|
|
else
|
|
if att_pos_estimator_ekf status
|
|
then
|
|
echo "fixedwing att filter running"
|
|
else
|
|
attitude_estimator_ekf start
|
|
fi
|
|
fi
|
|
|
|
# Start GPS
|
|
if gps start
|
|
then
|
|
echo "GPS started"
|
|
fi
|
|
|
|
echo "MAVLink started, exiting shell.."
|
|
|
|
# Exit shell to make it available to MAVLink
|
|
exit
|