mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_HAL: check for null buffer in ObjectBuffer get_size()
This commit is contained in:
parent
41de8286ef
commit
a14c5b2955
@ -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;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user