mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-06-02 11:59:17 +08:00
Changed ARDRONE to an OUTPUT_MODE setting and added a skip option to mixer. Fewer beeps than before.
This commit is contained in:
@@ -30,7 +30,6 @@ then
|
|||||||
param set MC_YAW_FF 0.15
|
param set MC_YAW_FF 0.15
|
||||||
fi
|
fi
|
||||||
|
|
||||||
set FMU_MODE gpio_serial
|
set OUTPUT_MODE ardrone
|
||||||
set OUTPUT_MODE fmu
|
|
||||||
set ARDRONE yes
|
|
||||||
set USE_IO no
|
set USE_IO no
|
||||||
|
set MIXER skip
|
||||||
@@ -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,9 +33,12 @@ then
|
|||||||
tone_alarm $TUNE_OUT_ERROR
|
tone_alarm $TUNE_OUT_ERROR
|
||||||
fi
|
fi
|
||||||
else
|
else
|
||||||
|
if [ $MIXER != skip ]
|
||||||
|
then
|
||||||
echo "[init] Mixer not defined"
|
echo "[init] Mixer not defined"
|
||||||
tone_alarm $TUNE_OUT_ERROR
|
tone_alarm $TUNE_OUT_ERROR
|
||||||
fi
|
fi
|
||||||
|
fi
|
||||||
|
|
||||||
if [ $OUTPUT_MODE == fmu -o $OUTPUT_MODE == io ]
|
if [ $OUTPUT_MODE == fmu -o $OUTPUT_MODE == io ]
|
||||||
then
|
then
|
||||||
|
|||||||
@@ -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,7 +282,7 @@ 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 PWM as primary output"
|
||||||
if fmu mode_$FMU_MODE
|
if fmu mode_$FMU_MODE
|
||||||
@@ -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
|
||||||
@@ -387,7 +392,7 @@ then
|
|||||||
mavlink start -b 230400 -d /dev/ttyACM0
|
mavlink start -b 230400 -d /dev/ttyACM0
|
||||||
usleep 5000
|
usleep 5000
|
||||||
else
|
else
|
||||||
if [ $TTYS1_BUSY == yes -o $ARDRONE == yes ]
|
if [ $TTYS1_BUSY == yes -o $OUTPUT_MODE == ardrone ]
|
||||||
then
|
then
|
||||||
# Start MAVLink on ttyS0, because FMU ttyS1 pins configured as something else
|
# Start MAVLink on ttyS0, because FMU ttyS1 pins configured as something else
|
||||||
mavlink start -d /dev/ttyS0
|
mavlink start -d /dev/ttyS0
|
||||||
@@ -430,7 +435,7 @@ then
|
|||||||
#
|
#
|
||||||
# Start up ARDrone Motor interface
|
# Start up ARDrone Motor interface
|
||||||
#
|
#
|
||||||
if [ $ARDRONE == yes ]
|
if [ $OUTPUT_MODE == ardrone ]
|
||||||
then
|
then
|
||||||
ardrone_interface start -d /dev/ttyS1
|
ardrone_interface start -d /dev/ttyS1
|
||||||
fi
|
fi
|
||||||
|
|||||||
Reference in New Issue
Block a user