2012-08-04 15:12:36 -07:00
|
|
|
#!nsh
|
|
|
|
|
#
|
|
|
|
|
# Flight startup script for PX4FMU on PX4IOAR carrier board.
|
|
|
|
|
#
|
2012-10-02 13:02:57 +02:00
|
|
|
|
2012-12-09 19:18:42 +01:00
|
|
|
# Disable the USB interface
|
2012-10-02 13:02:57 +02:00
|
|
|
set USB no
|
|
|
|
|
|
2012-12-09 19:18:42 +01:00
|
|
|
# Disable autostarting other apps
|
|
|
|
|
set MODE ardrone
|
|
|
|
|
|
2012-08-04 15:12:36 -07:00
|
|
|
echo "[init] doing PX4IOAR startup..."
|
2012-10-02 13:02:57 +02:00
|
|
|
|
2012-08-04 15:12:36 -07:00
|
|
|
#
|
|
|
|
|
# Start the ORB
|
|
|
|
|
#
|
|
|
|
|
uorb start
|
2012-10-02 13:02:57 +02:00
|
|
|
|
|
|
|
|
#
|
2013-02-17 18:11:33 +01:00
|
|
|
# Init the parameter storage
|
2012-10-02 13:02:57 +02:00
|
|
|
#
|
2012-12-09 19:18:42 +01:00
|
|
|
echo "[init] loading microSD params"
|
|
|
|
|
param select /fs/microsd/parameters
|
|
|
|
|
if [ -f /fs/microsd/parameters ]
|
2012-10-02 13:02:57 +02:00
|
|
|
then
|
2012-12-09 19:18:42 +01:00
|
|
|
param load /fs/microsd/parameters
|
2012-10-02 13:02:57 +02:00
|
|
|
fi
|
|
|
|
|
|
2012-08-04 15:12:36 -07:00
|
|
|
#
|
2013-02-17 18:11:33 +01:00
|
|
|
# Force some key parameters to sane values
|
|
|
|
|
# MAV_TYPE 1 = fixed wing, 2 = quadrotor, 13 = hexarotor
|
|
|
|
|
# see https://pixhawk.ethz.ch/mavlink/
|
2012-08-04 15:12:36 -07:00
|
|
|
#
|
2013-02-17 18:11:33 +01:00
|
|
|
param set MAV_TYPE 2
|
2012-10-02 13:02:57 +02:00
|
|
|
|
2012-12-09 19:18:42 +01:00
|
|
|
#
|
2013-02-17 18:11:33 +01:00
|
|
|
# Start the sensors.
|
2012-12-09 19:18:42 +01:00
|
|
|
#
|
|
|
|
|
sh /etc/init.d/rc.sensors
|
|
|
|
|
|
2013-02-17 18:11:33 +01:00
|
|
|
#
|
|
|
|
|
# Start MAVLink
|
|
|
|
|
#
|
|
|
|
|
mavlink start -d /dev/ttyS0 -b 57600
|
|
|
|
|
usleep 5000
|
|
|
|
|
|
2012-08-04 15:12:36 -07:00
|
|
|
#
|
|
|
|
|
# Start the commander.
|
|
|
|
|
#
|
2012-10-02 13:02:57 +02:00
|
|
|
commander start
|
|
|
|
|
|
2012-08-04 15:12:36 -07:00
|
|
|
#
|
|
|
|
|
# Start the attitude estimator
|
|
|
|
|
#
|
2012-10-02 13:02:57 +02:00
|
|
|
attitude_estimator_ekf start
|
|
|
|
|
|
2012-08-04 15:12:36 -07:00
|
|
|
#
|
|
|
|
|
# Configure PX4FMU for operation with PX4IOAR
|
|
|
|
|
#
|
2012-10-02 13:02:57 +02:00
|
|
|
fmu mode_gpio_serial
|
|
|
|
|
|
2012-08-04 15:12:36 -07:00
|
|
|
#
|
2012-10-02 13:02:57 +02:00
|
|
|
# Fire up the multi rotor attitude controller
|
2012-08-04 15:12:36 -07:00
|
|
|
#
|
2012-10-02 13:02:57 +02:00
|
|
|
multirotor_att_control start
|
|
|
|
|
|
2012-08-04 15:12:36 -07:00
|
|
|
#
|
2012-10-02 13:02:57 +02:00
|
|
|
# Fire up the AR.Drone interface.
|
2012-08-04 15:12:36 -07:00
|
|
|
#
|
2012-12-09 19:18:42 +01:00
|
|
|
ardrone_interface start -d /dev/ttyS1
|
|
|
|
|
|
2013-02-17 18:11:33 +01:00
|
|
|
#
|
|
|
|
|
# Start GPS capture
|
|
|
|
|
#
|
|
|
|
|
gps start
|
|
|
|
|
|
2012-08-04 15:12:36 -07:00
|
|
|
#
|
2012-12-09 19:18:42 +01:00
|
|
|
# Start logging
|
2012-08-04 15:12:36 -07:00
|
|
|
#
|
2013-02-17 18:11:33 +01:00
|
|
|
sdlog start -s 10
|
|
|
|
|
|
2012-08-04 15:12:36 -07:00
|
|
|
#
|
2013-02-17 18:11:33 +01:00
|
|
|
# Start system state
|
2012-08-04 15:12:36 -07:00
|
|
|
#
|
2013-02-17 18:11:33 +01:00
|
|
|
if blinkm start
|
|
|
|
|
then
|
|
|
|
|
echo "using BlinkM for state indication"
|
|
|
|
|
blinkm systemstate
|
|
|
|
|
else
|
|
|
|
|
echo "no BlinkM found, OK."
|
|
|
|
|
fi
|
2012-10-02 13:02:57 +02:00
|
|
|
|
2012-08-04 15:12:36 -07:00
|
|
|
#
|
|
|
|
|
# startup is done; we don't want the shell because we
|
2012-10-02 13:02:57 +02:00
|
|
|
# use the same UART for telemetry
|
2012-08-04 15:12:36 -07:00
|
|
|
#
|
2012-10-02 13:02:57 +02:00
|
|
|
echo "[init] startup done"
|
|
|
|
|
exit
|