AP_HAL: Change the return type of 'peekiovec'

Possible values are '0', '1' and '2' so uint8_t is a better fit. Also,
invert 'if' condition so it's clear that is returning 0, 1 or 2.
This commit is contained in:
Murilo Belluzzo 2016-06-25 22:10:04 -03:00 committed by Lucas De Marchi
parent 625f47def7
commit 9951b94d40
2 changed files with 9 additions and 9 deletions

View File

@ -96,7 +96,7 @@ bool ByteBuffer::advance(uint32_t n)
return true;
}
int ByteBuffer::peekiovec(ByteBuffer::IoVec iovec[2], uint32_t len)
uint8_t ByteBuffer::peekiovec(ByteBuffer::IoVec iovec[2], uint32_t len)
{
if (len > available()) {
len = available();
@ -113,14 +113,14 @@ int ByteBuffer::peekiovec(ByteBuffer::IoVec iovec[2], uint32_t len)
iovec[0].data = const_cast<uint8_t *>(b);
iovec[0].len = n;
if (len > n) {
iovec[1].data = buf;
iovec[1].len = len - n;
return 2;
if (len <= n) {
return 1;
}
return 1;
iovec[1].data = buf;
iovec[1].len = len - n;
return 2;
}
/*

View File

@ -74,13 +74,13 @@ public:
uint32_t peekbytes(uint8_t *data, uint32_t len);
// Similar to peekbytes(), but will fill out IoVec struct with
// both parts of the ring buffer if wraparound is happpening, or
// both parts of the ring buffer if wraparound is happening, or
// just one part. Returns the number of parts written to.
struct IoVec {
uint8_t *data;
uint32_t len;
};
int peekiovec(IoVec vec[2], uint32_t len);
uint8_t peekiovec(IoVec vec[2], uint32_t len);
// Reserve `len` bytes and fills out `vec` with both parts of the
// ring buffer (if wraparound is happening), or just one contiguous