diff options
author | Lorenz Meier <lm@inf.ethz.ch> | 2015-04-26 14:24:01 +0200 |
---|---|---|
committer | Lorenz Meier <lm@inf.ethz.ch> | 2015-04-26 14:24:01 +0200 |
commit | 0ebf626632675dc5d54d08164be04d37ec1d74d2 (patch) | |
tree | 17e75fc1c58f0dee765b1ca470872843878910c7 | |
parent | 8334073bb99e3da7a5bfdfc24f540f0d0e14a361 (diff) | |
download | px4-firmware-0ebf626632675dc5d54d08164be04d37ec1d74d2.tar.gz px4-firmware-0ebf626632675dc5d54d08164be04d37ec1d74d2.tar.bz2 px4-firmware-0ebf626632675dc5d54d08164be04d37ec1d74d2.zip |
MAVLink app: Allow higher max data rate
-rw-r--r-- | src/modules/mavlink/mavlink_main.cpp | 2 |
1 files changed, 1 insertions, 1 deletions
diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index ba049bac4..22ff3edf6 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -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. |