mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
HAL_SITL: added debug for multicast startup
useful for CI diagnosis
This commit is contained in:
parent
52d80241b9
commit
823ac579cd
@ -188,6 +188,7 @@ void SimMCast::multicast_open(void)
|
||||
strerror(errno));
|
||||
exit(1);
|
||||
}
|
||||
::printf("multicast receiver initialised\n");
|
||||
}
|
||||
|
||||
/*
|
||||
@ -247,7 +248,11 @@ void SimMCast::multicast_read(void)
|
||||
while (recvfrom(mc_fd, (void*)&state, sizeof(state), MSG_WAITALL, (sockaddr *)&in_addr, &len) != sizeof(state)) {
|
||||
// nop
|
||||
}
|
||||
if (_sitl->state.timestamp_us == 0) {
|
||||
printf("Got multicast state input\n");
|
||||
}
|
||||
if (state.timestamp_us < _sitl->state.timestamp_us) {
|
||||
printf("multicast state time reset\n");
|
||||
// main process has rebooted
|
||||
base_time_us += (_sitl->state.timestamp_us - state.timestamp_us);
|
||||
}
|
||||
|
@ -666,6 +666,7 @@ void SITL_State::multicast_state_open(void)
|
||||
fprintf(stderr, "udp servo connect failed\n");
|
||||
exit(1);
|
||||
}
|
||||
::printf("multicast initialised\n");
|
||||
}
|
||||
|
||||
/*
|
||||
|
Loading…
Reference in New Issue
Block a user