#!nsh echo "[init] 08_ardrone: PX4FMU on PX4IOAR carrier board" # # Load default params for this platform # if param compare SYS_AUTOCONFIG 1 then # Set all params here, then disable autoconfig # TODO param set SYS_AUTOCONFIG 0 param save fi # # Force some key parameters to sane values # MAV_TYPE 2 = quadrotor # param set MAV_TYPE 2 # # Start MAVLink # mavlink start -d /dev/ttyS0 -b 57600 usleep 5000 # # Configure PX4FMU for operation with PX4IOAR # fmu mode_gpio_serial # # Fire up the AR.Drone interface. # ardrone_interface start -d /dev/ttyS1 # # Start common for all multirotors apps # sh /etc/init.d/rc.multirotor # Exit, because /dev/ttyS0 is needed for MAVLink exit