px4-firmware/ROMFS/px4fmu_common/init.d/10_dji_f330

78 lines
1.4 KiB
Plaintext
Raw Normal View History

#!nsh
echo "[init] PX4FMU v1, v2 with or without IO on DJI F330"
2013-08-19 17:58:50 -03:00
#
# Load default params for this platform
#
if param compare SYS_AUTOCONFIG 1
then
# Set all params here, then disable autoconfig
param set SYS_AUTOCONFIG 0
param set MC_ATTRATE_D 0.004
param set MC_ATTRATE_I 0.0
param set MC_ATTRATE_P 0.12
param set MC_ATT_D 0.0
param set MC_ATT_I 0.0
param set MC_ATT_P 7.0
param set MC_YAWPOS_D 0.0
param set MC_YAWPOS_I 0.0
param set MC_YAWPOS_P 2.0
param set MC_YAWRATE_D 0.005
param set MC_YAWRATE_I 0.2
param set MC_YAWRATE_P 0.3
param save
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
2013-08-17 10:48:13 -03:00
set EXIT_ON_END no
2013-08-19 17:58:50 -03:00
#
# Start and configure PX4IO or FMU interface
#
if px4io detect
then
# Start MAVLink (depends on orb)
mavlink start
usleep 5000
sh /etc/init.d/rc.io
# Set PWM values for DJI ESCs
px4io idle 900 900 900 900
px4io min 1200 1200 1200 1200
px4io max 1800 1800 1800 1800
else
# Start MAVLink (on UART1 / ttyS0)
mavlink start -d /dev/ttyS0
usleep 5000
fmu mode_pwm
set EXIT_ON_END yes
fi
#
2013-08-25 14:27:11 -03:00
# Load mixer
#
2013-08-25 14:27:11 -03:00
mixer load /dev/pwm_output /etc/mixers/FMU_quad_x.mix
#
2013-08-25 14:27:11 -03:00
# Set PWM output frequency
#
2013-08-25 14:27:11 -03:00
pwm -u 400 -m 0xff
2013-08-11 12:39:10 -03:00
#
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
if [ $EXIT_ON_END == yes ]
then
exit
fi