mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
MAVLink: Do a better job at receive rate limiting
This commit is contained in:
parent
c20e7f8424
commit
8a6e9d17ba
@ -698,6 +698,8 @@ int Mavlink::mavlink_open_uart(int baud, const char *uart_name, struct termios *
|
||||
|
||||
} else {
|
||||
_is_usb_uart = true;
|
||||
/* USB has no baudrate, but use a magic number for 'fast' */
|
||||
_baudrate = 2000000;
|
||||
}
|
||||
|
||||
#if defined (__PX4_LINUX) || defined (__PX4_DARWIN)
|
||||
|
||||
@ -288,6 +288,8 @@ public:
|
||||
|
||||
float get_rate_mult();
|
||||
|
||||
float get_baudrate() { return _baudrate; }
|
||||
|
||||
/* Functions for waiting to start transmission until message received. */
|
||||
void set_has_received_messages(bool received_messages) { _received_messages = received_messages; }
|
||||
bool get_has_received_messages() { return _received_messages; }
|
||||
|
||||
@ -1757,7 +1757,7 @@ MavlinkReceiver::receive_thread(void *arg)
|
||||
uint8_t buf[1600];
|
||||
#else
|
||||
/* the serial port buffers internally as well, we just need to fit a small chunk */
|
||||
uint8_t buf[32];
|
||||
uint8_t buf[64];
|
||||
#endif
|
||||
mavlink_message_t msg;
|
||||
|
||||
@ -1799,8 +1799,13 @@ MavlinkReceiver::receive_thread(void *arg)
|
||||
if (_mavlink->get_protocol() == SERIAL) {
|
||||
/* non-blocking read. read may return negative values */
|
||||
if ((nread = ::read(uart_fd, buf, sizeof(buf))) < (ssize_t)sizeof(buf)) {
|
||||
/* to avoid reading very small chunks wait for data before reading */
|
||||
usleep(1000);
|
||||
/*
|
||||
* to avoid reading very small chunks wait for data before reading
|
||||
* this is designed to target ~30 bytes at a time
|
||||
*/
|
||||
const unsigned character_count = 20;
|
||||
unsigned sleeptime = (1.0f / (_mavlink->get_baudrate() / 10)) * character_count * 1000000;
|
||||
usleep(sleeptime);
|
||||
}
|
||||
}
|
||||
#ifdef __PX4_POSIX
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user