uart.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2017, James Jackson
3  *
4  * All rights reserved.
5  *
6  * Redistribution and use in source and binary forms, with or without
7  * modification, are permitted provided that the following conditions are met:
8  *
9  * * Redistributions of source code must retain the above copyright notice, this
10  * list of conditions and the following disclaimer.
11  *
12  * * Redistributions in binary form must reproduce the above copyright notice,
13  * this list of conditions and the following disclaimer in the documentation
14  * and/or other materials provided with the distribution.
15  *
16  * * Neither the name of the copyright holder nor the names of its
17  * contributors may be used to endorse or promote products derived from
18  * this software without specific prior written permission.
19  *
20  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
21  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
22  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
23  * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
24  * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
25  * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
26  * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
27  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
28  * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
29  * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
30  */
31 
32 #ifndef UART_H
33 #define UART_H
34 
35 // from serial.h
36 #include "gpio.h"
37 #include "serial.h"
38 #include "system.h"
39 
40 #include <functional>
41 
42 class UART : public Serial
43 {
44 public:
45  typedef enum
46  {
49  } uart_mode_t;
50 
51  UART();
52  void init(const uart_hardware_struct_t* conf, uint32_t baudrate_, uart_mode_t mode = MODE_8N1);
53 
54  void write(const uint8_t* ch, uint8_t len) override;
55  uint32_t rx_bytes_waiting() override;
56  uint32_t tx_bytes_free() override;
57  uint8_t read_byte() override;
58  bool set_mode(uint32_t baud, uart_mode_t mode);
59  bool tx_buffer_empty() override;
60  void put_byte(uint8_t ch) override;
61  bool flush() override;
62  void register_rx_callback(void (*cb)(uint8_t data)) override;
63  void unregister_rx_callback() override;
64 
65  void DMA_Tx_IRQ_callback();
66  void DMA_Rx_IRQ_callback();
67  void USART_IRQ_callback();
68 
69 private:
70  void init_UART(uint32_t baudrate_, uart_mode_t mode = MODE_8N1);
71  void init_DMA();
72  void init_NVIC();
73  void startDMA();
74 
75  const uart_hardware_struct_t* c_; // contains config information
76 
77  uint32_t baudrate_; // the baudrate for the connection
78  uint8_t rx_buffer_[RX_BUFFER_SIZE]; // the buffer for incoming data
79  uint8_t tx_buffer_[TX_BUFFER_SIZE]; // the buffer for outgoing data
80  uint16_t rx_buffer_head_;
81  uint16_t rx_buffer_tail_;
82  uint16_t tx_buffer_head_;
83  uint16_t tx_buffer_tail_;
84  GPIO rx_pin_; // The pin used for incoming data
85  GPIO tx_pin_; // The pin used for outgoing data
86 };
87 
88 #endif // UART_H
void init_UART(uint32_t baudrate_, uart_mode_t mode=MODE_8N1)
Definition: uart.cpp:65
bool tx_buffer_empty() override
Definition: uart.cpp:272
void init(const uart_hardware_struct_t *conf, uint32_t baudrate_, uart_mode_t mode=MODE_8N1)
Definition: uart.cpp:39
GPIO rx_pin_
Definition: uart.h:84
void register_rx_callback(void(*cb)(uint8_t data)) override
Definition: uart.cpp:319
#define TX_BUFFER_SIZE
Definition: serial.h:42
uint16_t tx_buffer_head_
Definition: uart.h:82
void DMA_Tx_IRQ_callback()
Definition: uart.cpp:310
bool flush() override
Definition: uart.cpp:277
void put_byte(uint8_t ch) override
Definition: uart.cpp:228
uint8_t rx_buffer_[RX_BUFFER_SIZE]
Definition: uart.h:78
uint16_t rx_buffer_tail_
Definition: uart.h:81
UART()
Definition: uart.cpp:37
uart_mode_t
Definition: uart.h:45
const uart_hardware_struct_t * c_
Definition: uart.h:75
uint8_t read_byte() override
Definition: uart.cpp:210
uint32_t tx_bytes_free() override
Definition: uart.cpp:254
void init_NVIC()
Definition: uart.cpp:156
void USART_IRQ_callback()
#define RX_BUFFER_SIZE
Definition: serial.h:41
void init_DMA()
Definition: uart.cpp:98
Definition: uart.h:42
uint16_t rx_buffer_head_
Definition: uart.h:80
uint8_t tx_buffer_[TX_BUFFER_SIZE]
Definition: uart.h:79
Definition: serial.h:44
uint32_t rx_bytes_waiting() override
Definition: uart.cpp:233
bool set_mode(uint32_t baud, uart_mode_t mode)
Definition: uart.cpp:266
void startDMA()
Definition: uart.cpp:188
Definition: gpio.h:37
void cb(uint8_t byte)
Definition: ublox.cpp:8
GPIO tx_pin_
Definition: uart.h:85
void DMA_Rx_IRQ_callback()
Definition: uart.cpp:288
uint16_t tx_buffer_tail_
Definition: uart.h:83
uint32_t baudrate_
Definition: uart.h:77
void write(const uint8_t *ch, uint8_t len) override
Definition: uart.cpp:173
void unregister_rx_callback() override
Definition: uart.cpp:324


rosflight_firmware
Author(s): Daniel Koch , James Jackson
autogenerated on Thu Apr 15 2021 05:07:49