mirror of https://github.com/ArduPilot/ardupilot
AP_HAL: added listen and accept APIs to socket API
This commit is contained in:
parent
fa40e7245e
commit
ef47a27ac8
|
@ -25,12 +25,19 @@
|
||||||
constructor
|
constructor
|
||||||
*/
|
*/
|
||||||
SocketAPM::SocketAPM(bool _datagram) :
|
SocketAPM::SocketAPM(bool _datagram) :
|
||||||
datagram(_datagram)
|
SocketAPM(_datagram,
|
||||||
|
socket(AF_INET, _datagram?SOCK_DGRAM:SOCK_STREAM, 0))
|
||||||
|
{}
|
||||||
|
|
||||||
|
SocketAPM::SocketAPM(bool _datagram, int _fd) :
|
||||||
|
datagram(_datagram),
|
||||||
|
fd(_fd)
|
||||||
{
|
{
|
||||||
fd = socket(AF_INET, datagram?SOCK_DGRAM:SOCK_STREAM, 0);
|
|
||||||
fcntl(fd, F_SETFD, FD_CLOEXEC);
|
fcntl(fd, F_SETFD, FD_CLOEXEC);
|
||||||
int one = 1;
|
if (!datagram) {
|
||||||
setsockopt(fd, IPPROTO_TCP, TCP_NODELAY, &one, sizeof(one));
|
int one = 1;
|
||||||
|
setsockopt(fd, IPPROTO_TCP, TCP_NODELAY, &one, sizeof(one));
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
SocketAPM::~SocketAPM()
|
SocketAPM::~SocketAPM()
|
||||||
|
@ -154,4 +161,29 @@ bool SocketAPM::pollin(uint32_t timeout_ms)
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/*
|
||||||
|
start listening for new tcp connections
|
||||||
|
*/
|
||||||
|
bool SocketAPM::listen(uint16_t backlog)
|
||||||
|
{
|
||||||
|
return ::listen(fd, (int)backlog) == 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
/*
|
||||||
|
accept a new connection. Only valid for TCP connections after
|
||||||
|
listen has been used. A new socket is returned
|
||||||
|
*/
|
||||||
|
SocketAPM *SocketAPM::accept(uint32_t timeout_ms)
|
||||||
|
{
|
||||||
|
if (!pollin(timeout_ms)) {
|
||||||
|
return NULL;
|
||||||
|
}
|
||||||
|
|
||||||
|
int newfd = ::accept(fd, NULL, NULL);
|
||||||
|
if (newfd == -1) {
|
||||||
|
return NULL;
|
||||||
|
}
|
||||||
|
return new SocketAPM(false, newfd);
|
||||||
|
}
|
||||||
|
|
||||||
#endif // HAL_OS_SOCKETS
|
#endif // HAL_OS_SOCKETS
|
||||||
|
|
|
@ -34,6 +34,7 @@
|
||||||
class SocketAPM {
|
class SocketAPM {
|
||||||
public:
|
public:
|
||||||
SocketAPM(bool _datagram);
|
SocketAPM(bool _datagram);
|
||||||
|
SocketAPM(bool _datagram, int _fd);
|
||||||
~SocketAPM();
|
~SocketAPM();
|
||||||
|
|
||||||
bool connect(const char *address, uint16_t port);
|
bool connect(const char *address, uint16_t port);
|
||||||
|
@ -48,6 +49,13 @@ 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);
|
||||||
|
|
||||||
|
// start listening for new tcp connections
|
||||||
|
bool listen(uint16_t backlog);
|
||||||
|
|
||||||
|
// accept a new connection. Only valid for TCP connections after
|
||||||
|
// listen has been used. A new socket is returned
|
||||||
|
SocketAPM *accept(uint32_t timeout_ms);
|
||||||
|
|
||||||
private:
|
private:
|
||||||
bool datagram;
|
bool datagram;
|
||||||
int fd = -1;
|
int fd = -1;
|
||||||
|
|
Loading…
Reference in New Issue