telemetry: Crank up rates to make param downloads and other things less painful

This commit is contained in:
Lorenz Meier
2015-06-30 12:55:28 +02:00
parent 7b05165249
commit 319f9d820f
2 changed files with 28 additions and 4 deletions
+4 -4
View File
@@ -457,13 +457,13 @@ then
if [ $TTYS1_BUSY == yes ]
then
# Start MAVLink on ttyS0, because FMU ttyS1 pins configured as something else
set MAVLINK_F "-r 1000 -d /dev/ttyS0"
set MAVLINK_F "-r 5000 -d /dev/ttyS0"
# Exit from nsh to free port for mavlink
set EXIT_ON_END yes
else
# Start MAVLink on default port: ttyS1
set MAVLINK_F "-r 1000"
set MAVLINK_F "-r 5000"
fi
fi
@@ -479,11 +479,11 @@ then
# but this works for now
if param compare SYS_COMPANION 921600
then
mavlink start -d /dev/ttyS2 -b 921600 -m onboard -r 20000 -x
mavlink start -d /dev/ttyS2 -b 921600 -m onboard -r 80000 -x
fi
if param compare SYS_COMPANION 57600
then
mavlink start -d /dev/ttyS2 -b 57600 -m onboard -r 1000 -x
mavlink start -d /dev/ttyS2 -b 57600 -m onboard -r 60000 -x
fi
if param compare SYS_COMPANION 157600
then
+24
View File
@@ -0,0 +1,24 @@
M: 1
O: 10000 10000 0 -10000 10000
S: 0 0 10000 10000 0 -10000 10000
M: 1
O: 10000 10000 0 -10000 10000
S: 0 1 10000 10000 0 -10000 10000
M: 1
O: 10000 10000 0 -10000 10000
S: 0 2 10000 10000 0 -10000 10000
M: 1
O: 10000 10000 0 -10000 10000
S: 0 3 10000 10000 0 -10000 10000
M: 1
O: 10000 10000 0 -10000 10000
S: 0 4 10000 10000 0 -10000 10000
M: 1
O: 10000 10000 0 -10000 10000
S: 0 5 10000 10000 0 -10000 10000
M: 1
O: 10000 10000 0 -10000 10000
S: 0 6 10000 10000 0 -10000 10000
M: 1
O: 10000 10000 0 -10000 10000
S: 0 7 10000 10000 0 -10000 10000