You can not select more than 25 topics
Topics must start with a letter or number, can include dashes ('-') and can be up to 35 characters long.
80 lines
1.0 KiB
80 lines
1.0 KiB
#!nsh |
|
|
|
# Disable USB and autostart |
|
set USB no |
|
set MODE camflyer |
|
|
|
# |
|
# Start the ORB |
|
# |
|
uorb start |
|
|
|
# |
|
# Load microSD params |
|
# |
|
echo "[init] loading microSD params" |
|
param select /fs/microsd/parameters |
|
if [ -f /fs/microsd/parameters ] |
|
then |
|
param load /fs/microsd/parameters |
|
fi |
|
|
|
# |
|
# Force some key parameters to sane values |
|
# MAV_TYPE 1 = fixed wing, 2 = quadrotor, 13 = hexarotor |
|
# see https://pixhawk.ethz.ch/mavlink/ |
|
# |
|
param set MAV_TYPE 1 |
|
|
|
# |
|
# Start the sensors. |
|
# |
|
sh /etc/init.d/rc.sensors |
|
|
|
# |
|
# Start MAVLink |
|
# |
|
mavlink start -d /dev/ttyS1 -b 57600 |
|
usleep 5000 |
|
|
|
# |
|
# Start the commander. |
|
# |
|
commander start |
|
|
|
# |
|
# Start GPS interface |
|
# |
|
gps start |
|
|
|
# |
|
# Start the attitude estimator |
|
# |
|
kalman_demo start |
|
|
|
# |
|
# Start PX4IO interface |
|
# |
|
px4io start |
|
|
|
# |
|
# Load mixer and start controllers |
|
# |
|
mixer load /dev/pwm_output /etc/mixers/FMU_Q.mix |
|
control_demo start |
|
|
|
# |
|
# Start logging |
|
# |
|
sdlog start -s 10 |
|
|
|
# |
|
# Start system state |
|
# |
|
if blinkm start |
|
then |
|
echo "using BlinkM for state indication" |
|
blinkm systemstate |
|
else |
|
echo "no BlinkM found, OK." |
|
fi
|
|
|