HAL_SITL: increase max timer procs

needed for compass learning
This commit is contained in:
Andrew Tridgell 2018-10-19 16:07:15 +11:00
parent 805647df85
commit 7e790a04d2
1 changed files with 1 additions and 1 deletions

View File

@ -6,7 +6,7 @@
#include <sys/time.h>
#include <pthread.h>
#define SITL_SCHEDULER_MAX_TIMER_PROCS 4
#define SITL_SCHEDULER_MAX_TIMER_PROCS 8
/* Scheduler implementation: */
class HALSITL::Scheduler : public AP_HAL::Scheduler {