Merge pull request #705 from helenol/helen_ardrone

Ardrone startup script
This commit is contained in:
Lorenz Meier 2014-03-06 17:08:27 +01:00
commit 3207450037
5 changed files with 69 additions and 9 deletions

View File

@ -0,0 +1,35 @@
#!nsh
#
# ARDrone
#
echo "[init] 4008_ardrone: PX4FMU on PX4IOAR carrier board"
# Just use the default multicopter settings.
sh /etc/init.d/rc.mc_defaults
#
# Load default params for this platform
#
if [ $DO_AUTOCONFIG == yes ]
then
# Set all params here, then disable autoconfig
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
param set MC_YAWRATE_P 0.15
param set MC_YAWRATE_I 0.0
param set MC_YAWRATE_D 0.0
param set MC_YAW_FF 0.15
fi
set OUTPUT_MODE ardrone
set USE_IO no
set MIXER skip

View File

@ -106,6 +106,15 @@ then
sh /etc/init.d/4001_quad_x sh /etc/init.d/4001_quad_x
fi fi
#
# ARDrone
#
if param compare SYS_AUTOSTART 4008 8
then
sh /etc/init.d/4008_ardrone
fi
if param compare SYS_AUTOSTART 4010 10 if param compare SYS_AUTOSTART 4010 10
then then
sh /etc/init.d/4010_dji_f330 sh /etc/init.d/4010_dji_f330

View File

@ -3,7 +3,7 @@
# Script to configure control interface # Script to configure control interface
# #
if [ $MIXER != none ] if [ $MIXER != none -a $MIXER != skip]
then then
# #
# Load mixer # Load mixer
@ -33,8 +33,11 @@ then
tone_alarm $TUNE_OUT_ERROR tone_alarm $TUNE_OUT_ERROR
fi fi
else else
echo "[init] Mixer not defined" if [ $MIXER != skip ]
tone_alarm $TUNE_OUT_ERROR then
echo "[init] Mixer not defined"
tone_alarm $TUNE_OUT_ERROR
fi
fi fi
if [ $OUTPUT_MODE == fmu -o $OUTPUT_MODE == io ] if [ $OUTPUT_MODE == fmu -o $OUTPUT_MODE == io ]

View File

@ -240,6 +240,11 @@ then
fi fi
fi fi
if [ $OUTPUT_MODE == ardrone ]
then
set FMU_MODE gpio_serial
fi
if [ $HIL == yes ] if [ $HIL == yes ]
then then
set OUTPUT_MODE hil set OUTPUT_MODE hil
@ -277,9 +282,9 @@ then
tone_alarm $TUNE_OUT_ERROR tone_alarm $TUNE_OUT_ERROR
fi fi
fi fi
if [ $OUTPUT_MODE == fmu ] if [ $OUTPUT_MODE == fmu -o $OUTPUT_MODE = ardrone ]
then then
echo "[init] Use FMU PWM as primary output" echo "[init] Use FMU as primary output"
if fmu mode_$FMU_MODE if fmu mode_$FMU_MODE
then then
echo "[init] FMU mode_$FMU_MODE started" echo "[init] FMU mode_$FMU_MODE started"
@ -294,7 +299,7 @@ then
then then
set TTYS1_BUSY yes set TTYS1_BUSY yes
fi fi
if [ $FMU_MODE == pwm_gpio ] if [ $FMU_MODE == pwm_gpio -o $OUTPUT_MODE == ardrone ]
then then
set TTYS1_BUSY yes set TTYS1_BUSY yes
fi fi
@ -351,7 +356,7 @@ then
fi fi
fi fi
else else
if [ $OUTPUT_MODE != fmu ] if [ $OUTPUT_MODE != fmu -a $OUTPUT_MODE != ardrone ]
then then
if fmu mode_$FMU_MODE if fmu mode_$FMU_MODE
then then
@ -367,7 +372,7 @@ then
then then
set TTYS1_BUSY yes set TTYS1_BUSY yes
fi fi
if [ $FMU_MODE == pwm_gpio ] if [ $FMU_MODE == pwm_gpio -o $OUTPUT_MODE == ardrone ]
then then
set TTYS1_BUSY yes set TTYS1_BUSY yes
fi fi
@ -427,6 +432,14 @@ then
gps start gps start
fi fi
#
# Start up ARDrone Motor interface
#
if [ $OUTPUT_MODE == ardrone ]
then
ardrone_interface start -d /dev/ttyS1
fi
# #
# Fixed wing setup # Fixed wing setup
# #

View File

@ -1714,7 +1714,7 @@ fmu_main(int argc, char *argv[])
} }
fprintf(stderr, "FMU: unrecognised command, try:\n"); fprintf(stderr, "FMU: unrecognised command %s, try:\n", verb);
#if defined(CONFIG_ARCH_BOARD_PX4FMU_V1) #if defined(CONFIG_ARCH_BOARD_PX4FMU_V1)
fprintf(stderr, " mode_gpio, mode_serial, mode_pwm, mode_gpio_serial, mode_pwm_serial, mode_pwm_gpio, test\n"); fprintf(stderr, " mode_gpio, mode_serial, mode_pwm, mode_gpio_serial, mode_pwm_serial, mode_pwm_gpio, test\n");
#elif defined(CONFIG_ARCH_BOARD_PX4FMU_V2) #elif defined(CONFIG_ARCH_BOARD_PX4FMU_V2)