mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-05-23 16:37:34 +08:00
MAVLink app: Increase max data rate
This commit is contained in:
@@ -95,7 +95,7 @@
|
||||
static const int ERROR = -1;
|
||||
|
||||
#define DEFAULT_DEVICE_NAME "/dev/ttyS1"
|
||||
#define MAX_DATA_RATE 1000000 ///< max data rate in bytes/s
|
||||
#define MAX_DATA_RATE 10000000 ///< 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.
|
||||
|
||||
|
||||
Reference in New Issue
Block a user