mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_HAL_SITL: correct port numbers in diagnostic output
This commit is contained in:
parent
5588229f68
commit
3074855ea3
@ -302,7 +302,7 @@ void UARTDriver::_tcp_start_connection(uint16_t port, bool wait_for_connection)
|
||||
}
|
||||
|
||||
fprintf(stderr, "Serial port %u on TCP port %u\n", _portNumber,
|
||||
_sitlState->base_port() + _portNumber);
|
||||
(unsigned)ntohs(sockaddr.sin_port));
|
||||
fflush(stdout);
|
||||
}
|
||||
|
||||
@ -318,7 +318,7 @@ void UARTDriver::_tcp_start_connection(uint16_t port, bool wait_for_connection)
|
||||
setsockopt(_fd, IPPROTO_TCP, TCP_NODELAY, &one, sizeof(one));
|
||||
fcntl(_fd, F_SETFD, FD_CLOEXEC);
|
||||
_connected = true;
|
||||
fprintf(stdout, "Connection on serial port %u\n", _portNumber);
|
||||
fprintf(stdout, "Connection on serial port %u\n", (unsigned)ntohs(sockaddr.sin_port));
|
||||
}
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user