ardupilot/libraries/AP_HAL/utility/Socket.h

83 lines
2.5 KiB
C
Raw Normal View History

2015-05-05 08:27:33 -03:00
/*
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 <http://www.gnu.org/licenses/>.
*/
/*
simple socket handling class for systems with BSD socket API
*/
#pragma once
#include <AP_HAL/AP_HAL.h>
#include <AP_Networking/AP_Networking_Config.h>
#if AP_NETWORKING_SOCKETS_ENABLED
2015-05-05 08:27:33 -03:00
#if HAL_OS_SOCKETS
2015-05-22 02:53:33 -03:00
#include <fcntl.h>
2015-05-05 20:07:03 -03:00
#include <unistd.h>
2015-05-22 02:53:33 -03:00
#include <sys/ioctl.h>
#include <sys/socket.h>
#include <netinet/in.h>
#include <netinet/tcp.h>
#include <arpa/inet.h>
#include <sys/select.h>
#elif AP_NETWORKING_BACKEND_CHIBIOS
#include <AP_Networking/AP_Networking_ChibiOS.h>
#include <lwip/sockets.h>
#endif
2015-05-05 20:07:03 -03:00
2015-05-05 08:27:33 -03:00
class SocketAPM {
public:
SocketAPM(bool _datagram);
SocketAPM(bool _datagram, int _fd);
2015-06-11 18:48:24 -03:00
~SocketAPM();
2015-05-05 08:27:33 -03:00
bool connect(const char *address, uint16_t port);
bool connect_timeout(const char *address, uint16_t port, uint32_t timeout_ms);
2015-05-05 08:27:33 -03:00
bool bind(const char *address, uint16_t port);
bool reuseaddress() const;
bool set_blocking(bool blocking) const;
bool set_cloexec() const;
void set_broadcast(void) const;
2015-05-05 08:27:33 -03:00
ssize_t send(const void *pkt, size_t size) const;
ssize_t sendto(const void *buf, size_t size, const char *address, uint16_t port);
2015-05-05 08:27:33 -03:00
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) const;
// 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) const;
// 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);
2015-05-05 08:27:33 -03:00
private:
bool datagram;
struct sockaddr_in in_addr {};
2015-07-28 19:39:16 -03:00
int fd = -1;
2015-05-22 02:53:33 -03:00
void make_sockaddr(const char *address, uint16_t port, struct sockaddr_in &sockaddr);
2015-05-05 08:27:33 -03:00
};
#endif // AP_NETWORKING_SOCKETS_ENABLED