APM:Libraries
UARTDriver.h
Go to the documentation of this file.
1 
2 #pragma once
3 
5 
6 #include <usart.h>
7 
8 #include <gpio_hal.h>
9 #include <hal.h>
10 #include "Scheduler.h"
11 
12 #define DEFAULT_TX_TIMEOUT 10000 // in uS - 10ms
13 
15  UART_Stop_Bits_1 = ((uint16_t)0x0000),
16  UART_Stop_Bits_0_5= ((uint16_t)0x1000),
17  UART_Stop_Bits_2 = ((uint16_t)0x2000),
18  UART_Stop_Bits_1_5= ((uint16_t)0x3000),
19 };
20 
22  UART_Parity_No = ((uint16_t)0x0000),
23  UART_Parity_Even = ((uint16_t)0x0400),
24  UART_Parity_Odd = ((uint16_t)0x0600),
25 };
26 
28 public:
29  UARTDriver(const struct usart_dev *usart);
30 
31  inline void begin(uint32_t b){
33  }
34 
35  void begin(uint32_t b, uint32_t mode); // must be
36  inline void begin(uint32_t b, uint16_t rxS, uint16_t txS) { begin(b); }
37  inline void end() { _initialized=false; if(_usart_device) usart_disable(_usart_device); }
38  void flush();
39  inline bool is_initialized(){ return _initialized; }
40 
41  inline void set_blocking_writes(bool blocking) { _blocking = blocking; }
42 
43  inline bool tx_pending() { return usart_txfifo_nbytes(_usart_device) > 0; }
44 
46 
47  uint32_t available() override;
48  uint32_t inline txspace() override { return usart_txfifo_freebytes(_usart_device); }
49  int16_t read() override;
50 
51  size_t write(uint8_t c);
52  size_t write(const uint8_t *buffer, size_t size);
53 
54  inline void disable(){ _usart_device = NULL; } // pins used for another needs
55 
56  uint64_t receive_time_constraint_us(uint16_t nbytes) override;
57 
58  void update_timestamp();
59 
60 private:
61 
62  const struct usart_dev *_usart_device;
64  bool _blocking;
65  uint32_t _baudrate;
66  uint32_t _receive_timestamp[2];
67  uint8_t _time_idx;
68 };
69 
70 
size_t write(uint8_t c)
Definition: UARTDriver.cpp:110
uint32_t _baudrate
Definition: UARTDriver.h:65
static uint32_t usart_txfifo_nbytes(const usart_dev *dev)
Definition: usart.h:195
static uint8_t buffer[SRXL_FRAMELEN_MAX]
Definition: srxl.cpp:56
UART_PARITY
Definition: UARTDriver.h:21
uint64_t receive_time_constraint_us(uint16_t nbytes) override
Definition: UARTDriver.cpp:152
void begin(uint32_t b, uint16_t rxS, uint16_t txS)
Definition: UARTDriver.h:36
void begin(uint32_t b)
Definition: UARTDriver.h:31
void setCallback(Handler cb)
Definition: UARTDriver.h:45
int16_t read() override
Definition: UARTDriver.cpp:103
static void usart_set_callback(const usart_dev *dev, Handler cb)
Definition: usart.h:304
#define NULL
Definition: hal_types.h:59
uint32_t available() override
Definition: UARTDriver.cpp:94
const struct usart_dev * _usart_device
Definition: UARTDriver.h:62
UART_STOP_BITS
Definition: UARTDriver.h:14
static void usart_disable(const usart_dev *dev)
Turn off a serial port.
Definition: usart.h:180
uint32_t txspace() override
Definition: UARTDriver.h:48
uint64_t Handler
Definition: hal_types.h:19
void set_blocking_writes(bool blocking)
Definition: UARTDriver.h:41
uint32_t _receive_timestamp[2]
Definition: UARTDriver.h:66
static uint32_t usart_txfifo_freebytes(const usart_dev *dev)
Definition: usart.h:198