/* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by the Free Software Foundation, either version 3 of the License, or (at your option) any later version. This program is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for more details. You should have received a copy of the GNU General Public License along with this program. If not, see . */ /* simple socket handling class for systems with BSD socket API */ #include #include #if AP_NETWORKING_SOCKETS_ENABLED #include "Socket.h" #include /* constructor */ SocketAPM::SocketAPM(bool _datagram) : SocketAPM(_datagram, socket(AF_INET, _datagram?SOCK_DGRAM:SOCK_STREAM, 0)) {} SocketAPM::SocketAPM(bool _datagram, int _fd) : datagram(_datagram), fd(_fd) { #ifdef FD_CLOEXEC fcntl(fd, F_SETFD, FD_CLOEXEC); #endif if (!datagram) { int one = 1; setsockopt(fd, IPPROTO_TCP, TCP_NODELAY, &one, sizeof(one)); } } SocketAPM::~SocketAPM() { if (fd != -1) { #if AP_NETWORKING_BACKEND_CHIBIOS ::lwip_close(fd); #else ::close(fd); #endif fd = -1; } } void SocketAPM::make_sockaddr(const char *address, uint16_t port, struct sockaddr_in &sockaddr) { memset(&sockaddr, 0, sizeof(sockaddr)); #ifdef HAVE_SOCK_SIN_LEN sockaddr.sin_len = sizeof(sockaddr); #endif sockaddr.sin_port = htons(port); sockaddr.sin_family = AF_INET; sockaddr.sin_addr.s_addr = inet_addr(address); } /* connect the socket */ bool SocketAPM::connect(const char *address, uint16_t port) { struct sockaddr_in sockaddr; make_sockaddr(address, port, sockaddr); #if AP_NETWORKING_BACKEND_CHIBIOS if (::lwip_connect(fd, (struct sockaddr *)&sockaddr, sizeof(sockaddr)) != 0) { #else if (::connect(fd, (struct sockaddr *)&sockaddr, sizeof(sockaddr)) != 0) { #endif return false; } return true; } /* connect the socket with a timeout */ bool SocketAPM::connect_timeout(const char *address, uint16_t port, uint32_t timeout_ms) { struct sockaddr_in sockaddr; make_sockaddr(address, port, sockaddr); set_blocking(false); #if AP_NETWORKING_BACKEND_CHIBIOS int ret = ::lwip_connect(fd, (struct sockaddr *)&sockaddr, sizeof(sockaddr)); #else int ret = ::connect(fd, (struct sockaddr *)&sockaddr, sizeof(sockaddr)); #endif if (ret == 0) { // instant connect? return true; } if (errno != EINPROGRESS) { return false; } bool pollret = pollout(timeout_ms); if (!pollret) { return false; } int sock_error = 0; socklen_t len = sizeof(sock_error); if (getsockopt(fd, SOL_SOCKET, SO_ERROR, (void*)&sock_error, &len) != 0) { return false; } return sock_error == 0; } /* bind the socket */ bool SocketAPM::bind(const char *address, uint16_t port) { struct sockaddr_in sockaddr; make_sockaddr(address, port, sockaddr); #if AP_NETWORKING_BACKEND_CHIBIOS if (::lwip_bind(fd, (struct sockaddr *)&sockaddr, sizeof(sockaddr)) != 0) { #else if (::bind(fd, (struct sockaddr *)&sockaddr, sizeof(sockaddr)) != 0) { #endif return false; } return true; } /* set SO_REUSEADDR */ bool SocketAPM::reuseaddress(void) const { int one = 1; return (setsockopt(fd, SOL_SOCKET, SO_REUSEADDR, &one, sizeof(one)) != -1); } /* set blocking state */ bool SocketAPM::set_blocking(bool blocking) const { int fcntl_ret; if (blocking) { fcntl_ret = fcntl(fd, F_SETFL, fcntl(fd, F_GETFL, 0) & ~O_NONBLOCK); } else { fcntl_ret = fcntl(fd, F_SETFL, fcntl(fd, F_GETFL, 0) | O_NONBLOCK); } return fcntl_ret != -1; } /* set cloexec state */ bool SocketAPM::set_cloexec() const { #ifdef FD_CLOEXEC return (fcntl(fd, F_SETFD, FD_CLOEXEC) != -1); #else return false; #endif } /* send some data */ ssize_t SocketAPM::send(const void *buf, size_t size) const { #if AP_NETWORKING_BACKEND_CHIBIOS return ::lwip_send(fd, buf, size, 0); #else return ::send(fd, buf, size, 0); #endif } /* send some data */ ssize_t SocketAPM::sendto(const void *buf, size_t size, const char *address, uint16_t port) { struct sockaddr_in sockaddr; make_sockaddr(address, port, sockaddr); #if AP_NETWORKING_BACKEND_CHIBIOS return ::lwip_sendto(fd, buf, size, 0, (struct sockaddr *)&sockaddr, sizeof(sockaddr)); #else return ::sendto(fd, buf, size, 0, (struct sockaddr *)&sockaddr, sizeof(sockaddr)); #endif } /* receive some data */ ssize_t SocketAPM::recv(void *buf, size_t size, uint32_t timeout_ms) { if (!pollin(timeout_ms)) { return -1; } socklen_t len = sizeof(in_addr); #if AP_NETWORKING_BACKEND_CHIBIOS return ::lwip_recvfrom(fd, buf, size, MSG_DONTWAIT, (sockaddr *)&in_addr, &len); #else return ::recvfrom(fd, buf, size, MSG_DONTWAIT, (sockaddr *)&in_addr, &len); #endif } /* return the IP address and port of the last received packet */ void SocketAPM::last_recv_address(const char *&ip_addr, uint16_t &port) const { ip_addr = inet_ntoa(in_addr.sin_addr); port = ntohs(in_addr.sin_port); } void SocketAPM::set_broadcast(void) const { int one = 1; setsockopt(fd,SOL_SOCKET,SO_BROADCAST,(char *)&one,sizeof(one)); } /* return true if there is pending data for input */ bool SocketAPM::pollin(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, &fds, nullptr, nullptr, &tv) != 1) { return false; } 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, nullptr, &fds, nullptr, &tv) != 1) { return false; } return true; } /* start listening for new tcp connections */ bool SocketAPM::listen(uint16_t backlog) const { #if AP_NETWORKING_BACKEND_CHIBIOS return ::lwip_listen(fd, (int)backlog) == 0; #else return ::listen(fd, (int)backlog) == 0; #endif } /* 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 nullptr; } #if AP_NETWORKING_BACKEND_CHIBIOS int newfd = ::lwip_accept(fd, nullptr, nullptr); #else int newfd = ::accept(fd, nullptr, nullptr); #endif if (newfd == -1) { return nullptr; } // turn off nagle for lower latency int one = 1; setsockopt(newfd, IPPROTO_TCP, TCP_NODELAY, &one, sizeof(one)); return new SocketAPM(false, newfd); } #endif // AP_NETWORKING_BACKEND_ANY