MAVLink app: Allow higher max data rate

This commit is contained in:
Lorenz Meier 2015-04-26 14:24:01 +02:00
parent 8334073bb9
commit 0ebf626632
1 changed files with 1 additions and 1 deletions

View File

@ -90,7 +90,7 @@
static const int ERROR = -1;
#define DEFAULT_DEVICE_NAME "/dev/ttyS1"
#define MAX_DATA_RATE 20000 ///< max data rate in bytes/s
#define MAX_DATA_RATE 60000 ///< max data rate in bytes/s
#define MAIN_LOOP_DELAY 10000 ///< 100 Hz @ 1000 bytes/s data rate
#define FLOW_CONTROL_DISABLE_THRESHOLD 40 ///< picked so that some messages still would fit it.