AP_HAL: check for null buffer in ObjectBuffer get_size()

This commit is contained in:
Andrew Tridgell 2023-01-02 08:54:16 +11:00
parent 41de8286ef
commit a14c5b2955

View File

@ -129,6 +129,9 @@ public:
// return size of ringbuffer
uint32_t get_size(void) const {
if (buffer == nullptr) {
return 0;
}
uint32_t size = buffer->get_size() / sizeof(T);
return size>0?size-1:0;
}
@ -291,6 +294,9 @@ public:
// return size of ringbuffer
uint32_t get_size(void) {
WITH_SEMAPHORE(sem);
if (buffer == nullptr) {
return 0;
}
uint32_t size = buffer->get_size() / sizeof(T);
return size>0?size-1:0;
}