2013-04-26 20:14:32 -03:00
|
|
|
#!nsh
|
2013-08-25 14:27:11 -03:00
|
|
|
|
2013-08-26 06:53:52 -03:00
|
|
|
echo "[init] 30_io_camflyer: PX4FMU+PX4IO on Camflyer"
|
2013-07-15 08:58:43 -03:00
|
|
|
|
|
|
|
#
|
|
|
|
# Load default params for this platform
|
|
|
|
#
|
|
|
|
if param compare SYS_AUTOCONFIG 1
|
|
|
|
then
|
|
|
|
# Set all params here, then disable autoconfig
|
2013-08-25 14:27:11 -03:00
|
|
|
# TODO
|
|
|
|
|
2013-07-15 08:58:43 -03:00
|
|
|
param set SYS_AUTOCONFIG 0
|
2013-08-28 09:58:29 -03:00
|
|
|
param save
|
2013-07-15 08:58:43 -03:00
|
|
|
fi
|
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 1 = fixed wing
|
2013-04-26 20:14:32 -03:00
|
|
|
#
|
|
|
|
param set MAV_TYPE 1
|
|
|
|
|
|
|
|
#
|
2013-04-18 10:53:25 -03:00
|
|
|
# Start MAVLink (depends on orb)
|
2013-04-26 20:14:32 -03:00
|
|
|
#
|
|
|
|
mavlink start -d /dev/ttyS1 -b 57600
|
|
|
|
usleep 5000
|
|
|
|
|
|
|
|
#
|
2013-04-18 10:53:25 -03:00
|
|
|
# Start the commander (depends on orb, mavlink)
|
2013-04-26 20:14:32 -03:00
|
|
|
#
|
|
|
|
commander start
|
|
|
|
|
|
|
|
#
|
2013-04-18 10:53:25 -03:00
|
|
|
# Start PX4IO interface (depends on orb, commander)
|
2013-04-26 20:14:32 -03:00
|
|
|
#
|
2013-04-18 10:53:25 -03:00
|
|
|
px4io start
|
2013-02-17 13:11:33 -04:00
|
|
|
|
2012-08-04 19:12:36 -03:00
|
|
|
#
|
2013-04-18 10:53:25 -03:00
|
|
|
# Allow PX4IO to recover from midair restarts.
|
|
|
|
# this is very unlikely, but quite safe and robust.
|
|
|
|
px4io recovery
|
2013-07-15 08:58:43 -03:00
|
|
|
|
|
|
|
#
|
|
|
|
# Set actuator limit to 100 Hz update (50 Hz PWM)
|
|
|
|
px4io limit 100
|
2013-04-26 20:14:32 -03:00
|
|
|
|
|
|
|
#
|
2013-04-18 10:53:25 -03:00
|
|
|
# Start the sensors (depends on orb, px4io)
|
2013-04-26 20:14:32 -03:00
|
|
|
#
|
2013-04-18 10:53:25 -03:00
|
|
|
sh /etc/init.d/rc.sensors
|
2013-08-26 06:53:52 -03:00
|
|
|
|
|
|
|
#
|
|
|
|
# Start logging (depends on sensors)
|
|
|
|
#
|
|
|
|
sh /etc/init.d/rc.logging
|
2013-04-26 20:14:32 -03:00
|
|
|
|
|
|
|
#
|
2013-04-18 10:53:25 -03:00
|
|
|
# Start GPS interface (depends on orb)
|
2013-04-26 20:14:32 -03:00
|
|
|
#
|
2013-04-18 10:53:25 -03:00
|
|
|
gps start
|
|
|
|
|
|
|
|
#
|
|
|
|
# Start the attitude estimator (depends on orb)
|
|
|
|
#
|
|
|
|
kalman_demo start
|
2013-04-26 20:14:32 -03:00
|
|
|
|
|
|
|
#
|
2013-04-18 10:53:25 -03:00
|
|
|
# Load mixer and start controllers (depends on px4io)
|
2013-04-26 20:14:32 -03:00
|
|
|
#
|
|
|
|
mixer load /dev/pwm_output /etc/mixers/FMU_Q.mix
|
2013-08-26 06:53:52 -03:00
|
|
|
fw_att_control start
|