AP_HAL: added pollout() function to socket API
This commit is contained in:
parent
a5f01c7ada
commit
19dee8419b
@ -161,6 +161,27 @@ bool SocketAPM::pollin(uint32_t timeout_ms)
|
|||||||
return true;
|
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
|
start listening for new tcp connections
|
||||||
*/
|
*/
|
||||||
@ -183,6 +204,9 @@ SocketAPM *SocketAPM::accept(uint32_t timeout_ms)
|
|||||||
if (newfd == -1) {
|
if (newfd == -1) {
|
||||||
return NULL;
|
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);
|
return new SocketAPM(false, newfd);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -49,6 +49,9 @@ public:
|
|||||||
// return true if there is pending data for input
|
// return true if there is pending data for input
|
||||||
bool pollin(uint32_t timeout_ms);
|
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
|
// start listening for new tcp connections
|
||||||
bool listen(uint16_t backlog);
|
bool listen(uint16_t backlog);
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user