mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-10 01:44:00 -04:00
SITL: Make socket error more verbose
This commit is contained in:
parent
8f2bdf51ea
commit
567a8d68e5
@ -117,7 +117,8 @@ 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.bind("0.0.0.0", _rcin_port)) {
|
||||||
fprintf(stderr, "SITL: socket bind failed - %s\n", strerror(errno));
|
fprintf(stderr, "SITL: socket bind failed on RC in port : %d - %s\n", _rcin_port, strerror(errno));
|
||||||
|
fprintf(stderr, "Abording launch...\n");
|
||||||
exit(1);
|
exit(1);
|
||||||
}
|
}
|
||||||
_sitl_rc_in.reuseaddress();
|
_sitl_rc_in.reuseaddress();
|
||||||
|
@ -418,14 +418,16 @@ void Aircraft::set_speedup(float speedup)
|
|||||||
void Aircraft::set_interface_ports(const char* address, const int port_in, const int port_out)
|
void Aircraft::set_interface_ports(const char* address, const int port_in, const int port_out)
|
||||||
{
|
{
|
||||||
if (!socket_in.bind("127.0.0.1", port_in)) {
|
if (!socket_in.bind("127.0.0.1", port_in)) {
|
||||||
fprintf(stderr, "SITL: socket in bind failed - %s\n", strerror(errno));
|
fprintf(stderr, "SITL: socket in bind failed on sim in : %d - %s\n", port_in, strerror(errno));
|
||||||
|
fprintf(stderr, "Abording launch...\n");
|
||||||
exit(1);
|
exit(1);
|
||||||
}
|
}
|
||||||
socket_in.reuseaddress();
|
socket_in.reuseaddress();
|
||||||
socket_in.set_blocking(false);
|
socket_in.set_blocking(false);
|
||||||
|
|
||||||
if (!socket_out.connect(address, port_out)) {
|
if (!socket_out.connect(address, port_out)) {
|
||||||
fprintf(stderr, "SITL: socket out bind failed - %s\n", strerror(errno));
|
fprintf(stderr, "SITL: socket out bind failed on sim out : %d - %s\n", port_out, strerror(errno));
|
||||||
|
fprintf(stderr, "Abording launch...\n");
|
||||||
exit(1);
|
exit(1);
|
||||||
}
|
}
|
||||||
socket_out.reuseaddress();
|
socket_out.reuseaddress();
|
||||||
|
Loading…
Reference in New Issue
Block a user