forked from Archive/PX4-Autopilot
MAVLink app: Allow higher max data rate
This commit is contained in:
parent
8334073bb9
commit
0ebf626632
|
@ -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.
|
||||
|
||||
|
|
Loading…
Reference in New Issue