px4-firmware/ROMFS/px4fmu_common/init.d/4008_ardrone

36 lines
749 B
Plaintext
Raw Normal View History

2014-03-04 11:33:18 -04:00
#!nsh
#
# ARDrone
#
2014-03-05 05:50:16 -04:00
echo "[init] 4008_ardrone: PX4FMU on PX4IOAR carrier board"
2014-03-04 11:33:18 -04:00
# Just use the default multicopter settings.
sh /etc/init.d/rc.mc_defaults
#
# Load default params for this platform
#
if param compare SYS_AUTOCONFIG 1
then
# Set all params here, then disable autoconfig
param set MC_ATTRATE_D 0
param set MC_ATTRATE_I 0
param set MC_ATTRATE_P 0.13
param set MC_ATT_D 0
param set MC_ATT_I 0.3
param set MC_ATT_P 5
param set MC_YAWPOS_D 0.1
param set MC_YAWPOS_I 0.15
param set MC_YAWPOS_P 1
param set MC_YAWRATE_D 0
param set MC_YAWRATE_I 0
param set MC_YAWRATE_P 0.15
param set SYS_AUTOCONFIG 0
param save
fi
2014-03-05 05:50:16 -04:00
set FMU_MODE gpio_serial
set OUTPUT_MODE fmu
set ARDRONE yes