APM:Libraries
BetterStream.cpp
Go to the documentation of this file.
1 #include "BetterStream.h"
2 
3 #include "print_vprintf.h"
4 
5 void AP_HAL::BetterStream::printf(const char *fmt, ...)
6 {
7  va_list ap;
8  va_start(ap, fmt);
9  vprintf(fmt, ap);
10  va_end(ap);
11 }
12 
13 void AP_HAL::BetterStream::vprintf(const char *fmt, va_list ap)
14 {
15  print_vprintf(this, fmt, ap);
16 }
17 
18 size_t AP_HAL::BetterStream::write(const uint8_t *buffer, size_t size)
19 {
20  for (size_t i=0; i<size;i++) {
21  if (write(buffer[i] == 0)) {
22  return i;
23  }
24  };
25  return size;
26 }
27 
28 size_t AP_HAL::BetterStream::write(const char *str)
29 {
30  return write((const uint8_t *)str, strlen(str));
31 }
static uint8_t buffer[SRXL_FRAMELEN_MAX]
Definition: srxl.cpp:56
virtual void printf(const char *,...) FMT_PRINTF(2
Definition: BetterStream.cpp:5
const char * fmt
Definition: Printf.cpp:14
virtual size_t write(uint8_t)=0
virtual void virtual void vprintf(const char *, va_list)