mirror of https://github.com/ArduPilot/ardupilot
AP_HAL: fixed socket destructor
This commit is contained in:
parent
3f3aaa3c50
commit
5067359ed7
|
@ -35,8 +35,9 @@ datagram(_datagram)
|
|||
|
||||
SocketAPM::~SocketAPM()
|
||||
{
|
||||
if (::close(fd) < 0) {
|
||||
perror("close");
|
||||
if (fd != -1) {
|
||||
::close(fd);
|
||||
fd = -1;
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -47,7 +47,7 @@ public:
|
|||
|
||||
private:
|
||||
bool datagram;
|
||||
int fd;
|
||||
int fd = -1;
|
||||
|
||||
void make_sockaddr(const char *address, uint16_t port, struct sockaddr_in &sockaddr);
|
||||
};
|
||||
|
|
Loading…
Reference in New Issue