mirror of https://github.com/ArduPilot/ardupilot
sitl cygwin mods
This commit is contained in:
parent
010f147fb2
commit
42960efe80
|
@ -84,6 +84,12 @@ int main(int argc, char * const argv[])
|
|||
fd_set fds;
|
||||
int fd_high = 0;
|
||||
|
||||
#ifdef __CYGWIN__
|
||||
// under windows if this loop is using alot of cpu,
|
||||
// the alarm gets called at a slower rate.
|
||||
sleep(5);
|
||||
#endif
|
||||
|
||||
FD_ZERO(&fds);
|
||||
loop();
|
||||
|
||||
|
|
|
@ -231,6 +231,17 @@ static void timer_handler(int signum)
|
|||
if (kill(parent_pid, 0) != 0) {
|
||||
exit(1);
|
||||
}
|
||||
#else
|
||||
|
||||
static uint16_t count = 0;
|
||||
static uint32_t last_report;
|
||||
|
||||
count++;
|
||||
if (millis() - last_report > 1000) {
|
||||
printf("TH %u cps\n", count);
|
||||
count = 0;
|
||||
last_report = millis();
|
||||
}
|
||||
#endif
|
||||
|
||||
/* check for packet from flight sim */
|
||||
|
|
Loading…
Reference in New Issue