mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-08 17:03:57 -04:00
AP_HAL: check for null buffer in ObjectBuffer get_size()
This commit is contained in:
parent
da4a9297a0
commit
0998bdc057
@ -129,6 +129,9 @@ public:
|
|||||||
|
|
||||||
// return size of ringbuffer
|
// return size of ringbuffer
|
||||||
uint32_t get_size(void) const {
|
uint32_t get_size(void) const {
|
||||||
|
if (buffer == nullptr) {
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
uint32_t size = buffer->get_size() / sizeof(T);
|
uint32_t size = buffer->get_size() / sizeof(T);
|
||||||
return size>0?size-1:0;
|
return size>0?size-1:0;
|
||||||
}
|
}
|
||||||
@ -291,6 +294,9 @@ public:
|
|||||||
// return size of ringbuffer
|
// return size of ringbuffer
|
||||||
uint32_t get_size(void) {
|
uint32_t get_size(void) {
|
||||||
WITH_SEMAPHORE(sem);
|
WITH_SEMAPHORE(sem);
|
||||||
|
if (buffer == nullptr) {
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
uint32_t size = buffer->get_size() / sizeof(T);
|
uint32_t size = buffer->get_size() / sizeof(T);
|
||||||
return size>0?size-1:0;
|
return size>0?size-1:0;
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user