AP_Scheduler: allow SCHED_LOOP_RATE for copter in SITL

very useful for slow simulation environment
This commit is contained in:
Andrew Tridgell 2016-06-05 11:20:09 +10:00
parent 95e9c1fd97
commit fb4cdafef8
1 changed files with 5 additions and 0 deletions

View File

@ -28,9 +28,14 @@
#if APM_BUILD_TYPE(APM_BUILD_ArduCopter) #if APM_BUILD_TYPE(APM_BUILD_ArduCopter)
#define SCHEDULER_DEFAULT_LOOP_RATE 400 #define SCHEDULER_DEFAULT_LOOP_RATE 400
#if CONFIG_HAL_BOARD != HAL_BOARD_SITL
#define SCHEDULER_EXPOSE_LOOP_RATE_PARAMETER 0 #define SCHEDULER_EXPOSE_LOOP_RATE_PARAMETER 0
#endif
#else #else
#define SCHEDULER_DEFAULT_LOOP_RATE 50 #define SCHEDULER_DEFAULT_LOOP_RATE 50
#endif
#ifndef SCHEDULER_EXPOSE_LOOP_RATE_PARAMETER
#define SCHEDULER_EXPOSE_LOOP_RATE_PARAMETER 1 #define SCHEDULER_EXPOSE_LOOP_RATE_PARAMETER 1
#endif #endif