mirror of https://github.com/ArduPilot/ardupilot
SITL: correct diagnostic message about what AirSim-in addr we bound
Co-authored-by: Oleksiy Protas <elfy.ua@gmail.com>
This commit is contained in:
parent
72f87edfb4
commit
6ef131c0f9
|
@ -55,12 +55,14 @@ AirSim::AirSim(const char *frame_str) :
|
||||||
*/
|
*/
|
||||||
void AirSim::set_interface_ports(const char* address, const int port_in, const int port_out)
|
void AirSim::set_interface_ports(const char* address, const int port_in, const int port_out)
|
||||||
{
|
{
|
||||||
if (!sock.bind("0.0.0.0", port_in)) {
|
static const char *port_in_addr = "0.0.0.0";
|
||||||
|
|
||||||
|
if (!sock.bind(port_in_addr, port_in)) {
|
||||||
printf("Unable to bind Airsim sensor_in socket at port %u - Error: %s\n",
|
printf("Unable to bind Airsim sensor_in socket at port %u - Error: %s\n",
|
||||||
port_in, strerror(errno));
|
port_in, strerror(errno));
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
printf("Bind SITL sensor input at %s:%u\n", "127.0.0.1", port_in);
|
printf("Bind SITL sensor input at %s:%u\n", port_in_addr, port_in);
|
||||||
sock.set_blocking(false);
|
sock.set_blocking(false);
|
||||||
sock.reuseaddress();
|
sock.reuseaddress();
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue