AP_HAL: added pollin() interface for Socket API

This commit is contained in:
Andrew Tridgell 2015-07-29 08:58:02 +10:00 committed by Randy Mackay
parent bd1b35804a
commit fa40e7245e
2 changed files with 18 additions and 3 deletions

View File

@ -125,6 +125,19 @@ ssize_t SocketAPM::sendto(const void *buf, size_t size, const char *address, uin
receive some data receive some data
*/ */
ssize_t SocketAPM::recv(void *buf, size_t size, uint32_t timeout_ms) ssize_t SocketAPM::recv(void *buf, size_t size, uint32_t timeout_ms)
{
if (!pollin(timeout_ms)) {
return -1;
}
return ::recvfrom(fd, buf, size, MSG_DONTWAIT, NULL, NULL);
}
/*
return true if there is pending data for input
*/
bool SocketAPM::pollin(uint32_t timeout_ms)
{ {
fd_set fds; fd_set fds;
struct timeval tv; struct timeval tv;
@ -136,10 +149,9 @@ ssize_t SocketAPM::recv(void *buf, size_t size, uint32_t timeout_ms)
tv.tv_usec = (timeout_ms % 1000) * 1000UL; tv.tv_usec = (timeout_ms % 1000) * 1000UL;
if (select(fd+1, &fds, NULL, NULL, &tv) != 1) { if (select(fd+1, &fds, NULL, NULL, &tv) != 1) {
return -1; return false;
} }
return true;
return ::recv(fd, buf, size, 0);
} }
#endif // HAL_OS_SOCKETS #endif // HAL_OS_SOCKETS

View File

@ -45,6 +45,9 @@ public:
ssize_t sendto(const void *buf, size_t size, const char *address, uint16_t port); ssize_t sendto(const void *buf, size_t size, const char *address, uint16_t port);
ssize_t recv(void *pkt, size_t size, uint32_t timeout_ms); ssize_t recv(void *pkt, size_t size, uint32_t timeout_ms);
// return true if there is pending data for input
bool pollin(uint32_t timeout_ms);
private: private:
bool datagram; bool datagram;
int fd = -1; int fd = -1;