diff --git a/CMakeLists.txt b/CMakeLists.txt index 3ec097d..c12fe13 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -64,7 +64,7 @@ pkg_check_modules(GST REQUIRED gstreamer-1.0 gstreamer-app-1.0) add_library(ArduPilotPlugin SHARED src/ArduPilotPlugin.cc - src/Socket.cpp + src/SocketUDP.cc src/Util.cc ) target_include_directories(ArduPilotPlugin PRIVATE diff --git a/include/Socket.h b/include/Socket.h deleted file mode 100644 index cae666c..0000000 --- a/include/Socket.h +++ /dev/null @@ -1,73 +0,0 @@ -/* - Copyright (C) 2022 ardupilot.org - - 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 - */ -#pragma once - -#include -#include -#include -#include -#include -#include -#include -#include - -class SocketAPM { -public: - explicit SocketAPM(bool _datagram); - SocketAPM(bool _datagram, int _fd); - ~SocketAPM(); - - bool connect(const char *address, uint16_t port); - bool bind(const char *address, uint16_t port); - bool reuseaddress(); - bool set_blocking(bool blocking); - bool set_cloexec(); - void set_broadcast(void); - - ssize_t send(const void *pkt, size_t size); - 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); - - // return the IP address and port of the last received packet - void last_recv_address(const char *&ip_addr, uint16_t &port); - - // return true if there is pending data for input - 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 - 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: - bool datagram; - struct sockaddr_in in_addr {}; - - int fd = -1; - - void make_sockaddr(const char *address, uint16_t port, - struct sockaddr_in &sockaddr); -}; diff --git a/include/SocketUDP.hh b/include/SocketUDP.hh new file mode 100644 index 0000000..7024313 --- /dev/null +++ b/include/SocketUDP.hh @@ -0,0 +1,75 @@ +/* + Copyright (C) 2024 ardupilot.org + + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU Lesser 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 Lesser General Public License + along with this program. If not, see . + */ + +#ifndef SOCKETUDP_HH_ +#define SOCKETUDP_HH_ + +#include +#include +#ifdef _WIN32 + #include + #include +#else + #include + #include + #include + #include + #include + #include +#endif + +/// \brief Simple UDP socket handling class. +class SocketUDP { +public: + /// \brief Constructor. + SocketUDP(bool reuseaddress, bool blocking); + + /// \brief Destructor. + ~SocketUDP(); + + /// \brief Bind socket to address and port. + bool bind(const char *address, uint16_t port); + + /// \brief Set reuse address option. + bool set_reuseaddress(); + + /// \brief Set blocking state. + bool set_blocking(bool blocking); + + /// \brief Send data to address and port. + ssize_t sendto(const void *buf, size_t size, const char *address, uint16_t port); + + /// \brief Receive data. + ssize_t recv(void *pkt, size_t size, uint32_t timeout_ms); + + /// \brief Get last client address and port + void get_client_address(const char *&ip_addr, uint16_t &port); + +private: + /// \brief File descriptor. + struct sockaddr_in in_addr {}; + + /// \brief File descriptor. + int fd = -1; + + /// \brief Poll for incoming data with timeout. + bool pollin(uint32_t timeout_ms); + + /// \brief Make a sockaddr_in struct from address and port. + void make_sockaddr(const char *address, uint16_t port, struct sockaddr_in &sockaddr); +}; +#endif // SOCKETUDP_HH_ diff --git a/src/ArduPilotPlugin.cc b/src/ArduPilotPlugin.cc index b2a3a25..3ef599b 100755 --- a/src/ArduPilotPlugin.cc +++ b/src/ArduPilotPlugin.cc @@ -57,7 +57,7 @@ #include -#include "Socket.h" +#include "SocketUDP.hh" #include "Util.hh" #define DEBUG_JSON_IO 0 @@ -219,7 +219,7 @@ class gz::sim::systems::ArduPilotPluginPrivate public: std::mutex mutex; /// \brief Socket manager - public: SocketAPM sock = SocketAPM(true); + public: SocketUDP sock = SocketUDP(true, true); /// \brief The address for the flight dynamics model (i.e. this plugin) public: std::string fdm_address{"127.0.0.1"}; @@ -1253,10 +1253,6 @@ void gz::sim::systems::ArduPilotPlugin::ResetPIDs() ///////////////////////////////////////////////// bool gz::sim::systems::ArduPilotPlugin::InitSockets(sdf::ElementPtr _sdf) const { - // configure port - this->dataPtr->sock.set_blocking(false); - this->dataPtr->sock.reuseaddress(); - // get the fdm address if provided, otherwise default to localhost this->dataPtr->fdm_address = _sdf->Get("fdm_addr", static_cast("127.0.0.1")).first; @@ -1407,7 +1403,7 @@ namespace /// \brief Get a servo packet. Templated for 16 or 32 channel packets. template ssize_t getServoPacket( - SocketAPM &_sock, + SocketUDP &_sock, const char *&_fcu_address, uint16_t &_fcu_port_out, uint32_t _waitMs, @@ -1417,7 +1413,7 @@ ssize_t getServoPacket( { ssize_t recvSize = _sock.recv(&_pkt, sizeof(TServoPacket), _waitMs); - _sock.last_recv_address(_fcu_address, _fcu_port_out); + _sock.get_client_address(_fcu_address, _fcu_port_out); // drain the socket in the case we're backed up int counter = 0; diff --git a/src/Socket.cpp b/src/Socket.cpp deleted file mode 100644 index 0ef3d78..0000000 --- a/src/Socket.cpp +++ /dev/null @@ -1,240 +0,0 @@ -/* - Copyright (C) 2022 ardupilot.org - - 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 "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) -{ - fcntl(fd, F_SETFD, FD_CLOEXEC); - if (!datagram) { - int one = 1; - setsockopt(fd, IPPROTO_TCP, TCP_NODELAY, &one, sizeof(one)); - } -} - -SocketAPM::~SocketAPM() -{ - if (fd != -1) { - ::close(fd); - 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 (::connect(fd, (struct sockaddr *)&sockaddr, sizeof(sockaddr)) != 0) { - return false; - } - return true; -} - -/* - bind the socket - */ -bool SocketAPM::bind(const char *address, uint16_t port) -{ - struct sockaddr_in sockaddr; - make_sockaddr(address, port, sockaddr); - - if (::bind(fd, (struct sockaddr *)&sockaddr, sizeof(sockaddr)) != 0) { - return false; - } - return true; -} - - -/* - set SO_REUSEADDR - */ -bool SocketAPM::reuseaddress(void) -{ - int one = 1; - return (setsockopt(fd, SOL_SOCKET, SO_REUSEADDR, &one, sizeof(one)) != -1); -} - -/* - set blocking state - */ -bool SocketAPM::set_blocking(bool blocking) -{ - 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() -{ - return (fcntl(fd, F_SETFD, FD_CLOEXEC) != -1); -} - -/* - send some data - */ -ssize_t SocketAPM::send(const void *buf, size_t size) -{ - return ::send(fd, buf, size, 0); -} - -/* - 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); - return ::sendto(fd, buf, size, 0, - (struct sockaddr *)&sockaddr, sizeof(sockaddr)); -} - -/* - 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); - return ::recvfrom(fd, buf, size, MSG_DONTWAIT, - reinterpret_cast(&in_addr), &len); -} - -/* - return the IP address and port of the last received packet - */ -void SocketAPM::last_recv_address(const char *&ip_addr, uint16_t &port) -{ - ip_addr = inet_ntoa(in_addr.sin_addr); - port = ntohs(in_addr.sin_port); -} - -void SocketAPM::set_broadcast(void) -{ - int one = 1; - setsockopt(fd, SOL_SOCKET, SO_BROADCAST, - reinterpret_cast(&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) -{ - return ::listen(fd, static_cast(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 nullptr; - } - - int newfd = ::accept(fd, nullptr, nullptr); - 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); -} diff --git a/src/SocketUDP.cc b/src/SocketUDP.cc new file mode 100644 index 0000000..f9aaa27 --- /dev/null +++ b/src/SocketUDP.cc @@ -0,0 +1,144 @@ +/* + Copyright (C) 2024 ardupilot.org + + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU Lesser 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 Lesser General Public License + along with this program. If not, see . + */ + + +#include "SocketUDP.hh" +#include +#include +#include + + +SocketUDP::SocketUDP(bool reuseaddress, bool blocking) { + fd = socket(AF_INET, SOCK_DGRAM, 0); + if (fd < 0) { + perror("SocketUDP creation failed"); + exit(EXIT_FAILURE); + } + +#ifndef _WIN32 + // Windows does not support FD_CLOEXEC + fcntl(fd, F_SETFD, FD_CLOEXEC); +#endif + + if (reuseaddress) { + set_reuseaddress(); + } + if (blocking) { + set_blocking(true); + } +} + + +SocketUDP::~SocketUDP() { + if (fd != -1) { + ::close(fd); + fd = -1; + } +} + + +bool SocketUDP::bind(const char *address, uint16_t port) { + struct sockaddr_in server_addr{}; + make_sockaddr(address, port, server_addr); + + if (::bind(fd, reinterpret_cast(&server_addr), sizeof(server_addr)) != 0) { + perror("SocketUDP Bind failed"); +#ifdef _WIN32 + closesocket(fd); +#else + close(fd); +#endif + return false; + } + return true; +} + + +bool SocketUDP::set_reuseaddress() { + int one = 1; + return (setsockopt(fd, SOL_SOCKET, SO_REUSEADDR, &one, sizeof(one)) != -1); +} + + +bool SocketUDP::set_blocking(bool blocking) { + int fcntl_ret; +#ifdef _WIN32 + u_long mode = blocking ? 0 : 1; + fcntl_ret = ioctlsocket(fd, FIONBIO, reinterpret_cast(&mode)); +#else + 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); + } +#endif + return fcntl_ret != -1; +} + + +ssize_t SocketUDP::sendto(const void *buf, size_t size, const char *address, uint16_t port) { + struct sockaddr_in sockaddr_out{}; + make_sockaddr(address, port, sockaddr_out); + + return ::sendto(fd, buf, size, 0, reinterpret_cast(&sockaddr_out), sizeof(sockaddr_out)); +} + +/* + receive some data + */ +ssize_t SocketUDP::recv(void *buf, size_t size, uint32_t timeout_ms) { + if (!pollin(timeout_ms)) { + return -1; + } + socklen_t len = sizeof(in_addr); + return ::recvfrom(fd, buf, size, MSG_DONTWAIT, reinterpret_cast(&in_addr), &len); +} + + +void SocketUDP::get_client_address(const char *&ip_addr, uint16_t &port) { + ip_addr = inet_ntoa(in_addr.sin_addr); + port = ntohs(in_addr.sin_port); +} + + +bool SocketUDP::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; +} + +void SocketUDP::make_sockaddr(const char *address, uint16_t port, struct sockaddr_in &sockaddr) +{ + sockaddr = {}; + + sockaddr.sin_family = AF_INET; + sockaddr.sin_addr.s_addr = inet_addr(address); + sockaddr.sin_port = htons(port); +#ifdef HAVE_SOCK_SIN_LEN + sockaddr.sin_len = sizeof(sockaddr); +#endif +}