APM:Libraries
UART_SoftDriver.h
Go to the documentation of this file.
1 // inspired by AN4655
2 // http://www.st.com/content/ccc/resource/technical/document/application_note/3d/80/91/f9/4c/25/4a/26/DM00160482.pdf/files/DM00160482.pdf/jcr:content/translations/en.DM00160482.pdf
3 // last in page http://www.st.com/content/st_com/en/products/microcontrollers/stm32-32-bit-arm-cortex-mcus/stm32l0-series/stm32l0x2/stm32l052c6.html
4 /*
5 
6 This example shows how to control both transmit and receive processes by software, based on HW events.
7 
8 Overflow and IO capture events of a single Capture & Compare timer is used to control timing of emulation of UART input sampling and
9  output handling of the Rx and Tx signals. The associated input capture pin is dedicated to receive data. Any general-purpose output
10 pin or associated output compare pin can be used for data transmission. The timer overflow period is set to the channel half bit rate
11 by setting the timer auto reload register.
12 
13 illustrates the timing diagram.
14 
15 Figure 3. UART duplex channel based on timer capture events
16 
17 Transmission process control is based on regular interrupts from the timer overflow events.
18 After data for transmission is stored into dedicated variable (transmit buffer simulated by SW), an internal transmission request appears and
19  the nearest overflow interrupt is used to start a new transmission (maximum latency for transmission start could be half a bit period).
20 This is because the same timer is used for control both transmit and receive processes not synchronized normally. Every even timer overflow
21  event interrupt controls the consecutive edge changes of the transmitted signal on the dedicated output pin until the end of the frame
22 transmission. Odd overflow interrupts are discarded.
23 
24 The receive process uses both input capture and output compare feature of the same timer and its dedicated pin.
25 Initially, the input capture is performed at the pin. After detecting the first falling edge, the value captured in the
26 capture register is then used for compare purposes because the input pin functionality is switched to output compare mode (without
27 affecting any output GPIO capability since the pin still stays in input mode). Due to the half-a-bit overflow period of the timer, the nearest
28  output compare event points to the middle of the first receive bit (start bit). Sampling can be simulated by three consecutive reading of the
29 input pin level at that moment and if, for each of them, a low level is detected, the correctly received start bit is evaluated. The receive
30 process then continues by watching every next odd output compare event. The same three point sampling method can be performed with noise
31 detection logic here and for all the other received data bits until the end of the current receive frame. All even compare interrupts are
32 discarded. After the stop bits of the frame are sampled, the Rx pin is switched back to input capture mode and waits for the next frame
33 start condition. The detection of noise while the stop bits are being sampled should cause a frame error. If a noise is detected during start
34 bit, the receive process should be aborted and the Rx pin switched back to input capture mode while waiting for the next falling edge capture.
35 
36 User can build an API interface upon this low level HW abstraction level. It can include the UART channel initialization, enable and disabl
37 e Rx and Tx channels, read and write the data flow (e.g. control the data buffers) and check the transactions’ status. Size of data, parity
38 control number of stop bits or other control can be solved on pre-compilation level by conditional compilation to speed up the code when
39 these features are not used.
40 
41 
42 (C)
43 
44 in case of RevoMini we have pins
45 
46  14, // PC8 T8/3 - Soft_scl or soft_tx
47  15, // PC9 T8/4 - Soft_sda or soft_rx
48 
49 */
50 
51 #pragma once
52 
53 #if defined(BOARD_SOFTSERIAL_RX) && defined(BOARD_SOFTSERIAL_TX)
54 
56 
57 #include <usart.h>
58 #include <gpio_hal.h>
59 #include <pwm_in.h>
60 #include "Scheduler.h"
61 #include "GPIO.h"
62 
63 #define DEFAULT_TX_TIMEOUT 10000
64 
65 #define SS_DEBUG
66 
67 #define SSI_RX_BUFF_SIZE 64
68 #define SSI_TX_BUFF_SIZE 64
69 #define SS_MAX_RX_BUFF (SSI_RX_BUFF_SIZE - 1) // RX buffer size
70 #define SS_MAX_TX_BUFF (SSI_TX_BUFF_SIZE - 1) // TX buffer size
71 
72 extern const struct TIM_Channel PWM_Channels[];
73 
74 class F4Light::SerialDriver : public AP_HAL::UARTDriver {
75 public:
76  SerialDriver( uint8_t tx_pin, uint8_t rx_pin, bool inverseLogic)
77  :_inverse(inverseLogic)
78  , _initialized(false)
79  , _blocking(true)
80  , txSkip(false)
81  , rxSkip(false)
82  , activeRX(false)
83  , activeTX(false)
84  ,_tx_pin(tx_pin)
85  ,_rx_pin(rx_pin)
86  , tx_pp(PIN_MAP[tx_pin])
87  , rx_pp(PIN_MAP[rx_pin])
88  , timer(rx_pp.timer_device)
89  , channel(rx_pp.timer_channel)
90  {
91  }
92 
93 
94  /* F4Light implementations of UARTDriver virtual methods */
95  void begin(uint32_t b);
96  void begin(uint32_t baud, uint16_t rxS, uint16_t txS) { begin(baud); }
97  void end();
98  void flush();
99 
100  bool inline is_initialized(){ return _initialized; }
101 
102  void inline set_blocking_writes(bool blocking) { _blocking=blocking; }
103  bool tx_pending();
104 
105  /* F4Light implementations of Stream virtual methods */
106  uint32_t available() override;
107  uint32_t txspace() override;
108  int16_t read() override;
109 
110  /* Empty implementations of Print virtual methods */
111  size_t write(uint8_t c);
112  size_t write(const uint8_t *buffer, size_t size);
113 
114 private:
115 
116  bool _inverse;
117  bool _initialized;
118  bool _blocking;
119 
120  uint16_t bitPeriod;
121 
122 #ifdef SS_DEBUG
123  volatile uint8_t bufferOverflow;
124 #endif
125 
126  volatile int8_t rxBitCount;
127  volatile uint16_t receiveBufferWrite;
128  volatile uint16_t receiveBufferRead;
129  volatile uint8_t receiveBuffer[SSI_RX_BUFF_SIZE];
130  uint8_t receiveByte;
131 
132  volatile int8_t txBitCount;
133  uint16_t transmitBufferWrite;
134  volatile uint16_t transmitBufferRead;
135  uint8_t transmitBuffer[SSI_RX_BUFF_SIZE];
136 
137  bool txSkip;
138  bool rxSkip;
139 
140  bool activeRX;
141  bool activeTX;
142 
143  uint8_t _tx_pin;
144  uint8_t _rx_pin;
145  const stm32_pin_info &tx_pp;
146  const stm32_pin_info &rx_pp;
147 
148  const timer_dev *timer;
149  const timer_Channel channel;
150 
151  // Clear pending interrupt and enable receive interrupt
152  // Note: Clears pending interrupt
153  inline void txEnableInterrupts() {
154  timer->regs->SR &= ~TIMER_SR_UIF;
156  }
157 
158  // Mask transmit interrupt
159  inline void txDisableInterrupts() {
161  }
162 
163  void rxSetCapture();
164  void rxSetCompare();
165 
166  void txNextBit( /* TIM_TypeDef *tim */ );
167  void rxNextBit( /* TIM_TypeDef *tim */ );
168 
169 };
170 
171 #endif // defined(BOARD_SOFTSERIAL_RX) && defined(BOARD_SOFTSERIAL_TX)
virtual void set_blocking_writes(bool blocking)=0
virtual bool tx_pending()=0
virtual void begin(uint32_t baud)=0
static uint8_t buffer[SRXL_FRAMELEN_MAX]
Definition: srxl.cpp:56
virtual bool is_initialized()=0
const stm32_pin_info PIN_MAP[BOARD_NR_GPIO_PINS]
virtual uint32_t txspace()=0
uint32_t timer
timer_Channel
Definition: timer.h:441
virtual size_t write(uint8_t)=0
#define TIMER_SR_UIF
Definition: timer.h:225
virtual void flush()=0
virtual void end()=0
virtual int16_t read()=0
static void timer_enable_irq(const timer_dev *dev, timer_interrupt_id interrupt)
Enable a timer interrupt.
Definition: timer.h:1125
static void timer_disable_irq(const timer_dev *dev, timer_interrupt_id interrupt)
Disable a timer interrupt.
Definition: timer.h:1138
virtual uint32_t available()=0
TIM_TypeDef * regs
Definition: timer.h:575
const struct TIM_Channel PWM_Channels[]
Definition: board.cpp:135
Stores STM32-specific information related to a given Maple pin.
Definition: boards.h:88