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/rcS39
1 files changed, 24 insertions, 15 deletions
diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS
index 65a66a085..503dbb83e 100644
--- a/ROMFS/px4fmu_common/init.d/rcS
+++ b/ROMFS/px4fmu_common/init.d/rcS
@@ -116,6 +116,8 @@ 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
@@ -394,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
@@ -560,6 +568,7 @@ then
if [ $EXIT_ON_END == yes ]
then
+ echo "[init] Exit from nsh"
exit
fi