SITL: make socket manipulation functions bool rather than void

... so callers can check if they succeeded or not
This commit is contained in:
Peter Barker 2018-12-14 13:36:50 +11:00 committed by Peter Barker
parent 89be497897
commit 24653a33ed
2 changed files with 12 additions and 10 deletions

View File

@ -92,30 +92,32 @@ bool SocketAPM::bind(const char *address, uint16_t port)
/*
set SO_REUSEADDR
*/
void SocketAPM::reuseaddress(void)
bool SocketAPM::reuseaddress(void)
{
int one = 1;
setsockopt(fd, SOL_SOCKET, SO_REUSEADDR, &one, sizeof(one));
return (setsockopt(fd, SOL_SOCKET, SO_REUSEADDR, &one, sizeof(one)) != -1);
}
/*
set blocking state
*/
void SocketAPM::set_blocking(bool blocking)
bool SocketAPM::set_blocking(bool blocking)
{
int fcntl_ret;
if (blocking) {
fcntl(fd, F_SETFL, fcntl(fd, F_GETFL, 0) & ~O_NONBLOCK);
fcntl_ret = fcntl(fd, F_SETFL, fcntl(fd, F_GETFL, 0) & ~O_NONBLOCK);
} else {
fcntl(fd, F_SETFL, fcntl(fd, F_GETFL, 0) | O_NONBLOCK);
fcntl_ret = fcntl(fd, F_SETFL, fcntl(fd, F_GETFL, 0) | O_NONBLOCK);
}
return fcntl_ret != -1;
}
/*
set cloexec state
*/
void SocketAPM::set_cloexec()
bool SocketAPM::set_cloexec()
{
fcntl(fd, F_SETFD, FD_CLOEXEC);
return (fcntl(fd, F_SETFD, FD_CLOEXEC) != -1);
}
/*

View File

@ -37,9 +37,9 @@ public:
bool connect(const char *address, uint16_t port);
bool bind(const char *address, uint16_t port);
void reuseaddress();
void set_blocking(bool blocking);
void set_cloexec();
bool reuseaddress();
bool set_blocking(bool blocking);
bool set_cloexec();
void set_broadcast(void);
ssize_t send(const void *pkt, size_t size);