Skip to content

Commit

Permalink
SocketUDP: reformat to pass cpplint check
Browse files Browse the repository at this point in the history
  • Loading branch information
khancyr committed Aug 8, 2024
1 parent c80e90e commit 79437e6
Show file tree
Hide file tree
Showing 2 changed files with 28 additions and 17 deletions.
28 changes: 17 additions & 11 deletions include/SocketUDP.hh
Original file line number Diff line number Diff line change
Expand Up @@ -20,16 +20,19 @@

#include <fcntl.h>
#include <unistd.h>

#ifdef _WIN32
#include <winsock2.h>
#include <Ws2tcpip.h>
#include <winsock2.h>
#include <Ws2tcpip.h>
#else
#include <sys/ioctl.h>
#include <sys/socket.h>
#include <netinet/in.h>
#include <netinet/tcp.h>
#include <arpa/inet.h>
#include <sys/select.h>

#include <sys/ioctl.h>
#include <sys/socket.h>
#include <netinet/in.h>
#include <netinet/tcp.h>
#include <arpa/inet.h>
#include <sys/select.h>

#endif

/// \brief Simple UDP socket handling class.
Expand All @@ -51,7 +54,8 @@ public:
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);
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);
Expand All @@ -61,7 +65,7 @@ public:

private:
/// \brief File descriptor.
struct sockaddr_in in_addr {};
struct sockaddr_in in_addr{};

/// \brief File descriptor.
int fd = -1;
Expand All @@ -70,6 +74,8 @@ private:
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);
void make_sockaddr(const char *address, uint16_t port,
struct sockaddr_in &sockaddr);
};

#endif // SOCKETUDP_HH_
17 changes: 11 additions & 6 deletions src/SocketUDP.cc
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,8 @@ 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<sockaddr *>(&server_addr), sizeof(server_addr)) != 0) {
if (::bind(fd, reinterpret_cast<sockaddr *>(&server_addr),
sizeof(server_addr)) != 0) {
perror("SocketUDP Bind failed");
#ifdef _WIN32
closesocket(fd);
Expand Down Expand Up @@ -90,11 +91,14 @@ bool SocketUDP::set_blocking(bool blocking) {
}


ssize_t SocketUDP::sendto(const void *buf, size_t size, const char *address, uint16_t port) {
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 *>(&sockaddr_out), sizeof(sockaddr_out));
return ::sendto(fd, buf, size, 0,
reinterpret_cast<sockaddr *>(&sockaddr_out),
sizeof(sockaddr_out));
}

/*
Expand All @@ -105,7 +109,8 @@ ssize_t SocketUDP::recv(void *buf, size_t size, uint32_t timeout_ms) {
return -1;
}
socklen_t len = sizeof(in_addr);
return ::recvfrom(fd, buf, size, MSG_DONTWAIT, reinterpret_cast<sockaddr *>(&in_addr), &len);
return ::recvfrom(fd, buf, size, MSG_DONTWAIT,
reinterpret_cast<sockaddr *>(&in_addr), &len);
}


Expand All @@ -131,8 +136,8 @@ bool SocketUDP::pollin(uint32_t timeout_ms) {
return true;
}

void SocketUDP::make_sockaddr(const char *address, uint16_t port, struct sockaddr_in &sockaddr)
{
void SocketUDP::make_sockaddr(const char *address, uint16_t port,
struct sockaddr_in &sockaddr) {
sockaddr = {};

sockaddr.sin_family = AF_INET;
Expand Down

0 comments on commit 79437e6

Please sign in to comment.