mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
AP_HAL: ringbuffer get_size cannot be const because of semaphore
This commit is contained in:
parent
940d708438
commit
ad895c2654
@ -267,7 +267,7 @@ public:
|
|||||||
}
|
}
|
||||||
|
|
||||||
// return size of ringbuffer
|
// return size of ringbuffer
|
||||||
uint32_t get_size(void) const {
|
uint32_t get_size(void) {
|
||||||
WITH_SEMAPHORE(sem);
|
WITH_SEMAPHORE(sem);
|
||||||
return buffer->get_size() / sizeof(T);
|
return buffer->get_size() / sizeof(T);
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user