AP_HAL: require a buffer write() function in all ports

this makes a sufficient performance difference that it is worth it
This commit is contained in:
Andrew Tridgell 2013-10-02 17:36:01 +10:00
parent 5489097476
commit efe1e01700
3 changed files with 9 additions and 12 deletions

View File

@ -15,6 +15,14 @@ public:
return 0; return 0;
} }
} }
size_t write(const uint8_t *buffer, size_t size) {
size_t n = 0;
while (size--) {
n += write(*buffer++);
}
return n;
}
size_t _offs; size_t _offs;
char* const _str; char* const _str;
const size_t _size; const size_t _size;

View File

@ -29,16 +29,6 @@
#include "Print.h" #include "Print.h"
using namespace AP_HAL; using namespace AP_HAL;
/* default implementation: may be overridden */
size_t Print::write_implementation(const uint8_t *buffer, size_t size)
{
size_t n = 0;
while (size--) {
n += write(*buffer++);
}
return n;
}
size_t Print::print(const char str[]) size_t Print::print(const char str[])
{ {
return write(str); return write(str);

View File

@ -49,10 +49,9 @@ class AP_HAL::Print {
Print() {} Print() {}
virtual size_t write(uint8_t) = 0; virtual size_t write(uint8_t) = 0;
virtual size_t write(const uint8_t *buffer, size_t size) = 0;
size_t write(const char *str) { return write((const uint8_t *)str, strlen(str)); } size_t write(const char *str) { return write((const uint8_t *)str, strlen(str)); }
size_t write(const uint8_t *buffer, size_t size) {return write_implementation(buffer, size);}
virtual size_t write_implementation(const uint8_t *buffer, size_t size);
public: public:
size_t print(const char[]); size_t print(const char[]);
size_t print(char); size_t print(char);