mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
SITL: added in recursion check in timer_handler()
This commit is contained in:
parent
833d433caf
commit
07f5baea9e
@ -228,13 +228,16 @@ static void sitl_simulator_output(void)
|
||||
static void timer_handler(int signum)
|
||||
{
|
||||
static uint32_t last_update_count;
|
||||
static bool in_timer;
|
||||
|
||||
if (_interrupts_are_blocked()) {
|
||||
if (in_timer || _interrupts_are_blocked()) {
|
||||
return;
|
||||
}
|
||||
uint8_t oldSREG = SREG;
|
||||
cli();
|
||||
|
||||
in_timer = true;
|
||||
|
||||
#ifndef __CYGWIN__
|
||||
/* make sure we die if our parent dies */
|
||||
if (kill(parent_pid, 0) != 0) {
|
||||
@ -242,15 +245,15 @@ static void timer_handler(int signum)
|
||||
}
|
||||
#else
|
||||
|
||||
static uint16_t count = 0;
|
||||
static uint32_t last_report;
|
||||
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();
|
||||
}
|
||||
if (millis() - last_report > 1000) {
|
||||
printf("TH %u cps\n", count);
|
||||
count = 0;
|
||||
last_report = millis();
|
||||
}
|
||||
#endif
|
||||
|
||||
/* check for packet from flight sim */
|
||||
@ -267,11 +270,13 @@ static void timer_handler(int signum)
|
||||
if (update_count == 0) {
|
||||
sitl_update_gps(0, 0, 0, 0, 0, false);
|
||||
SREG = oldSREG;
|
||||
in_timer = false;
|
||||
return;
|
||||
}
|
||||
|
||||
if (update_count == last_update_count) {
|
||||
SREG = oldSREG;
|
||||
in_timer = false;
|
||||
return;
|
||||
}
|
||||
last_update_count = update_count;
|
||||
@ -295,6 +300,7 @@ static void timer_handler(int signum)
|
||||
timer_scheduler.run();
|
||||
|
||||
SREG = oldSREG;
|
||||
in_timer = false;
|
||||
}
|
||||
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user