mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
AP_HAL: added readptr() and advance() to ObjectBuffer
this gives a more efficient way of accessing an ObjectBuffer, which reduces interrupt latency in SoftSigReader
This commit is contained in:
parent
e1385573b1
commit
9ea03e085d
@ -98,7 +98,11 @@ template <class T>
|
||||
class ObjectBuffer {
|
||||
public:
|
||||
ObjectBuffer(uint32_t _size) {
|
||||
buffer = new ByteBuffer((_size * sizeof(T))+1);
|
||||
// we set size to 1 more than requested as the byte buffer
|
||||
// gives one less byte than requested. We round up to a full
|
||||
// multiple of the object size so that we always get aligned
|
||||
// elements, which makes the readptr() method possible
|
||||
buffer = new ByteBuffer(((_size+1) * sizeof(T)));
|
||||
}
|
||||
~ObjectBuffer(void) {
|
||||
delete buffer;
|
||||
@ -188,6 +192,25 @@ public:
|
||||
return buffer->peekbytes((uint8_t*)&object, sizeof(T)) == sizeof(T);
|
||||
}
|
||||
|
||||
/*
|
||||
return a pointer to first contiguous array of available
|
||||
objects. Return nullptr if none available
|
||||
*/
|
||||
const T *readptr(uint32_t &n) {
|
||||
uint32_t avail_bytes = 0;
|
||||
const T *ret = (const T *)buffer->readptr(avail_bytes);
|
||||
if (!ret || avail_bytes < sizeof(T)) {
|
||||
return nullptr;
|
||||
}
|
||||
n = avail_bytes / sizeof(T);
|
||||
return ret;
|
||||
}
|
||||
|
||||
// advance the read pointer (discarding objects)
|
||||
bool advance(uint32_t n) {
|
||||
return buffer->advance(n * sizeof(T));
|
||||
}
|
||||
|
||||
/* update the object at the front of the queue (the one that would
|
||||
be fetched by pop()) */
|
||||
bool update(const T &object) {
|
||||
|
Loading…
Reference in New Issue
Block a user