aboutsummaryrefslogtreecommitdiff
path: root/ROMFS/px4fmu_common/init.d/rcS
diff options
context:
space:
mode:
Diffstat (limited to 'ROMFS/px4fmu_common/init.d/rcS')
-rw-r--r--ROMFS/px4fmu_common/init.d/rcS84
1 files changed, 61 insertions, 23 deletions
diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS
index 76f021e33..503dbb83e 100644
--- a/ROMFS/px4fmu_common/init.d/rcS
+++ b/ROMFS/px4fmu_common/init.d/rcS
@@ -108,7 +108,6 @@ then
set HIL no
set VEHICLE_TYPE none
set MIXER none
- set USE_IO yes
set OUTPUT_MODE none
set PWM_OUTPUTS none
set PWM_RATE none
@@ -117,7 +116,10 @@ then
set PWM_MAX none
set MKBLCTRL_MODE none
set FMU_MODE pwm
+ set MAVLINK_FLAGS default
+ set EXIT_ON_END no
set MAV_TYPE none
+ set LOAD_DEFAULT_APPS yes
#
# Set DO_AUTOCONFIG flag to use it in AUTOSTART scripts
@@ -128,6 +130,16 @@ then
else
set DO_AUTOCONFIG no
fi
+
+ #
+ # Set USE_IO flag
+ #
+ if param compare SYS_USE_IO 1
+ then
+ set USE_IO yes
+ else
+ set USE_IO no
+ fi
#
# Set parameters and env variables for selected AUTOSTART
@@ -240,6 +252,11 @@ then
fi
fi
+ if [ $OUTPUT_MODE == ardrone ]
+ then
+ set FMU_MODE gpio_serial
+ fi
+
if [ $HIL == yes ]
then
set OUTPUT_MODE hil
@@ -277,9 +294,9 @@ then
tone_alarm $TUNE_OUT_ERROR
fi
fi
- if [ $OUTPUT_MODE == fmu ]
+ if [ $OUTPUT_MODE == fmu -o $OUTPUT_MODE == ardrone ]
then
- echo "[init] Use FMU PWM as primary output"
+ echo "[init] Use FMU as primary output"
if fmu mode_$FMU_MODE
then
echo "[init] FMU mode_$FMU_MODE started"
@@ -294,7 +311,7 @@ then
then
set TTYS1_BUSY yes
fi
- if [ $FMU_MODE == pwm_gpio ]
+ if [ $FMU_MODE == pwm_gpio -o $OUTPUT_MODE == ardrone ]
then
set TTYS1_BUSY yes
fi
@@ -351,7 +368,7 @@ then
fi
fi
else
- if [ $OUTPUT_MODE != fmu ]
+ if [ $OUTPUT_MODE != fmu -a $OUTPUT_MODE != ardrone ]
then
if fmu mode_$FMU_MODE
then
@@ -367,7 +384,7 @@ then
then
set TTYS1_BUSY yes
fi
- if [ $FMU_MODE == pwm_gpio ]
+ if [ $FMU_MODE == pwm_gpio -o $OUTPUT_MODE == ardrone ]
then
set TTYS1_BUSY yes
fi
@@ -379,28 +396,34 @@ then
#
# MAVLink
#
- set EXIT_ON_END no
- if [ $HIL == yes ]
+ if [ $MAVLINK_FLAGS == default ]
then
- sleep 1
- mavlink start -b 230400 -d /dev/ttyACM0
- usleep 5000
- else
- if [ $TTYS1_BUSY == yes ]
+ if [ $HIL == yes ]
then
- # Start MAVLink on ttyS0, because FMU ttyS1 pins configured as something else
- mavlink start -d /dev/ttyS0
+ sleep 1
+ set MAVLINK_FLAGS "-r 10000 -d /dev/ttyACM0"
usleep 5000
-
- # Exit from nsh to free port for mavlink
- set EXIT_ON_END yes
else
- # Start MAVLink on default port: ttyS1
- mavlink start
- usleep 5000
+ # Normal mode, use baudrate 57600 (default) and data rate 1000 bytes/s
+ if [ $TTYS1_BUSY == yes ]
+ then
+ # Start MAVLink on ttyS0, because FMU ttyS1 pins configured as something else
+ set MAVLINK_FLAGS "-r 1000 -d /dev/ttyS0"
+ usleep 5000
+
+ # Exit from nsh to free port for mavlink
+ set EXIT_ON_END yes
+ else
+ # Start MAVLink on default port: ttyS1
+ set MAVLINK_FLAGS "-r 1000"
+ usleep 5000
+ fi
fi
fi
+
+ mavlink start $MAVLINK_FLAGS
+ usleep 5000
#
# Start the datamanager
@@ -428,6 +451,14 @@ then
fi
#
+ # Start up ARDrone Motor interface
+ #
+ if [ $OUTPUT_MODE == ardrone ]
+ then
+ ardrone_interface start -d /dev/ttyS1
+ fi
+
+ #
# Fixed wing setup
#
if [ $VEHICLE_TYPE == fw ]
@@ -452,7 +483,10 @@ then
sh /etc/init.d/rc.interface
# Start standard fixedwing apps
- sh /etc/init.d/rc.fw_apps
+ if [ $LOAD_DEFAULT_APPS == yes ]
+ then
+ sh /etc/init.d/rc.fw_apps
+ fi
fi
#
@@ -508,7 +542,10 @@ then
sh /etc/init.d/rc.interface
# Start standard multicopter apps
- sh /etc/init.d/rc.mc_apps
+ if [ $LOAD_DEFAULT_APPS == yes ]
+ then
+ sh /etc/init.d/rc.mc_apps
+ fi
fi
#
@@ -531,6 +568,7 @@ then
if [ $EXIT_ON_END == yes ]
then
+ echo "[init] Exit from nsh"
exit
fi