px4-firmware/ROMFS/px4fmu_common/init.d/3030_io_camflyer

59 lines
1.1 KiB
Plaintext
Raw Normal View History

#!nsh
2013-08-25 14:27:11 -03:00
2013-09-07 07:17:27 -03:00
echo "[init] PX4FMU v1, v2 with or without IO on Camflyer"
#
# 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
param set SYS_AUTOCONFIG 0
param save
fi
#
# Force some key parameters to sane values
2013-08-25 14:27:11 -03:00
# MAV_TYPE 1 = fixed wing
#
param set MAV_TYPE 1
2013-09-07 07:17:27 -03:00
#
2013-09-07 07:17:27 -03:00
# Start and configure PX4IO or FMU interface
#
2013-09-07 07:17:27 -03:00
if px4io detect
then
# Start MAVLink (depends on orb)
mavlink start
2013-09-07 07:17:27 -03:00
sh /etc/init.d/rc.io
# Limit to 100 Hz updates and (implicit) 50 Hz PWM
px4io limit 100
else
# Start MAVLink (on UART1 / ttyS0)
mavlink start -d /dev/ttyS0
2013-09-07 07:17:27 -03:00
fmu mode_pwm
param set BAT_V_SCALING 0.004593
set EXIT_ON_END yes
fi
#
# Load mixer and start controllers (depends on px4io)
#
if [ -f /fs/microsd/etc/mixers/FMU_Q.mix ]
then
echo "Using /fs/microsd/etc/mixers/FMU_Q.mix"
mixer load /dev/pwm_output /fs/microsd/etc/mixers/FMU_Q.mix
else
echo "Using /etc/mixers/FMU_Q.mix"
mixer load /dev/pwm_output /etc/mixers/FMU_Q.mix
fi
2013-09-07 07:17:27 -03:00
#
2013-11-06 18:41:15 -04:00
# Start common fixedwing apps
#
sh /etc/init.d/rc.fixedwing