APM:Libraries
UART_SoftDriver.cpp
Go to the documentation of this file.
1 /*
2 
3  (c) 2017 night_ghost@ykoctpa.ru
4 
5 based on: ST appnote
6 
7  * SerialDriver.cpp --- AP_HAL_F4Light SoftSerial driver.
8  *
9  */
10 
11 #pragma GCC optimize ("O2")
12 
13 #include <AP_HAL/AP_HAL.h>
14 
15 #if CONFIG_HAL_BOARD == HAL_BOARD_F4LIGHT && defined(BOARD_SOFTSERIAL_RX) && defined(BOARD_SOFTSERIAL_TX)
16 #include "UART_SoftDriver.h"
17 
18 #include <stdio.h>
19 #include <unistd.h>
20 #include <stdlib.h>
21 #include <errno.h>
22 #include <fcntl.h>
23 
24 #include <gpio_hal.h>
25 
26 
27 using namespace F4Light;
28 
29 
30 // hardware RX and software TX
31 
32 void SerialDriver::begin(uint32_t baud) {
33  gpio_write_bit(tx_pp.gpio_device, tx_pp.gpio_bit, _inverse?LOW:HIGH);
34  gpio_set_mode(tx_pp.gpio_device, tx_pp.gpio_bit, GPIO_OUTPUT_PP);
35  gpio_set_mode(rx_pp.gpio_device, rx_pp.gpio_bit, GPIO_INPUT_PU);
36 
37 
39  uint32_t prescaler;
40 
41  if (baud > 2400) {
42  bitPeriod = (uint16_t)((uint32_t)(CYCLES_PER_MICROSECOND * 1000000) / baud);
43  prescaler=1;
44  } else {
45  bitPeriod = (uint16_t)(((uint32_t)(CYCLES_PER_MICROSECOND * 1000000) / 16) / baud);
46  prescaler=16;
47  }
48 
49  timer_set_prescaler(timer, prescaler-1);
50 
51  timer_set_reload(timer, bitPeriod/2); // for TX needs
52 
53  transmitBufferRead = transmitBufferWrite = 0;
54  txBitCount = 8; // 1st interrupt will generate STOP
55  txSkip=true;
56 
57  // Set rx State machine start state, attach the bit interrupt and mask it until start bit is received
58  receiveBufferRead = receiveBufferWrite = 0;
59  rxBitCount = 9;
60 
61  rxSetCapture(); // wait for start bit
63  timer_attach_interrupt(timer, TIMER_UPDATE_INTERRUPT, Scheduler::get_handler(FUNCTOR_BIND_MEMBER(&SerialDriver::txNextBit,void)), SOFT_UART_INT_PRIORITY); // also enables interrupt, so 1st interrupt will be ASAP
64  // there will be interrupt after enabling TX interrupts, it will be disabled in handler
65 
66  timer_generate_update(timer); // Load the timer values and start it
68 
69  _initialized = true;
70 }
71 
72 
73 void SerialDriver::rxSetCapture(){
74  timer_ic_set_mode(timer, channel, TIM_ICSelection_DirectTI | TIM_ICPSC_DIV1, 3);
76 }
77 
78 void SerialDriver::rxSetCompare(){
79  timer_set_mode(timer, channel, TIMER_OUTPUT_COMPARE); // for RX needs, capture mode by hands
80 }
81 
82 
83 void SerialDriver::end() {
85  gpio_write_bit(tx_pp.gpio_device, tx_pp.gpio_bit, 1);
86  _initialized = false;
87 
88 }
89 
90 void SerialDriver::flush() {
91  receiveBufferRead = receiveBufferWrite = 0;
92 }
93 
94 
95 bool SerialDriver::tx_pending() {
96  if(!_initialized) return 0;
97 
98  return (transmitBufferWrite + SS_MAX_TX_BUFF - transmitBufferRead) % SS_MAX_TX_BUFF;
99 }
100 
101 
102 uint32_t SerialDriver::available() {
103 
104  return (receiveBufferWrite + SS_MAX_RX_BUFF - receiveBufferRead) % SS_MAX_RX_BUFF;
105 }
106 
107 uint32_t SerialDriver::txspace() {
108  return SS_MAX_TX_BUFF - tx_pending();
109 }
110 
111 int16_t SerialDriver::read() {
112  if (!_initialized)
113  return -1;
114 
115  // Wait if buffer is empty
116  if(receiveBufferRead == receiveBufferWrite) return -1; // no data
117 
118  uint8_t inData = receiveBuffer[receiveBufferRead];
119 
120  receiveBufferRead = (receiveBufferRead + 1) % SS_MAX_RX_BUFF;
121 
122  return inData;
123 }
124 
125 size_t SerialDriver::write(uint8_t c) {
126  if (!_initialized) return 0;
127 
128  // Blocks if buffer full
129  uint16_t n_try=3;
130  do { // wait for free space
131  if( ((transmitBufferWrite + 1) % SS_MAX_TX_BUFF) == transmitBufferRead ){
132  Scheduler::yield(); // while we wait - let others work
133  if(! _blocking) n_try--;
134  } else break; // got it!
135  } while(n_try);
136 
137  // Save new data in buffer and bump the write pointer
138  transmitBuffer[transmitBufferWrite] = c;
139 
140  transmitBufferWrite = (transmitBufferWrite == SS_MAX_TX_BUFF) ? 0 : transmitBufferWrite + 1;
141 
142 
143  // Check if transmit timer interrupt enabled and if not unmask it
144  // transmit timer interrupt will get masked by transmit ISR when buffer becomes empty
145  if (!activeTX) {
146  activeTX=true;
147 
148  // Set state to 10 (send start bit) and re-enable transmit interrupt
149  txBitCount = 10;
150 
151  txEnableInterrupts(); // enable
152  }
153 
154  return 1;
155 }
156 
157 size_t SerialDriver::write(const uint8_t *buffer, size_t size)
158 {
159  size_t n = 0;
160  while (size--) {
161  n += write(*buffer++);
162  }
163  return n;
164 }
165 
166 
167 #define bitRead(value, bit) (((value) >> (bit)) & 0x01)
168 
169 // Transmits next bit. Called by timer update interrupt
170 void SerialDriver::txNextBit(void /* TIM_TypeDef *tim */) { // ISR
171 
172  txSkip= !txSkip;
173 
174  if(txSkip) return; // one bit per 2 periods
175 
176 
177  // State 0 through 7 - transmit bits
178  if (txBitCount <= 7) {
179  if (bitRead(transmitBuffer[transmitBufferRead], txBitCount) == (_inverse?0:1)) {
180  gpio_write_bit(tx_pp.gpio_device, tx_pp.gpio_bit,HIGH);
181  } else {
182  gpio_write_bit(tx_pp.gpio_device, tx_pp.gpio_bit,LOW);
183  }
184 
185  // Bump the bit/state counter to state 8
186  txBitCount++;
187 
188 #if DEBUG_DELAY && defined(DEBUG_PIN1)
189  GPIO::_write(DEBUG_PIN1,1);
190  GPIO::_write(DEBUG_PIN1,0);
191 #endif
192 
193  // State 8 - Send the stop bit and reset state to state -1
194  // Shutdown timer interrupt if buffer empty
195  } else if (txBitCount == 8) {
196 
197  // Send the stop bit
198  gpio_write_bit(tx_pp.gpio_device, tx_pp.gpio_bit, _inverse?LOW:HIGH);
199 
200  transmitBufferRead = (transmitBufferRead == SS_MAX_TX_BUFF ) ? 0 : transmitBufferRead + 1;
201 
202  if (transmitBufferRead != transmitBufferWrite) { // we have data do transmit
203  txBitCount = 10;
204  } else {
205  // Buffer empty so shutdown timer until write() puts data in
206  txDisableInterrupts();
207  activeTX=false;
208  }
209 
210  // Send start bit for new byte
211  } else if (txBitCount >= 10) {
212  gpio_write_bit(tx_pp.gpio_device, tx_pp.gpio_bit, _inverse?HIGH:LOW);
213 
214  txBitCount = 0;
215  }
216 }
217 
218 
219 
220 // Receive next bit. Called by timer channel interrupt
221 void SerialDriver::rxNextBit(void /* TIM_TypeDef *tim */) { // ISR
222 
223  if(!activeRX) { // capture start bit
224 
225  // Test if this is really the start bit and not a spurious edge
226  if (rxBitCount == 9) {
227 
228  uint16_t pos = timer_get_capture(timer, channel);
229 
230  rxSetCompare(); // turn to compare mode
231 
232  timer_set_compare(timer, channel, pos); // captured value
233 
234  // Set state/bit to first bit
235  rxSkip=false; // next half bit will OK
236  activeRX=true;
237  }
238  } else { // compare match twice per bit;
239  rxSkip= !rxSkip;
240 
241  if(!rxSkip) return; // not the middle of bit
242 
243 // now in middle of bit
244  uint8_t d = gpio_read_bit( rx_pp.gpio_device, rx_pp.gpio_bit);
245 
246  if (rxBitCount == 9) { // check start bit again
247  if ( d == _inverse?HIGH:LOW) { // start OK
248  rxBitCount = 0;
249  } else { // false start
250  activeRX=false;
251  rxSetCapture(); // turn back to capture mode
252  }
253  } else if (rxBitCount < 8) { // get bits
254  receiveByte >>= 1;
255 
256 
257  if ( d == _inverse?LOW:HIGH)
258  receiveByte |= 0x80;
259 
260 #if DEBUG_DELAY
261  GPIO::_write(DEBUG_PIN,1);
262  GPIO::_write(DEBUG_PIN,0);
263 #endif
264 
265 
266  rxBitCount++;
267 
268  // State 8 - Save incoming byte and update buffer
269  } else if (rxBitCount == 8) {
270  if ( d == _inverse?LOW:HIGH) { // stop OK - save byte
271  // Finish out stop bit while we...
272 
273  if (gpio_read_bit( rx_pp.gpio_device, rx_pp.gpio_bit) == _inverse?LOW:HIGH) // valid STOP
274  receiveBuffer[receiveBufferWrite] = receiveByte;
275 
276  // Calculate location in buffer for next incoming byte
277  uint8_t next = (receiveBufferWrite + 1) % SS_MAX_RX_BUFF; // FYI - With this logic we effectively only have an (SS_MAX_RX_BUFF - 1) buffer size
278 
279  // Test if buffer full
280  // If the buffer isn't full update the tail pointer to point to next location
281  if (next != receiveBufferRead) {
282  receiveBufferWrite = next;
283  }
284 #ifdef SS_DEBUG
285  else {
286  bufferOverflow = true; // Else if it is now full set the buffer overflow flag
287 
288 
289 #if DEBUG_DELAY && defined(DEBUG_PIN1)
290  overFlowTail = receiveBufferWrite;
291  overFlowHead = receiveBufferRead;
292 
293  GPIO::_write(DEBUG_PIN1, 1);
294  GPIO::_write(DEBUG_PIN1, 0);
295 #endif
296  }
297 #endif
298  }
299  // Set for state 9 to receive next byte
300  rxBitCount = 9;
301  activeRX=false;
302  rxSetCapture(); // turn back to capture mode
303  }
304  }
305 }
306 
307 #endif
static Handler get_handler(AP_HAL::MemberProc proc)
Definition: Scheduler.h:436
void timer_set_mode(const timer_dev *dev, timer_Channel channel, timer_mode mode)
Definition: timer.c:442
static void timer_cc_set_pol(const timer_dev *dev, timer_Channel channel, timer_cc_polarity pol)
Set a timer channel&#39;s capture/compare output polarity.
Definition: timer.h:950
static uint8_t buffer[SRXL_FRAMELEN_MAX]
Definition: srxl.cpp:56
ssize_t write(int fd, const void *buf, size_t count)
POSIX Write count bytes from *buf to fileno fd.
Definition: posix.c:1169
static void _write(uint8_t pin, uint8_t value)
Definition: GPIO.h:165
static INLINE uint16_t timer_get_capture(const timer_dev *dev, timer_Channel channel)
Definition: timer.h:791
uint32_t timer
static INLINE void timer_pause(const timer_dev *dev)
Stop a timer&#39;s counter from changing.
Definition: timer.h:679
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
void timer_attach_interrupt(const timer_dev *dev, timer_interrupt_id interrupt, Handler handler, uint8_t priority)
Attach a timer interrupt.
Definition: timer.c:485
void gpio_set_mode(const gpio_dev *const dev, uint8_t pin, gpio_pin_mode mode)
Definition: gpio_hal.c:125
static INLINE void timer_resume(const timer_dev *dev)
Start a timer&#39;s counter.
Definition: timer.h:690
#define HIGH
Definition: board.h:34
ssize_t read(int fd, void *buf, size_t count)
POSIX read count bytes from *buf to fileno fd.
Definition: posix.c:995
#define LOW
Definition: board.h:31
#define SOFT_UART_INT_PRIORITY
Definition: Config.h:40
static void yield(uint16_t ttw=0)
Definition: Scheduler.cpp:1188
static void timer_set_compare(const timer_dev *dev, timer_Channel channel, uint16_t value)
Set the compare value for the given timer channel.
Definition: timer.h:783
static void timer_ic_set_mode(const timer_dev *dev, timer_Channel _channel, uint8_t mode, uint16_t filter)
Configure a channel&#39;s input capture mode.
Definition: timer.h:1096
static INLINE uint8_t gpio_read_bit(const gpio_dev *const dev, uint8_t pin)
Definition: gpio_hal.h:130
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
Definition: functor.h:31
static INLINE void timer_set_reload(const timer_dev *dev, uint32_t arr)
Set a timer&#39;s reload value.
Definition: timer.h:763
#define CYCLES_PER_MICROSECOND
Definition: board.h:20
static void timer_set_prescaler(const timer_dev *dev, uint16_t psc)
Set a timer&#39;s prescale value.
Definition: timer.h:745
static void timer_generate_update(const timer_dev *dev)
Generate an update event for the given timer.
Definition: timer.h:807
static INLINE void gpio_write_bit(const gpio_dev *const dev, uint8_t pin, uint8_t val)
Definition: gpio_hal.h:115