mirror of https://github.com/ArduPilot/ardupilot
AP_HAL: add and use a "bool read(c)" method to AP_HAL
this is much less likely to not work vs the int16_t equivalent
This commit is contained in:
parent
ec40a9641b
commit
394d70abe0
|
@ -66,7 +66,7 @@ public:
|
||||||
virtual size_t write_locked(const uint8_t *buffer, size_t size, uint32_t key) { return 0; }
|
virtual size_t write_locked(const uint8_t *buffer, size_t size, uint32_t key) { return 0; }
|
||||||
|
|
||||||
// read from a locked port. If port is locked and key is not correct then 0 is returned
|
// read from a locked port. If port is locked and key is not correct then 0 is returned
|
||||||
virtual int16_t read_locked(uint32_t key) { return -1; }
|
virtual bool read_locked(uint32_t key, uint8_t &b) WARN_IF_UNUSED { return -1; }
|
||||||
|
|
||||||
// control optional features
|
// control optional features
|
||||||
virtual bool set_options(uint16_t options) { _last_options = options; return options==0; }
|
virtual bool set_options(uint16_t options) { _last_options = options; return options==0; }
|
||||||
|
|
|
@ -36,7 +36,7 @@ public:
|
||||||
const size_t _size;
|
const size_t _size;
|
||||||
|
|
||||||
uint32_t available() override { return 0; }
|
uint32_t available() override { return 0; }
|
||||||
int16_t read() override { return -1; }
|
bool read(uint8_t &b) override { return false; }
|
||||||
uint32_t txspace() override { return 0; }
|
uint32_t txspace() override { return 0; }
|
||||||
bool discard_input() override { return false; }
|
bool discard_input() override { return false; }
|
||||||
};
|
};
|
||||||
|
|
|
@ -20,6 +20,15 @@ size_t AP_HAL::BetterStream::write(const char *str)
|
||||||
return write((const uint8_t *)str, strlen(str));
|
return write((const uint8_t *)str, strlen(str));
|
||||||
}
|
}
|
||||||
|
|
||||||
|
int16_t AP_HAL::BetterStream::read()
|
||||||
|
{
|
||||||
|
uint8_t b;
|
||||||
|
if (!read(b)) {
|
||||||
|
return -1;
|
||||||
|
}
|
||||||
|
return b;
|
||||||
|
}
|
||||||
|
|
||||||
ssize_t AP_HAL::BetterStream::read(uint8_t *buffer, uint16_t count) {
|
ssize_t AP_HAL::BetterStream::read(uint8_t *buffer, uint16_t count) {
|
||||||
uint16_t offset = 0;
|
uint16_t offset = 0;
|
||||||
while (count--) {
|
while (count--) {
|
||||||
|
|
|
@ -40,9 +40,8 @@ public:
|
||||||
|
|
||||||
virtual uint32_t available() = 0;
|
virtual uint32_t available() = 0;
|
||||||
|
|
||||||
/* return value for read():
|
int16_t read(); // old function; prefer calling the boolean method
|
||||||
* -1 if nothing available, uint8_t value otherwise. */
|
virtual bool read(uint8_t &b) WARN_IF_UNUSED = 0;
|
||||||
virtual int16_t read() = 0;
|
|
||||||
|
|
||||||
// no base-class implementation to force descendants to
|
// no base-class implementation to force descendants to
|
||||||
// do things efficiently. Looping over 2^32-1 bytes would be bad.
|
// do things efficiently. Looping over 2^32-1 bytes would be bad.
|
||||||
|
|
Loading…
Reference in New Issue