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:
Andrew Tridgell 2013-01-14 08:26:29 +11:00
parent 4609114a81
commit 4c4b6afaff
1 changed files with 0 additions and 3 deletions

View File

@ -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);
}
}
}