mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_SITL: set_cloexec on SITL's RCIN port
This commit is contained in:
parent
584c5d5806
commit
f2a842e415
|
@ -118,11 +118,12 @@ void SITL_State::_setup_fdm(void)
|
||||||
{
|
{
|
||||||
if (!_sitl_rc_in.bind("0.0.0.0", _rcin_port)) {
|
if (!_sitl_rc_in.bind("0.0.0.0", _rcin_port)) {
|
||||||
fprintf(stderr, "SITL: socket bind 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, "Abording launch...\n");
|
fprintf(stderr, "Aborting launch...\n");
|
||||||
exit(1);
|
exit(1);
|
||||||
}
|
}
|
||||||
_sitl_rc_in.reuseaddress();
|
_sitl_rc_in.reuseaddress();
|
||||||
_sitl_rc_in.set_blocking(false);
|
_sitl_rc_in.set_blocking(false);
|
||||||
|
_sitl_rc_in.set_cloexec();
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue