Browse Source

AP_HAL: added pollout() function to socket API

master
Andrew Tridgell 10 years ago
parent
commit
3e4b0b9869
  1. 24
      libraries/AP_HAL/utility/Socket.cpp
  2. 3
      libraries/AP_HAL/utility/Socket.h

24
libraries/AP_HAL/utility/Socket.cpp

@ -161,6 +161,27 @@ bool SocketAPM::pollin(uint32_t timeout_ms) @@ -161,6 +161,27 @@ bool SocketAPM::pollin(uint32_t timeout_ms)
return true;
}
/*
return true if there is room for output data
*/
bool SocketAPM::pollout(uint32_t timeout_ms)
{
fd_set fds;
struct timeval tv;
FD_ZERO(&fds);
FD_SET(fd, &fds);
tv.tv_sec = timeout_ms / 1000;
tv.tv_usec = (timeout_ms % 1000) * 1000UL;
if (select(fd+1, NULL, &fds, NULL, &tv) != 1) {
return false;
}
return true;
}
/*
start listening for new tcp connections
*/
@ -183,6 +204,9 @@ SocketAPM *SocketAPM::accept(uint32_t timeout_ms) @@ -183,6 +204,9 @@ SocketAPM *SocketAPM::accept(uint32_t timeout_ms)
if (newfd == -1) {
return NULL;
}
// turn off nagle for lower latency
int one = 1;
setsockopt(newfd, IPPROTO_TCP, TCP_NODELAY, &one, sizeof(one));
return new SocketAPM(false, newfd);
}

3
libraries/AP_HAL/utility/Socket.h

@ -49,6 +49,9 @@ public: @@ -49,6 +49,9 @@ public:
// return true if there is pending data for input
bool pollin(uint32_t timeout_ms);
// return true if there is room for output data
bool pollout(uint32_t timeout_ms);
// start listening for new tcp connections
bool listen(uint16_t backlog);

Loading…
Cancel
Save