APM:Libraries
UART_PPM.h
Go to the documentation of this file.
1 /*
2  * UART_PPM.cpp --- fake UART to get serial data from PPM inputs
3  *
4  */
5 
6 #pragma once
7 
8 #include "AP_HAL_F4Light.h"
9 #include "Scheduler.h"
10 #include <AP_HAL/UARTDriver.h>
11 
12 
13 #define USART_PPM_BUF_SIZE 256
14 
15 
17 public:
18  UART_PPM(uint8_t n);
19 
20  /* F4Light implementations of UARTDriver virtual methods */
21  void begin(uint32_t b);
22  void inline begin(uint32_t b, uint16_t rxS, uint16_t txS) { begin(b); }
23  void inline end() { }
24  void flush() {}
25  bool inline is_initialized(){ return _initialized; }
26 
27  inline void set_blocking_writes(bool blocking) { _blocking = blocking; }
28 
29  inline bool tx_pending() { return 0; }
30 
31  uint32_t available() override;
32  int16_t read() override;
33 
34  uint32_t inline txspace() override { return 0; } // can't TX
35  size_t write(uint8_t c) { return 1; }
36  size_t write(const uint8_t *buffer, size_t size) { return size; }
37 
38  static void putch(uint8_t c, uint8_t n);
39 
40 private:
41 
43  bool _blocking;
44  uint8_t _id;
45 
46  static ring_buffer ppm_rxrb[2] IN_CCM;
47  static uint8_t rx_buf[2][USART_PPM_BUF_SIZE] IN_CCM;
48 
49 };
50 
51 
uint32_t available() override
Definition: UART_PPM.cpp:44
void begin(uint32_t b)
Definition: UART_PPM.cpp:37
static uint8_t buffer[SRXL_FRAMELEN_MAX]
Definition: srxl.cpp:56
static uint8_t rx_buf [2][USART_PPM_BUF_SIZE] IN_CCM
Definition: UART_PPM.h:47
bool tx_pending()
Definition: UART_PPM.h:29
size_t write(uint8_t c)
Definition: UART_PPM.h:35
void set_blocking_writes(bool blocking)
Definition: UART_PPM.h:27
bool is_initialized()
Definition: UART_PPM.h:25
int16_t read() override
Definition: UART_PPM.cpp:48
static void putch(uint8_t c, uint8_t n)
Definition: UART_PPM.cpp:53
static uint8_t rx_buf[USB_RXFIFO_SIZE]
Definition: usb.c:60
uint32_t txspace() override
Definition: UART_PPM.h:34
#define USART_PPM_BUF_SIZE
Definition: UART_PPM.h:13
size_t write(const uint8_t *buffer, size_t size)
Definition: UART_PPM.h:36
UART_PPM(uint8_t n)
Definition: UART_PPM.cpp:29
void begin(uint32_t b, uint16_t rxS, uint16_t txS)
Definition: UART_PPM.h:22
static ring_buffer ppm_rxrb [2] IN_CCM
Definition: UART_PPM.h:46