|
|
|
#!nsh
|
|
|
|
#
|
|
|
|
# Flight startup script for PX4FMU on PX4IOAR carrier board.
|
|
|
|
#
|
|
|
|
|
|
|
|
echo "[init] doing PX4IOAR 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
|
|
|
|
|
|
|
|
#
|
|
|
|
# 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 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
|
|
|
|
#
|
|
|
|
multirotor_att_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
|
|
|
|
|
|
|
|
#
|
|
|
|
# Start GPS capture
|
|
|
|
#
|
|
|
|
gps start
|
|
|
|
|
|
|
|
#
|
|
|
|
# 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
|