mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
SITL: fix gimbal connection on Windows
This commit is contained in:
parent
bcb0ead71a
commit
491b545fab
@ -181,6 +181,11 @@ void Gimbal::update(void)
|
||||
*/
|
||||
void Gimbal::send_report(void)
|
||||
{
|
||||
if (AP_HAL::millis() < 10000) {
|
||||
// simulated aircraft don't appear until 10s after startup. This avoids a windows
|
||||
// threading issue with non-blocking sockets and the initial wait on uartA
|
||||
return;
|
||||
}
|
||||
if (!mavlink.connected && mav_socket.connect(target_address, target_port)) {
|
||||
::printf("Gimbal connected to %s:%u\n", target_address, (unsigned)target_port);
|
||||
mavlink.connected = true;
|
||||
|
Loading…
Reference in New Issue
Block a user