px4-firmware/ROMFS/px4fmu_common/init.d/08_ardrone

46 lines
718 B
Plaintext
Raw Normal View History

#!nsh
2013-08-25 14:27:11 -03:00
echo "[init] 08_ardrone: PX4FMU on PX4IOAR carrier board"
#
2013-08-25 14:27:11 -03:00
# Load default params for this platform
#
2013-08-25 14:27:11 -03:00
if param compare SYS_AUTOCONFIG 1
then
2013-08-25 14:27:11 -03:00
# 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
2013-08-25 14:27:11 -03:00
# MAV_TYPE 2 = quadrotor
#
param set MAV_TYPE 2
#
# Start MAVLink
#
mavlink start -d /dev/ttyS0 -b 57600
usleep 5000
2013-08-25 14:27:11 -03:00
#
2013-08-25 14:27:11 -03:00
# Configure PX4FMU for operation with PX4IOAR
#
2013-08-25 14:27:11 -03:00
fmu mode_gpio_serial
#
# Fire up the AR.Drone interface.
#
ardrone_interface start -d /dev/ttyS1
#
2013-08-25 14:27:11 -03:00
# Start common for all multirotors apps
#
2013-08-25 14:27:11 -03:00
sh /etc/init.d/rc.multirotor
# Exit, because /dev/ttyS0 is needed for MAVLink
exit