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

36 lines
783 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
#
2014-03-05 10:07:05 -04:00
if [ $DO_AUTOCONFIG == yes ]
2014-03-04 11:33:18 -04:00
then
# Set all params here, then disable autoconfig
2014-03-05 10:07:05 -04:00
param set MC_ROLL_P 5.0
param set MC_ROLLRATE_P 0.13
param set MC_ROLLRATE_I 0.0
param set MC_ROLLRATE_D 0.0
param set MC_PITCH_P 5.0
param set MC_PITCHRATE_P 0.13
param set MC_PITCHRATE_I 0.0
param set MC_PITCHRATE_D 0.0
param set MC_YAW_P 1.0
param set MC_YAW_D 0.1
2014-03-04 11:33:18 -04:00
param set MC_YAWRATE_P 0.15
2014-03-05 10:07:05 -04:00
param set MC_YAWRATE_I 0.0
param set MC_YAWRATE_D 0.0
param set MC_YAW_FF 0.15
2014-03-04 11:33:18 -04:00
fi
2014-03-05 05:50:16 -04:00
set FMU_MODE gpio_serial
set OUTPUT_MODE fmu
2014-03-05 10:11:41 -04:00
set ARDRONE yes