APM:Libraries
UARTDriver.cpp
Go to the documentation of this file.
1 /*
2  * UARTDriver.cpp --- AP_HAL_F4Light UART driver.
3 
4  (c) 2017 night_ghost@ykoctpa.ru
5 
6 based on:
7 
8  * UART driver
9  * Copyright (C) 2013, Virtualrobotix.com Roberto Navoni , Emile
10  * All Rights Reserved.
11  *
12  * This software is released under the "BSD3" license. Read the file
13  * "LICENSE" for more information.
14  */
15 
16 #pragma GCC optimize ("O2")
17 
18 #include <AP_HAL/AP_HAL.h>
19 
20 #if CONFIG_HAL_BOARD == HAL_BOARD_F4LIGHT
21 #include "UARTDriver.h"
22 
23 #include <stdio.h>
24 #include <unistd.h>
25 #include <stdlib.h>
26 #include <errno.h>
27 #include <fcntl.h>
28 
29 #include <usb.h>
30 #include <usart.h>
31 #include <gpio_hal.h>
33 
34 using namespace F4Light;
35 
36 UARTDriver::UARTDriver(const struct usart_dev *usart):
37  _usart_device(usart),
38  _initialized(false),
39  _blocking(true)
40 {
41 }
42 
43 //uint8_t mode = (UART_Parity_No <<16) | UART_Stop_Bits_1
44 void UARTDriver::begin(uint32_t baud, uint32_t bmode) {
45 
46  if(!_usart_device) return;
47 
48 #ifdef BOARD_SBUS_UART
49  if(_initialized && hal_param_helper->_uart_sbus && _usart_device==UARTS[hal_param_helper->_uart_sbus]) return; //already used as SBUS
50 #endif
51 
52  _baudrate = baud;
53 
54  uint32_t mode=0;
55 
60  mode |= USART_Mode_Tx;
61  }
62 
67  mode |= USART_Mode_Rx;
68  }
69 
70  if(!mode) return;
71 
73 
75  usart_setup(_usart_device, (uint32_t)baud,
76  UART_Word_8b, bmode & 0xffff /*USART_StopBits_1*/ , (bmode>>16) & 0xffff /* USART_Parity_No*/, mode, UART_HardwareFlowControl_None);
78 
80 
81  _initialized = true;
82 }
83 
84 
86  if (!_initialized) {
87  return;
88  }
91 }
92 
93 
95  if (!_initialized) {
96  return 0;
97  }
98 
100  return v;
101 }
102 
103 int16_t UARTDriver::read() {
104  if (available() == 0) {
105  return -1;
106  }
107  return usart_getc(_usart_device);
108 }
109 
110 size_t UARTDriver::write(uint8_t c) {
111 
112  if (!_initialized) {
113  return 0;
114  }
115  uint16_t n;
116  uint16_t tr=2; // попытки
117  while(tr) {
118  n = usart_putc(_usart_device, c);
119  if(n==0) { // no place for character
120  hal_yield(0);
121  if(!_blocking) tr--; // in unlocking mode we reduce the retry count
122  } else break; // sent!
123  }
124  return n;
125 }
126 
127 size_t UARTDriver::write(const uint8_t *buffer, size_t size)
128 {
129  uint16_t tr=2; // tries
130  uint16_t n;
131  uint16_t sent=0;
132  while(tr && size) {
133 
134  n = usart_tx(_usart_device, buffer, size);
135  if(n<size) { // no place for character
136  hal_yield(0);
137  if(!_blocking) tr--; // in unlocking mode we reduce the retry count
138  } else break; // sent
139  buffer+=n;
140  sent+=n;
141  size-=n;
142  }
143  return sent;
144 }
145 
146 void UARTDriver::update_timestamp(){ // called from ISR
147  _time_idx ^= 1;
149 }
150 
151 // this is mostly a
152 uint64_t UARTDriver::receive_time_constraint_us(uint16_t nbytes) {
153 
154  // timestamp is 32 bits so read is atomic, in worst case we get 2nd timestamp
155  uint32_t time_from_last_byte = AP_HAL::micros() - _receive_timestamp[_time_idx];
156  uint32_t transport_time_us = 0;
157  if (_baudrate > 0) {
158  // assume 10 bits per byte
159  transport_time_us = (1000000UL * 10UL / _baudrate) * (nbytes+available());
160  }
161  return AP_HAL::micros64() - (time_from_last_byte + transport_time_us);
162 }
163 
164 
165 #endif // CONFIG_HAL_BOARD
size_t write(uint8_t c)
Definition: UARTDriver.cpp:110
static uint32_t usart_data_available(const usart_dev *dev)
Return the amount of data available in a serial port&#39;s RX buffer.
Definition: usart.h:286
static Handler get_handler(AP_HAL::MemberProc proc)
Definition: Scheduler.h:436
uint32_t _baudrate
Definition: UARTDriver.h:65
uint8_t tx_pin
Definition: usart.h:39
uint8_t gpio_af
Definition: usart.h:40
static uint8_t buffer[SRXL_FRAMELEN_MAX]
Definition: srxl.cpp:56
void usart_setup(const usart_dev *dev, uint32_t baudRate, uint16_t wordLength, uint16_t stopBits, uint16_t parity, uint16_t mode, uint16_t hardwareFlowControl)
Configure a serial port&#39;s baud rate.
Definition: usart.c:199
static void usart_enable(const usart_dev *dev)
Enable a serial port.
Definition: usart.h:155
const stm32_pin_info PIN_MAP[BOARD_NR_GPIO_PINS]
uint64_t receive_time_constraint_us(uint16_t nbytes) override
Definition: UARTDriver.cpp:152
void begin(uint32_t b)
Definition: UARTDriver.h:31
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
void gpio_set_mode(const gpio_dev *const dev, uint8_t pin, gpio_pin_mode mode)
Definition: gpio_hal.c:125
const usart_dev *const UARTS[]
Definition: usart.c:136
#define UART_Word_8b
Definition: usart.h:83
int16_t read() override
Definition: UARTDriver.cpp:103
static uint32_t usart_putc(const usart_dev *dev, uint8_t bt)
Transmit one character on a serial port.
Definition: usart.h:240
static void usart_set_callback(const usart_dev *dev, Handler cb)
Definition: usart.h:304
uint64_t micros64()
Definition: system.cpp:162
uint32_t usart_tx(const usart_dev *dev, const uint8_t *buf, uint32_t len)
Nonblocking USART transmit.
Definition: usart.c:258
float v
Definition: Printf.cpp:15
#define BOARD_NR_GPIO_PINS
Definition: board.h:96
uint32_t available() override
Definition: UARTDriver.cpp:94
const struct usart_dev * _usart_device
Definition: UARTDriver.h:62
void usart_init(const usart_dev *dev)
Initialize a serial port.
Definition: usart.c:187
static void usart_disable(const usart_dev *dev)
Turn off a serial port.
Definition: usart.h:180
static void usart_reset_rx(const usart_dev *dev)
Discard the contents of a serial port&#39;s RX buffer.
Definition: usart.h:295
static void gpio_set_af_mode(const gpio_dev *const dev, uint8_t pin, uint8_t mode)
Definition: gpio_hal.h:102
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
Definition: functor.h:31
uint8_t gpio_bit
Definition: boards.h:92
static uint8_t usart_getc(const usart_dev *dev)
Read one character from a serial port.
Definition: usart.h:277
Stores STM32-specific information related to a given Maple pin.
Definition: boards.h:88
static void usart_reset_tx(const usart_dev *dev)
Definition: usart.h:299
uint32_t micros()
Definition: system.cpp:152
uint32_t _receive_timestamp[2]
Definition: UARTDriver.h:66
const gpio_dev *const gpio_device
Definition: boards.h:89
#define UART_HardwareFlowControl_None
Definition: usart.h:78
void hal_yield(uint16_t ttw)
Definition: Scheduler.cpp:1430
uint8_t rx_pin
Definition: usart.h:38