mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_SITL: allow sim_vehicle.py -I to work again
... or at least not die instantly because instance-0 has bound this port
This commit is contained in:
parent
7c52d8b468
commit
efd5fec24d
|
@ -663,7 +663,7 @@ void SITL_State::multicast_state_open(void)
|
|||
}
|
||||
|
||||
sockaddr.sin_addr.s_addr = htonl(INADDR_ANY);
|
||||
sockaddr.sin_port = htons(SITL_SERVO_PORT);
|
||||
sockaddr.sin_port = htons(SITL_SERVO_PORT + _instance);
|
||||
|
||||
ret = bind(servo_in_fd, (struct sockaddr *)&sockaddr, sizeof(sockaddr));
|
||||
if (ret == -1) {
|
||||
|
|
Loading…
Reference in New Issue