Browse Source

AP_HAL_SITL: provide method to get amount of data still pending in outbound system queues

c415-sdk
Peter Barker 5 years ago committed by Peter Barker
parent
commit
7028eb8d24
  1. 20
      libraries/AP_HAL_SITL/UARTDriver.cpp
  2. 2
      libraries/AP_HAL_SITL/UARTDriver.h

20
libraries/AP_HAL_SITL/UARTDriver.cpp

@ -770,5 +770,25 @@ uint64_t UARTDriver::receive_time_constraint_us(uint16_t nbytes) @@ -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

2
libraries/AP_HAL_SITL/UARTDriver.h

@ -33,6 +33,8 @@ public: @@ -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…
Cancel
Save