AP_HAL: added destructor for Socket
This commit is contained in:
parent
4411c1fed4
commit
1a588263e4
@ -33,6 +33,13 @@ datagram(_datagram)
|
|||||||
setsockopt(fd, IPPROTO_TCP, TCP_NODELAY, &one, sizeof(one));
|
setsockopt(fd, IPPROTO_TCP, TCP_NODELAY, &one, sizeof(one));
|
||||||
}
|
}
|
||||||
|
|
||||||
|
SocketAPM::~SocketAPM()
|
||||||
|
{
|
||||||
|
if (::close(fd) < 0) {
|
||||||
|
perror("close");
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
void SocketAPM::make_sockaddr(const char *address, uint16_t port, struct sockaddr_in &sockaddr)
|
void SocketAPM::make_sockaddr(const char *address, uint16_t port, struct sockaddr_in &sockaddr)
|
||||||
{
|
{
|
||||||
memset(&sockaddr, 0, sizeof(sockaddr));
|
memset(&sockaddr, 0, sizeof(sockaddr));
|
||||||
|
@ -34,6 +34,8 @@
|
|||||||
class SocketAPM {
|
class SocketAPM {
|
||||||
public:
|
public:
|
||||||
SocketAPM(bool _datagram);
|
SocketAPM(bool _datagram);
|
||||||
|
~SocketAPM();
|
||||||
|
|
||||||
bool connect(const char *address, uint16_t port);
|
bool connect(const char *address, uint16_t port);
|
||||||
bool bind(const char *address, uint16_t port);
|
bool bind(const char *address, uint16_t port);
|
||||||
void reuseaddress();
|
void reuseaddress();
|
||||||
|
Loading…
Reference in New Issue
Block a user