2013-04-26 20:14:32 -03:00
|
|
|
#!nsh
|
2013-08-25 14:27:11 -03:00
|
|
|
|
|
|
|
echo "[init] 08_ardrone: PX4FMU on PX4IOAR carrier board"
|
2013-04-26 20:14:32 -03:00
|
|
|
|
|
|
|
#
|
2013-08-25 14:27:11 -03:00
|
|
|
# Load default params for this platform
|
2013-04-26 20:14:32 -03:00
|
|
|
#
|
2013-08-25 14:27:11 -03:00
|
|
|
if param compare SYS_AUTOCONFIG 1
|
2013-04-26 20:14:32 -03:00
|
|
|
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
|
2013-04-26 20:14:32 -03:00
|
|
|
fi
|
2013-04-18 10:53:25 -03:00
|
|
|
|
2013-04-26 20:14:32 -03:00
|
|
|
#
|
|
|
|
# Force some key parameters to sane values
|
2013-08-25 14:27:11 -03:00
|
|
|
# MAV_TYPE 2 = quadrotor
|
2013-04-26 20:14:32 -03:00
|
|
|
#
|
|
|
|
param set MAV_TYPE 2
|
2013-04-18 10:53:25 -03:00
|
|
|
|
2013-04-26 20:14:32 -03:00
|
|
|
#
|
|
|
|
# Start MAVLink
|
|
|
|
#
|
|
|
|
mavlink start -d /dev/ttyS0 -b 57600
|
|
|
|
usleep 5000
|
2013-08-25 14:27:11 -03:00
|
|
|
|
2013-04-26 20:14:32 -03:00
|
|
|
#
|
2013-08-25 14:27:11 -03:00
|
|
|
# Configure PX4FMU for operation with PX4IOAR
|
2013-04-26 20:14:32 -03:00
|
|
|
#
|
2013-08-25 14:27:11 -03:00
|
|
|
fmu mode_gpio_serial
|
2013-04-26 20:14:32 -03:00
|
|
|
|
|
|
|
#
|
|
|
|
# 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-04-26 20:14:32 -03:00
|
|
|
#
|
2013-08-25 14:27:11 -03:00
|
|
|
sh /etc/init.d/rc.multirotor
|
|
|
|
|
2013-08-22 04:25:13 -03:00
|
|
|
# Exit, because /dev/ttyS0 is needed for MAVLink
|
2013-04-26 23:16:55 -03:00
|
|
|
exit
|