mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
AP_HAL: added last_recv_address() with supplied buffer
this prevents a race condition with a static string
This commit is contained in:
parent
be668ddc1b
commit
a05acfc090
@ -247,6 +247,7 @@ ssize_t SocketAPM::sendto(const void *buf, size_t size, const char *address, uin
|
||||
ssize_t SocketAPM::recv(void *buf, size_t size, uint32_t timeout_ms)
|
||||
{
|
||||
if (!pollin(timeout_ms)) {
|
||||
errno = EWOULDBLOCK;
|
||||
return -1;
|
||||
}
|
||||
socklen_t len = sizeof(in_addr);
|
||||
@ -284,6 +285,19 @@ void SocketAPM::last_recv_address(const char *&ip_addr, uint16_t &port) const
|
||||
port = ntohs(in_addr.sin_port);
|
||||
}
|
||||
|
||||
/*
|
||||
return the IP address and port of the last received packet, using caller supplied buffer
|
||||
*/
|
||||
const char *SocketAPM::last_recv_address(char *ip_addr_buf, uint8_t buflen, uint16_t &port) const
|
||||
{
|
||||
const char *ret = inet_ntop(AF_INET, (void*)&in_addr.sin_addr, ip_addr_buf, buflen);
|
||||
if (ret == nullptr) {
|
||||
return nullptr;
|
||||
}
|
||||
port = ntohs(in_addr.sin_port);
|
||||
return ret;
|
||||
}
|
||||
|
||||
void SocketAPM::set_broadcast(void) const
|
||||
{
|
||||
int one = 1;
|
||||
@ -350,13 +364,11 @@ SocketAPM *SocketAPM::accept(uint32_t timeout_ms)
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
int newfd = CALL_PREFIX(accept)(fd, nullptr, nullptr);
|
||||
socklen_t len = sizeof(in_addr);
|
||||
int newfd = CALL_PREFIX(accept)(fd, (sockaddr *)&in_addr, &len);
|
||||
if (newfd == -1) {
|
||||
return nullptr;
|
||||
}
|
||||
// turn off nagle for lower latency
|
||||
int one = 1;
|
||||
CALL_PREFIX(setsockopt)(newfd, IPPROTO_TCP, TCP_NODELAY, &one, sizeof(one));
|
||||
return new SocketAPM(false, newfd);
|
||||
}
|
||||
|
||||
|
@ -57,6 +57,9 @@ public:
|
||||
// return the IP address and port of the last received packet
|
||||
void last_recv_address(const char *&ip_addr, uint16_t &port) const;
|
||||
|
||||
// return the IP address and port of the last received packet, using caller supplied buffer
|
||||
const char *last_recv_address(char *ip_addr_buf, uint8_t buflen, uint16_t &port) const;
|
||||
|
||||
// return true if there is pending data for input
|
||||
bool pollin(uint32_t timeout_ms);
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user