Browse Source

SITL: fix gimbal connection on Windows

mission-4.1.18
CSe 8 years ago committed by Francisco Ferreira
parent
commit
491b545fab
  1. 5
      libraries/SITL/SIM_Gimbal.cpp

5
libraries/SITL/SIM_Gimbal.cpp

@ -181,6 +181,11 @@ void Gimbal::update(void) @@ -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…
Cancel
Save