mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
AP_HAL: BetterStream add a read(uint8_t*buffer, uint16_t count method
This commit is contained in:
parent
539e73e49c
commit
d259c03079
libraries/AP_HAL/utility
@ -19,3 +19,15 @@ size_t AP_HAL::BetterStream::write(const char *str)
|
||||
{
|
||||
return write((const uint8_t *)str, strlen(str));
|
||||
}
|
||||
|
||||
ssize_t AP_HAL::BetterStream::read(uint8_t *buffer, uint16_t count) {
|
||||
uint16_t offset = 0;
|
||||
while (count--) {
|
||||
const int16_t x = read();
|
||||
if (x == -1) {
|
||||
return offset;
|
||||
}
|
||||
buffer[offset++] = (uint8_t)x;
|
||||
}
|
||||
return offset;
|
||||
}
|
||||
|
@ -19,11 +19,12 @@
|
||||
//
|
||||
#pragma once
|
||||
|
||||
#include <stdarg.h>
|
||||
|
||||
#include <AP_Common/AP_Common.h>
|
||||
#include <AP_HAL/AP_HAL_Namespace.h>
|
||||
|
||||
#include <stdarg.h>
|
||||
#include <unistd.h>
|
||||
|
||||
class AP_HAL::BetterStream {
|
||||
public:
|
||||
|
||||
@ -48,6 +49,10 @@ public:
|
||||
// returns false if discard failed (e.g. port locked)
|
||||
virtual bool discard_input() = 0; // discard all bytes available for reading
|
||||
|
||||
// returns -1 on error (e.g. port locked), number of bytes read
|
||||
// otherwise
|
||||
virtual ssize_t read(uint8_t *buffer, uint16_t count);
|
||||
|
||||
/* NB txspace was traditionally a member of BetterStream in the
|
||||
* FastSerial library. As far as concerns go, it belongs with available() */
|
||||
virtual uint32_t txspace() = 0;
|
||||
|
Loading…
Reference in New Issue
Block a user