Browse Source
this library provides a clean API for drivers to request periodic timer driven calls at whatever rate they needmaster
Pat Hickey
13 years ago
6 changed files with 144 additions and 0 deletions
@ -0,0 +1,9 @@ |
|||||||
|
|
||||||
|
#ifndef __AP_PERIODIC_PROCESS_H__ |
||||||
|
#define __AP_PERIODIC_PROCESS_H__ |
||||||
|
|
||||||
|
#include "PeriodicProcess.h" |
||||||
|
#include "AP_TimerProcess.h" |
||||||
|
#include "AP_TimerAperiodicProcess.h" |
||||||
|
|
||||||
|
#endif // __AP_PERIODIC_PROCESS_H__
|
@ -0,0 +1,39 @@ |
|||||||
|
|
||||||
|
#include "AP_TimerAperiodicProcess.h" |
||||||
|
|
||||||
|
extern "C" { |
||||||
|
#include <inttypes.h> |
||||||
|
#include <stdint.h> |
||||||
|
#include "WConstants.h" |
||||||
|
} |
||||||
|
// TCNT2 values for various interrupt rates,
|
||||||
|
// assuming 256 prescaler. Note that these values
|
||||||
|
// assume a zero-time ISR. The actual rate will be a
|
||||||
|
// bit lower than this
|
||||||
|
#define TCNT2_781_HZ (256-80) |
||||||
|
#define TCNT2_1008_HZ (256-62) |
||||||
|
#define TCNT2_1302_HZ (256-48) |
||||||
|
|
||||||
|
uint8_t AP_TimerAperiodicProcess::_timer_offset; |
||||||
|
|
||||||
|
void AP_TimerAperiodicProcess::init( Arduino_Mega_ISR_Registry * isr_reg ) |
||||||
|
{ |
||||||
|
// Enable Timer2 Overflow interrupt to trigger process.
|
||||||
|
TIMSK2 = 0; // Disable interrupts
|
||||||
|
TCCR2A = 0; // normal counting mode
|
||||||
|
TCCR2B = _BV(CS21) | _BV(CS22); // Set prescaler of clk/256
|
||||||
|
TCNT2 = 0; // Set count to zero, so it goes off right away.
|
||||||
|
TIFR2 = _BV(TOV2); // clear pending interrupts;
|
||||||
|
TIMSK2 = _BV(TOIE2); // enable the overflow interrupt
|
||||||
|
|
||||||
|
isr_reg->register_signal(ISR_REGISTRY_TIMER2_OVF, AP_TimerAperiodicProcess::run); |
||||||
|
} |
||||||
|
|
||||||
|
void AP_TimerAperiodicProcess::run(void) |
||||||
|
{ |
||||||
|
_timer_offset = (_timer_offset + 49) % 32; |
||||||
|
_period = TCNT2_781_HZ + _timer_offset; |
||||||
|
TCNT2 = _period; |
||||||
|
if (_proc != NULL) |
||||||
|
_proc(); |
||||||
|
} |
@ -0,0 +1,19 @@ |
|||||||
|
|
||||||
|
#ifndef __AP_TIMER_APERIODIC_PROCESS_H__ |
||||||
|
#define __AP_TIMER_APERIODIC_PROCESS_H__ |
||||||
|
|
||||||
|
#include <stdint.h> |
||||||
|
|
||||||
|
#include "../Arduino_Mega_ISR_Registry/Arduino_Mega_ISR_Registry.h" |
||||||
|
#include "AP_TimerProcess.h" |
||||||
|
|
||||||
|
class AP_TimerAperiodicProcess : public AP_TimerProcess |
||||||
|
{ |
||||||
|
public: |
||||||
|
void init( Arduino_Mega_ISR_Registry * isr_reg ); |
||||||
|
static void run(void); |
||||||
|
private: |
||||||
|
static uint8_t _timer_offset; |
||||||
|
}; |
||||||
|
|
||||||
|
#endif // __AP_TIMER_APERIODIC_PROCESS_H__
|
@ -0,0 +1,43 @@ |
|||||||
|
|
||||||
|
#include "AP_TimerProcess.h" |
||||||
|
|
||||||
|
extern "C" { |
||||||
|
#include <inttypes.h> |
||||||
|
#include <stdint.h> |
||||||
|
#include "WConstants.h" |
||||||
|
} |
||||||
|
|
||||||
|
int AP_TimerProcess::_period; |
||||||
|
void (*AP_TimerProcess::_proc)(void); |
||||||
|
|
||||||
|
AP_TimerProcess::AP_TimerProcess(int period) |
||||||
|
{ |
||||||
|
_period = period; |
||||||
|
_proc = NULL; |
||||||
|
} |
||||||
|
|
||||||
|
void AP_TimerProcess::init( Arduino_Mega_ISR_Registry * isr_reg ) |
||||||
|
{ |
||||||
|
// Enable Timer2 Overflow interrupt to trigger process.
|
||||||
|
TIMSK2 = 0; // Disable interrupts
|
||||||
|
TCCR2A = 0; // normal counting mode
|
||||||
|
TCCR2B = _BV(CS21) | _BV(CS22); // Set prescaler of clk/256
|
||||||
|
TCNT2 = 0; // Set count to zero, so it goes off right away.
|
||||||
|
TIFR2 = _BV(TOV2); // clear pending interrupts;
|
||||||
|
TIMSK2 = _BV(TOIE2); // enable the overflow interrupt
|
||||||
|
|
||||||
|
isr_reg->register_signal( ISR_REGISTRY_TIMER2_OVF, AP_TimerProcess::run); |
||||||
|
} |
||||||
|
|
||||||
|
void AP_TimerProcess::register_process(void (*proc)(void) ) |
||||||
|
{ |
||||||
|
_proc = proc; |
||||||
|
TCNT2 = 1; // Should go off almost immediately.
|
||||||
|
} |
||||||
|
|
||||||
|
void AP_TimerProcess::run(void) |
||||||
|
{ |
||||||
|
TCNT2 = _period; |
||||||
|
if (_proc != NULL) |
||||||
|
_proc(); |
||||||
|
} |
@ -0,0 +1,23 @@ |
|||||||
|
|
||||||
|
#ifndef __AP_TIMERPROCESS_H__ |
||||||
|
#define __AP_TIMERPROCESS_H__ |
||||||
|
|
||||||
|
#include "PeriodicProcess.h" |
||||||
|
#include "../Arduino_Mega_ISR_Registry/Arduino_Mega_ISR_Registry.h" |
||||||
|
|
||||||
|
/* XXX this value is a total guess, will look up. */ |
||||||
|
#define TIMERPROCESS_PER_DEFAULT (256) |
||||||
|
|
||||||
|
class AP_TimerProcess : public AP_PeriodicProcess |
||||||
|
{ |
||||||
|
public: |
||||||
|
AP_TimerProcess(int period = TIMERPROCESS_PER_DEFAULT); |
||||||
|
void init( Arduino_Mega_ISR_Registry * isr_reg ); |
||||||
|
void register_process(void (* proc)(void)); |
||||||
|
static void run(void); |
||||||
|
protected: |
||||||
|
static int _period; |
||||||
|
static void (*_proc)(void); |
||||||
|
}; |
||||||
|
|
||||||
|
#endif // __AP_TIMERPROCESS_H__
|
Loading…
Reference in new issue