forked from ArduPilot/ardupilot
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathUARTDriver.cpp
216 lines (180 loc) · 4.66 KB
/
UARTDriver.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
/*
* This file is free software: you can redistribute it and/or modify it
* under the terms of the GNU General Public License as published by the
* Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This file is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
* See the GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#include <AP_HAL_ESP32/UARTDriver.h>
#include <AP_Math/AP_Math.h>
#include "esp_log.h"
extern const AP_HAL::HAL& hal;
namespace ESP32
{
UARTDesc uart_desc[] = {HAL_ESP32_UART_DEVICES};
void UARTDriver::vprintf(const char *fmt, va_list ap)
{
uart_port_t p = uart_desc[uart_num].port;
if (p == 0) {
esp_log_writev(ESP_LOG_INFO, "", fmt, ap);
} else {
AP_HAL::UARTDriver::vprintf(fmt, ap);
}
}
void UARTDriver::begin(uint32_t b)
{
begin(b, 0, 0);
}
void UARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS)
{
if (uart_num < ARRAY_SIZE(uart_desc)) {
uart_port_t p = uart_desc[uart_num].port;
if (!_initialized) {
uart_config_t config = {
.baud_rate = (int)b,
.data_bits = UART_DATA_8_BITS,
.parity = UART_PARITY_DISABLE,
.stop_bits = UART_STOP_BITS_1,
.flow_ctrl = UART_HW_FLOWCTRL_DISABLE,
};
uart_param_config(p, &config);
uart_set_pin(p,
uart_desc[uart_num].tx,
uart_desc[uart_num].rx,
UART_PIN_NO_CHANGE, UART_PIN_NO_CHANGE);
//uart_driver_install(p, 2*UART_FIFO_LEN, 0, 0, nullptr, 0);
uart_driver_install(p, 2*UART_FIFO_LEN, 0, 0, nullptr, 0);
_readbuf.set_size(RX_BUF_SIZE);
_writebuf.set_size(TX_BUF_SIZE);
_initialized = true;
} else {
flush();
uart_set_baudrate(p, b);
}
}
}
void UARTDriver::end()
{
if (_initialized) {
uart_driver_delete(uart_desc[uart_num].port);
_readbuf.set_size(0);
_writebuf.set_size(0);
}
_initialized = false;
}
void UARTDriver::flush()
{
uart_port_t p = uart_desc[uart_num].port;
uart_flush(p);
}
bool UARTDriver::is_initialized()
{
return _initialized;
}
void UARTDriver::set_blocking_writes(bool blocking)
{
//blocking writes do not used anywhere
}
bool UARTDriver::tx_pending()
{
return (_writebuf.available() > 0);
}
uint32_t UARTDriver::available()
{
if (!_initialized) {
return 0;
}
return _readbuf.available();
}
uint32_t UARTDriver::txspace()
{
if (!_initialized) {
return 0;
}
int result = _writebuf.space();
result -= TX_BUF_SIZE / 4;
return MAX(result, 0);
}
ssize_t IRAM_ATTR UARTDriver::read(uint8_t *buffer, uint16_t count)
{
if (!_initialized) {
return -1;
}
const uint32_t ret = _readbuf.read(buffer, count);
if (ret == 0) {
return 0;
}
return ret;
}
int16_t IRAM_ATTR UARTDriver::read()
{
if (!_initialized) {
return -1;
}
uint8_t byte;
if (!_readbuf.read_byte(&byte)) {
return -1;
}
return byte;
}
void IRAM_ATTR UARTDriver::_timer_tick(void)
{
if (!_initialized) {
return;
}
read_data();
write_data();
}
void IRAM_ATTR UARTDriver::read_data()
{
uart_port_t p = uart_desc[uart_num].port;
int count = 0;
do {
count = uart_read_bytes(p, _buffer, sizeof(_buffer), 0);
if (count > 0) {
_readbuf.write(_buffer, count);
}
} while (count > 0);
}
void IRAM_ATTR UARTDriver::write_data()
{
uart_port_t p = uart_desc[uart_num].port;
int count = 0;
_write_mutex.take_blocking();
do {
count = _writebuf.peekbytes(_buffer, sizeof(_buffer));
if (count > 0) {
count = uart_tx_chars(p, (const char*) _buffer, count);
_writebuf.advance(count);
}
} while (count > 0);
_write_mutex.give();
}
size_t IRAM_ATTR UARTDriver::write(uint8_t c)
{
return write(&c,1);
}
size_t IRAM_ATTR UARTDriver::write(const uint8_t *buffer, size_t size)
{
if (!_initialized) {
return 0;
}
_write_mutex.take_blocking();
size_t ret = _writebuf.write(buffer, size);
_write_mutex.give();
return ret;
}
bool UARTDriver::discard_input()
{
//uart_port_t p = uart_desc[uart_num].port;
//return uart_flush_input(p) == ESP_OK;
return false;
}
}