mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Logger: do not use AP_Scheduler for AP_Periph builds
This commit is contained in:
parent
1db7e9e2e2
commit
6bbfe35c73
@ -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) {
|
||||||
|
Loading…
Reference in New Issue
Block a user