Skip to content

Commit

Permalink
AP_HAL: Sockets to use LwIP if available
Browse files Browse the repository at this point in the history
  • Loading branch information
magicrub committed Nov 12, 2023
1 parent fb4a0f8 commit dda1f4d
Show file tree
Hide file tree
Showing 2 changed files with 54 additions and 0 deletions.
50 changes: 50 additions & 0 deletions libraries/AP_HAL/utility/Socket.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,20 @@
#include "Socket.h"
#include <errno.h>

#if AP_NETWORKING_BACKEND_CHIBIOS
#include <AP_Networking/AP_Networking.h>
#include <lwip/sockets.h>

// not defined/implememnted in LwIP.
#ifndef F_SETFD
#define F_SETFD 2
#endif

/* For F_[GET|SET]FD. */
#define FD_CLOEXEC 1 /* Actually anything with low bit set goes */

#endif

/*
constructor
*/
Expand All @@ -45,7 +59,11 @@ SocketAPM::SocketAPM(bool _datagram, int _fd) :
SocketAPM::~SocketAPM()
{
if (fd != -1) {
#if AP_NETWORKING_BACKEND_CHIBIOS
lwip_close(fd);
#else
::close(fd);
#endif
fd = -1;
}
}
Expand All @@ -70,7 +88,11 @@ 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;
Expand All @@ -86,7 +108,11 @@ bool SocketAPM::connect_timeout(const char *address, uint16_t port, uint32_t tim

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;
Expand Down Expand Up @@ -114,7 +140,11 @@ 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;
Expand Down Expand Up @@ -157,7 +187,11 @@ bool SocketAPM::set_cloexec() const
*/
ssize_t SocketAPM::send(const void *buf, size_t size) const
{
#if AP_NETWORKING_BACKEND_CHIBIOS
return send(fd, buf, size, 0);
#else
return ::send(fd, buf, size, 0);
#endif
}

/*
Expand All @@ -167,7 +201,11 @@ ssize_t SocketAPM::sendto(const void *buf, size_t size, const char *address, uin
{
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
}

/*
Expand All @@ -179,7 +217,11 @@ ssize_t SocketAPM::recv(void *buf, size_t size, uint32_t 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
}

/*
Expand Down Expand Up @@ -243,7 +285,11 @@ bool SocketAPM::pollout(uint32_t timeout_ms)
*/
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
}

/*
Expand All @@ -256,7 +302,11 @@ SocketAPM *SocketAPM::accept(uint32_t 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;
}
Expand Down
4 changes: 4 additions & 0 deletions libraries/AP_HAL/utility/Socket.h
Original file line number Diff line number Diff line change
Expand Up @@ -71,7 +71,11 @@ class SocketAPM {

private:
bool datagram;
#if AP_NETWORKING_BACKEND_CHIBIOS
typedef struct sockaddr_in in_addr;
#else
struct sockaddr_in in_addr {};
#endif

int fd = -1;

Expand Down

0 comments on commit dda1f4d

Please sign in to comment.