timer: enable interrupts during timer processing
this prevents us losing serial bytes when we call sensor drivers that take more than 100usec to read. We also prevent timer recursion by re-enabling the timer after all callbacks are complete
This commit is contained in:
parent
af7e34fcc1
commit
be1ba5354e
@ -5,6 +5,7 @@ extern "C" {
|
|||||||
#include <inttypes.h>
|
#include <inttypes.h>
|
||||||
#include <stdint.h>
|
#include <stdint.h>
|
||||||
#include "WConstants.h"
|
#include "WConstants.h"
|
||||||
|
#include <avr/interrupt.h>
|
||||||
}
|
}
|
||||||
|
|
||||||
int AP_TimerProcess::_period;
|
int AP_TimerProcess::_period;
|
||||||
@ -40,9 +41,17 @@ void AP_TimerProcess::register_process(void (*proc)(void) )
|
|||||||
|
|
||||||
void AP_TimerProcess::run(void)
|
void AP_TimerProcess::run(void)
|
||||||
{
|
{
|
||||||
TCNT2 = _period;
|
// we re-enable interrupts here as some of these functions
|
||||||
for (int i = 0; i < _pidx; i++) {
|
// take a long time, and we don't want to block other critical
|
||||||
if (_proc[i] != NULL)
|
// interrupts, especially the serial interrupt
|
||||||
_proc[i]();
|
sei();
|
||||||
}
|
|
||||||
|
for (int i = 0; i < _pidx; i++) {
|
||||||
|
if (_proc[i] != NULL)
|
||||||
|
_proc[i]();
|
||||||
|
}
|
||||||
|
|
||||||
|
// to prevent recursion, we don't enable the timer interrupt
|
||||||
|
// again until we've completed the tasks
|
||||||
|
TCNT2 = _period;
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user