mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_Scheduler: allow SCHED_LOOP_RATE for copter in SITL
very useful for slow simulation environment
This commit is contained in:
parent
95e9c1fd97
commit
fb4cdafef8
@ -28,9 +28,14 @@
|
||||
|
||||
#if APM_BUILD_TYPE(APM_BUILD_ArduCopter)
|
||||
#define SCHEDULER_DEFAULT_LOOP_RATE 400
|
||||
#if CONFIG_HAL_BOARD != HAL_BOARD_SITL
|
||||
#define SCHEDULER_EXPOSE_LOOP_RATE_PARAMETER 0
|
||||
#endif
|
||||
#else
|
||||
#define SCHEDULER_DEFAULT_LOOP_RATE 50
|
||||
#endif
|
||||
|
||||
#ifndef SCHEDULER_EXPOSE_LOOP_RATE_PARAMETER
|
||||
#define SCHEDULER_EXPOSE_LOOP_RATE_PARAMETER 1
|
||||
#endif
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user