mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 15:23:57 -04:00
AP_HAL: fixed get_size() on ObjectBuffer to be consistent with set_size()
This commit is contained in:
parent
3d03979b16
commit
90aed6f338
@ -128,7 +128,10 @@ public:
|
||||
}
|
||||
|
||||
// return size of ringbuffer
|
||||
uint32_t get_size(void) const { return buffer->get_size() / sizeof(T); }
|
||||
uint32_t get_size(void) const {
|
||||
uint32_t size = buffer->get_size() / sizeof(T);
|
||||
return size>0?size-1:0;
|
||||
}
|
||||
|
||||
// set size of ringbuffer, caller responsible for locking
|
||||
bool set_size(uint32_t size) { return buffer->set_size(((size+1) * sizeof(T))); }
|
||||
@ -288,7 +291,8 @@ public:
|
||||
// return size of ringbuffer
|
||||
uint32_t get_size(void) {
|
||||
WITH_SEMAPHORE(sem);
|
||||
return buffer->get_size() / sizeof(T);
|
||||
uint32_t size = buffer->get_size() / sizeof(T);
|
||||
return size>0?size-1:0;
|
||||
}
|
||||
|
||||
// set size of ringbuffer, caller responsible for locking
|
||||
@ -578,4 +582,4 @@ private:
|
||||
|
||||
typedef ObjectBuffer<float> FloatBuffer;
|
||||
typedef ObjectBuffer_TS<float> FloatBuffer_TS;
|
||||
typedef ObjectArray<float> FloatArray;
|
||||
typedef ObjectArray<float> FloatArray;
|
||||
|
Loading…
Reference in New Issue
Block a user