ardupilot/libraries/AP_PeriodicProcess/AP_TimerProcess.h
Andrew Tridgell b484411c41 timers: change to 1kHz timer by default
we were using a 227Hz timer, which is far too slow
2011-12-16 20:09:25 +11:00

27 lines
719 B
C++

#ifndef __AP_TIMERPROCESS_H__
#define __AP_TIMERPROCESS_H__
#include "PeriodicProcess.h"
#include "../Arduino_Mega_ISR_Registry/Arduino_Mega_ISR_Registry.h"
// default to 1kHz timer interrupt
#define TIMERPROCESS_PER_DEFAULT (256-62) // 1kHz
#define AP_TIMERPROCESS_MAX_PROCS 3
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 ap_procedure _proc[AP_TIMERPROCESS_MAX_PROCS];
static int _pidx;
};
#endif // __AP_TIMERPROCESS_H__