Browse Source

HAL_VRBRAIN: removed restriction on delay in threads

threads other than the main thread should be able to sleep, but not
call the delay callback
mission-4.1.18
Andrew Tridgell 7 years ago
parent
commit
3cd6d8cac7
  1. 6
      libraries/AP_HAL_VRBRAIN/Scheduler.cpp

6
libraries/AP_HAL_VRBRAIN/Scheduler.cpp

@ -173,17 +173,13 @@ void VRBRAINScheduler::delay_microseconds_boost(uint16_t usec) @@ -173,17 +173,13 @@ void VRBRAINScheduler::delay_microseconds_boost(uint16_t usec)
void VRBRAINScheduler::delay(uint16_t ms)
{
if (!in_main_thread()) {
::printf("ERROR: delay() from timer process\n");
return;
}
perf_begin(_perf_delay);
uint64_t start = AP_HAL::micros64();
while ((AP_HAL::micros64() - start)/1000 < ms &&
!_vrbrain_thread_should_exit) {
delay_microseconds_semaphore(1000);
if (_min_delay_cb_ms <= ms) {
if (in_main_thread() && _min_delay_cb_ms <= ms) {
call_delay_cb();
}
}

Loading…
Cancel
Save