mirror of https://github.com/ArduPilot/ardupilot
HAL_AVR_SITL: fixed log dump
the sockets need to default blocking, and only be non-blocking per call fixes issue #9
This commit is contained in:
parent
4609114a81
commit
4c4b6afaff
|
@ -220,7 +220,6 @@ void SITLUARTDriver::_tcp_start_connection(bool wait_for_connection)
|
|||
_connected = true;
|
||||
_listen_fd = -1;
|
||||
_fd = 1;
|
||||
_set_nonblocking(0);
|
||||
return;
|
||||
}
|
||||
|
||||
|
@ -279,7 +278,6 @@ void SITLUARTDriver::_tcp_start_connection(bool wait_for_connection)
|
|||
setsockopt(_fd, SOL_SOCKET, SO_REUSEADDR, &one, sizeof(one));
|
||||
setsockopt(_fd, IPPROTO_TCP, TCP_NODELAY, &one, sizeof(one));
|
||||
_connected = true;
|
||||
_set_nonblocking(_fd);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -300,7 +298,6 @@ void SITLUARTDriver::_check_connection(void)
|
|||
setsockopt(_fd, IPPROTO_TCP, TCP_NODELAY, &one, sizeof(one));
|
||||
setsockopt(_fd, SOL_SOCKET, SO_REUSEADDR, &one, sizeof(one));
|
||||
fprintf(stdout, "New connection on serial port %u\n", _portNumber);
|
||||
_set_nonblocking(_fd);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue