TimerProcess: check for duplicate registrations

if a driver gets initialised twice, make sure it doesn't get called
twice in the timer loop
This commit is contained in:
Andrew Tridgell 2011-12-27 07:25:00 +11:00
parent dbaa6fb6d2
commit 4d71482d1c
1 changed files with 9 additions and 1 deletions

View File

@ -33,14 +33,22 @@ void AP_TimerProcess::init( Arduino_Mega_ISR_Registry * isr_reg )
_failsafe = NULL; _failsafe = NULL;
_in_timer_call = false; _in_timer_call = false;
for (int i = 0; i < AP_TIMERPROCESS_MAX_PROCS; i++) for (uint8_t i = 0; i < AP_TIMERPROCESS_MAX_PROCS; i++)
_proc[i] = NULL; _proc[i] = NULL;
isr_reg->register_signal( ISR_REGISTRY_TIMER2_OVF, AP_TimerProcess::run); isr_reg->register_signal( ISR_REGISTRY_TIMER2_OVF, AP_TimerProcess::run);
} }
/*
register a process to be called at the timer interrupt rate
*/
void AP_TimerProcess::register_process(ap_procedure proc) void AP_TimerProcess::register_process(ap_procedure proc)
{ {
// see if its already registered (due to double initialisation
// of a driver)
for (uint8_t i=0; i<_pidx; i++) {
if (_proc[i] == proc) return;
}
if (_pidx < AP_TIMERPROCESS_MAX_PROCS) if (_pidx < AP_TIMERPROCESS_MAX_PROCS)
_proc[_pidx++] = proc; _proc[_pidx++] = proc;
} }