APM:Libraries
UART_OSD.h
Go to the documentation of this file.
1 /*
2  * UART_OSD.cpp --- AP_HAL_F4Light OSD implementation via fake UART
3  *
4  */
5 
6 #pragma once
7 
9 
10 #include <gpio_hal.h>
11 #include "Scheduler.h"
12 #include "osd/osd.h"
13 
14 
15 
17 public:
18  UART_OSD();
19 
20  void begin(uint32_t b);
21  void inline begin(uint32_t b, uint16_t rxS, uint16_t txS) { begin(b); }
22  void inline end() { } // no way to unview
23  void flush() {}
24  bool inline is_initialized(){ return _initialized; }
25 
26  inline void set_blocking_writes(bool blocking) { _blocking = blocking; }
27 
28  inline bool tx_pending() { return 0; }
29 
30  uint32_t available() override;
31  uint32_t txspace() override;
32  int16_t read() override;
33 
34  size_t write(uint8_t c);
35  size_t write(const uint8_t *buffer, size_t size);
36 
37 private:
38 
40  bool _blocking;
41 };
42 
43 
void set_blocking_writes(bool blocking)
Definition: UART_OSD.h:26
static uint8_t buffer[SRXL_FRAMELEN_MAX]
Definition: srxl.cpp:56
void begin(uint32_t b, uint16_t rxS, uint16_t txS)
Definition: UART_OSD.h:21
void begin(uint32_t b)
bool tx_pending()
Definition: UART_OSD.h:28
size_t write(uint8_t c)
bool is_initialized()
Definition: UART_OSD.h:24
uint32_t available() override
uint32_t txspace() override
int16_t read() override