AP_Logger: do not use AP_Scheduler for AP_Periph builds

This commit is contained in:
bugobliterator 2021-08-11 19:11:18 +05:30 committed by Andrew Tridgell
parent 1db7e9e2e2
commit 6bbfe35c73

View File

@ -674,6 +674,7 @@ bool AP_Logger_RateLimiter::should_log(uint8_t msgid)
} }
} }
#if !defined(HAL_BUILD_AP_PERIPH)
// if we've already decided on sending this msgid in this tick then use the // if we've already decided on sending this msgid in this tick then use the
// same decision again // same decision again
const uint16_t sched_ticks = AP::scheduler().ticks(); const uint16_t sched_ticks = AP::scheduler().ticks();
@ -681,6 +682,7 @@ bool AP_Logger_RateLimiter::should_log(uint8_t msgid)
return last_return.get(msgid); return last_return.get(msgid);
} }
last_sched_count[msgid] = sched_ticks; last_sched_count[msgid] = sched_ticks;
#endif
bool ret = should_log_streaming(msgid); bool ret = should_log_streaming(msgid);
if (ret) { if (ret) {