Browse Source

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

this makes a sufficient performance difference that it is worth it
mission-4.1.18
Andrew Tridgell 12 years ago
parent
commit
efe1e01700
  1. 8
      libraries/AP_HAL/Util.cpp
  2. 10
      libraries/AP_HAL/utility/Print.cpp
  3. 3
      libraries/AP_HAL/utility/Print.h

8
libraries/AP_HAL/Util.cpp

@ -15,6 +15,14 @@ public: @@ -15,6 +15,14 @@ public:
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;
char* const _str;
const size_t _size;

10
libraries/AP_HAL/utility/Print.cpp

@ -29,16 +29,6 @@ @@ -29,16 +29,6 @@
#include "Print.h"
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[])
{
return write(str);

3
libraries/AP_HAL/utility/Print.h

@ -49,10 +49,9 @@ class AP_HAL::Print { @@ -49,10 +49,9 @@ class AP_HAL::Print {
Print() {}
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 uint8_t *buffer, size_t size) {return write_implementation(buffer, size);}
virtual size_t write_implementation(const uint8_t *buffer, size_t size);
public:
size_t print(const char[]);
size_t print(char);

Loading…
Cancel
Save