AP_HAL: added update() method for object ringbuffer

to support updating objects for GCS work Tom is doing
This commit is contained in:
Andrew Tridgell 2016-02-22 18:32:51 +11:00
parent 181b6f5c2e
commit 1df2512935
2 changed files with 35 additions and 1 deletions

View File

@ -66,6 +66,28 @@ uint32_t ByteBuffer::write(const uint8_t *data, uint32_t len)
return len;
}
/*
update bytes at the read pointer. Used to update an object without
popping it
*/
bool ByteBuffer::update(const uint8_t *data, uint32_t len)
{
if (len > available()) {
return false;
}
// perform as two memcpy calls
uint32_t n = size - head;
if (n > len) {
n = len;
}
memcpy(&buf[head], data, n);
data += n;
if (len > n) {
memcpy(&buf[0], data, len-n);
}
return true;
}
bool ByteBuffer::advance(uint32_t n)
{
if (n > available()) {

View File

@ -46,6 +46,12 @@ public:
// read bytes from ringbuffer. Returns number of bytes read
uint32_t read(uint8_t *data, uint32_t len);
/*
update bytes at the read pointer. Used to update an object without
popping it
*/
bool update(const uint8_t *data, uint32_t len);
// return size of ringbuffer
uint32_t get_size(void) const { return size; }
@ -110,7 +116,7 @@ public:
}
return buffer->write((uint8_t*)&object, sizeof(T)) == sizeof(T);
}
/*
throw away an object
*/
@ -146,6 +152,12 @@ public:
bool peek(T &object) {
return peekbytes(&object, sizeof(T)) == sizeof(T);
}
/* update the object at the front of the queue (the one that would
be fetched by pop()) */
bool update(const T &object) {
return buffer->update((uint8_t*)&object, sizeof(T));
}
private:
ByteBuffer *buffer = nullptr;