mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_SITL: provide method to get amount of data still pending in outbound system queues
This commit is contained in:
parent
2b18b0f480
commit
7028eb8d24
|
@ -770,5 +770,25 @@ uint64_t UARTDriver::receive_time_constraint_us(uint16_t nbytes)
|
|||
return last_receive_us;
|
||||
}
|
||||
|
||||
ssize_t UARTDriver::get_system_outqueue_length() const
|
||||
{
|
||||
if (!_connected) {
|
||||
return 0;
|
||||
}
|
||||
|
||||
#if defined(__CYGWIN__) || defined(__CYGWIN64__) || defined(CYGWIN_BUILD)
|
||||
return 0;
|
||||
#elif defined(__APPLE__) && defined(__MACH__)
|
||||
return 0;
|
||||
#else
|
||||
int size;
|
||||
if (ioctl(_fd, TIOCOUTQ, &size) == -1) {
|
||||
// ::fprintf(stderr, "ioctl TIOCOUTQ failed: %m\n");
|
||||
return 0;
|
||||
}
|
||||
return size;
|
||||
#endif
|
||||
}
|
||||
|
||||
#endif // CONFIG_HAL_BOARD
|
||||
|
||||
|
|
|
@ -33,6 +33,8 @@ public:
|
|||
return true;
|
||||
}
|
||||
|
||||
ssize_t get_system_outqueue_length() const;
|
||||
|
||||
void set_blocking_writes(bool blocking) override
|
||||
{
|
||||
_nonblocking_writes = !blocking;
|
||||
|
|
Loading…
Reference in New Issue