mirror of https://github.com/ArduPilot/ardupilot
timers: change to 1kHz timer by default
we were using a 227Hz timer, which is far too slow
This commit is contained in:
parent
6ad5df2958
commit
5b4717ea55
|
@ -5,8 +5,8 @@
|
|||
#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)
|
||||
// default to 1kHz timer interrupt
|
||||
#define TIMERPROCESS_PER_DEFAULT (256-62) // 1kHz
|
||||
|
||||
#define AP_TIMERPROCESS_MAX_PROCS 3
|
||||
|
||||
|
|
Loading…
Reference in New Issue