@ -8,7 +8,7 @@ then
if hw_ver compare PX4FMU_V1
then
echo "Start sdlog2 at 50Hz"
sdlog2 start -r 50 -a -b 8 -t
sdlog2 start -r 50 -a -b 1 -t -e
else
echo "Start sdlog2 at 200Hz"
sdlog2 start -r 200 -a -b 16 -t
@ -410,7 +410,7 @@ then
if [ $TTYS1_BUSY == yes ]
# Start MAVLink on ttyS0, because FMU ttyS1 pins configured as something else
set MAVLINK_FLAGS "-r 1000 -d /dev/ttyS0"
set MAVLINK_FLAGS "-r 1000 -d /dev/ttyS0 -b 115200"
# Exit from nsh to free port for mavlink
set EXIT_ON_END yes