mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
HAL_Empty: implement a dummy buffered write
This commit is contained in:
parent
c035eef845
commit
a8c97f99d1
@ -40,3 +40,12 @@ size_t EmptyConsoleDriver::write(uint8_t c) {
|
||||
return _d->write(c);
|
||||
}
|
||||
|
||||
|
||||
size_t EmptyConsoleDriver::write(const uint8_t *buffer, size_t size)
|
||||
{
|
||||
size_t n = 0;
|
||||
while (size--) {
|
||||
n += write(*buffer++);
|
||||
}
|
||||
return n;
|
||||
}
|
||||
|
@ -18,6 +18,7 @@ public:
|
||||
int16_t read();
|
||||
|
||||
size_t write(uint8_t c);
|
||||
size_t write(const uint8_t *buffer, size_t size);
|
||||
private:
|
||||
AP_HAL::BetterStream *_d;
|
||||
};
|
||||
|
@ -20,3 +20,12 @@ int16_t EmptyUARTDriver::read() { return -1; }
|
||||
|
||||
/* Empty implementations of Print virtual methods */
|
||||
size_t EmptyUARTDriver::write(uint8_t c) { return 0; }
|
||||
|
||||
size_t EmptyUARTDriver::write(const uint8_t *buffer, size_t size)
|
||||
{
|
||||
size_t n = 0;
|
||||
while (size--) {
|
||||
n += write(*buffer++);
|
||||
}
|
||||
return n;
|
||||
}
|
||||
|
@ -23,6 +23,7 @@ public:
|
||||
|
||||
/* Empty implementations of Print virtual methods */
|
||||
size_t write(uint8_t c);
|
||||
size_t write(const uint8_t *buffer, size_t size);
|
||||
};
|
||||
|
||||
#endif // __AP_HAL_EMPTY_UARTDRIVER_H__
|
||||
|
Loading…
Reference in New Issue
Block a user