mirror of https://github.com/ArduPilot/ardupilot
TimerProcess: prevent a race in setting up the timer callbacks
This commit is contained in:
parent
8d87aa41b9
commit
e7dab19260
|
@ -49,8 +49,10 @@ void AP_TimerProcess::register_process(ap_procedure proc)
|
||||||
for (uint8_t i=0; i<_pidx; i++) {
|
for (uint8_t i=0; i<_pidx; i++) {
|
||||||
if (_proc[i] == proc) return;
|
if (_proc[i] == proc) return;
|
||||||
}
|
}
|
||||||
|
cli();
|
||||||
if (_pidx < AP_TIMERPROCESS_MAX_PROCS)
|
if (_pidx < AP_TIMERPROCESS_MAX_PROCS)
|
||||||
_proc[_pidx++] = proc;
|
_proc[_pidx++] = proc;
|
||||||
|
sei();
|
||||||
}
|
}
|
||||||
|
|
||||||
void AP_TimerProcess::set_failsafe(ap_procedure proc)
|
void AP_TimerProcess::set_failsafe(ap_procedure proc)
|
||||||
|
|
Loading…
Reference in New Issue