mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_SITL: reorder setting SO_REUSEADDR and binding rc in port
This stops things failing on cygwin, and may explain rebind failures we see in SITL.
This commit is contained in:
parent
447fab595e
commit
3d08d02a66
|
@ -117,13 +117,13 @@ void SITL_State::_sitl_setup(const char *home_str)
|
||||||
*/
|
*/
|
||||||
void SITL_State::_setup_fdm(void)
|
void SITL_State::_setup_fdm(void)
|
||||||
{
|
{
|
||||||
if (!_sitl_rc_in.bind("0.0.0.0", _rcin_port)) {
|
if (!_sitl_rc_in.reuseaddress()) {
|
||||||
fprintf(stderr, "SITL: socket bind failed on RC in port : %d - %s\n", _rcin_port, strerror(errno));
|
fprintf(stderr, "SITL: socket reuseaddress failed on RC in port: %d - %s\n", _rcin_port, strerror(errno));
|
||||||
fprintf(stderr, "Aborting launch...\n");
|
fprintf(stderr, "Aborting launch...\n");
|
||||||
exit(1);
|
exit(1);
|
||||||
}
|
}
|
||||||
if (!_sitl_rc_in.reuseaddress()) {
|
if (!_sitl_rc_in.bind("0.0.0.0", _rcin_port)) {
|
||||||
fprintf(stderr, "SITL: socket reuseaddress failed on RC in port: %d - %s\n", _rcin_port, strerror(errno));
|
fprintf(stderr, "SITL: socket bind failed on RC in port : %d - %s\n", _rcin_port, strerror(errno));
|
||||||
fprintf(stderr, "Aborting launch...\n");
|
fprintf(stderr, "Aborting launch...\n");
|
||||||
exit(1);
|
exit(1);
|
||||||
}
|
}
|
||||||
|
|
Loading…
Reference in New Issue