Details | Last modification | View Log | RSS feed
Rev | Author | Line No. | Line |
---|---|---|---|
1702 | - | 1 | // -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*- |
2 | // |
||
3 | // Interrupt-driven serial transmit/receive library. |
||
4 | // |
||
5 | // Copyright (c) 2010 Michael Smith. All rights reserved. |
||
6 | // |
||
7 | // Receive and baudrate calculations derived from the Arduino |
||
8 | // HardwareSerial driver: |
||
9 | // |
||
10 | // Copyright (c) 2006 Nicholas Zambetti. All right reserved. |
||
11 | // |
||
12 | // Transmit algorithm inspired by work: |
||
13 | // |
||
14 | // Code Jose Julio and Jordi Munoz. DIYDrones.com |
||
15 | // |
||
16 | // This library is free software; you can redistribute it and/or |
||
17 | // modify it under the terms of the GNU Lesser General Public |
||
18 | // License as published by the Free Software Foundation; either |
||
19 | // version 2.1 of the License, or (at your option) any later version. |
||
20 | // |
||
21 | // This library is distributed in the hope that it will be useful, |
||
22 | // but WITHOUT ANY WARRANTY; without even the implied warranty of |
||
23 | // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU |
||
24 | // Lesser General Public License for more details. |
||
25 | // |
||
26 | // You should have received a copy of the GNU Lesser General Public |
||
27 | // License along with this library; if not, write to the Free Software |
||
28 | // Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA |
||
29 | // |
||
30 | |||
31 | |||
32 | //#include "../AP_Common/AP_Common.h" |
||
33 | #include "FastSerial.h" |
||
34 | |||
35 | #if defined(ARDUINO) && ARDUINO >= 100 |
||
36 | #include "Arduino.h" |
||
37 | #else |
||
38 | #include "WProgram.h" |
||
39 | #endif |
||
40 | |||
41 | #if defined(UDR3) |
||
42 | # define FS_MAX_PORTS 4 |
||
43 | #elif defined(UDR2) |
||
44 | # define FS_MAX_PORTS 3 |
||
45 | #elif defined(UDR1) |
||
46 | # define FS_MAX_PORTS 2 |
||
47 | #else |
||
48 | # define FS_MAX_PORTS 1 |
||
49 | #endif |
||
50 | |||
51 | FastSerial::Buffer __FastSerial__rxBuffer[FS_MAX_PORTS]; |
||
52 | FastSerial::Buffer __FastSerial__txBuffer[FS_MAX_PORTS]; |
||
53 | uint8_t FastSerial::_serialInitialized = 0; |
||
54 | |||
55 | // Constructor ///////////////////////////////////////////////////////////////// |
||
56 | |||
57 | FastSerial::FastSerial(const uint8_t portNumber, volatile uint8_t *ubrrh, volatile uint8_t *ubrrl, |
||
58 | volatile uint8_t *ucsra, volatile uint8_t *ucsrb, const uint8_t u2x, |
||
59 | const uint8_t portEnableBits, const uint8_t portTxBits) : |
||
60 | _ubrrh(ubrrh), |
||
61 | _ubrrl(ubrrl), |
||
62 | _ucsra(ucsra), |
||
63 | _ucsrb(ucsrb), |
||
64 | _u2x(u2x), |
||
65 | _portEnableBits(portEnableBits), |
||
66 | _portTxBits(portTxBits), |
||
67 | _rxBuffer(&__FastSerial__rxBuffer[portNumber]), |
||
68 | _txBuffer(&__FastSerial__txBuffer[portNumber]) |
||
69 | { |
||
70 | setInitialized(portNumber); |
||
71 | begin(57600); |
||
72 | } |
||
73 | |||
74 | // Public Methods ////////////////////////////////////////////////////////////// |
||
75 | |||
76 | void FastSerial::begin(long baud) |
||
77 | { |
||
78 | begin(baud, 0, 0); |
||
79 | } |
||
80 | |||
81 | void FastSerial::begin(long baud, unsigned int rxSpace, unsigned int txSpace) |
||
82 | { |
||
83 | uint16_t ubrr; |
||
84 | bool use_u2x = true; |
||
85 | |||
86 | // if we are currently open... |
||
87 | if (_open) { |
||
88 | // If the caller wants to preserve the buffer sizing, work out what |
||
89 | // it currently is... |
||
90 | if (0 == rxSpace) |
||
91 | rxSpace = _rxBuffer->mask + 1; |
||
92 | if (0 == txSpace) |
||
93 | txSpace = _txBuffer->mask + 1; |
||
94 | |||
95 | // close the port in its current configuration, clears _open |
||
96 | end(); |
||
97 | } |
||
98 | |||
99 | // allocate buffers |
||
100 | if (!_allocBuffer(_rxBuffer, rxSpace ? : _default_rx_buffer_size) || !_allocBuffer(_txBuffer, txSpace ? : _default_tx_buffer_size)) { |
||
101 | end(); |
||
102 | return; // couldn't allocate buffers - fatal |
||
103 | } |
||
104 | |||
105 | // reset buffer pointers |
||
106 | _txBuffer->head = _txBuffer->tail = 0; |
||
107 | _rxBuffer->head = _rxBuffer->tail = 0; |
||
108 | |||
109 | // mark the port as open |
||
110 | _open = true; |
||
111 | |||
112 | // If the user has supplied a new baud rate, compute the new UBRR value. |
||
113 | if (baud > 0) { |
||
114 | #if F_CPU == 16000000UL |
||
115 | // hardcoded exception for compatibility with the bootloader shipped |
||
116 | // with the Duemilanove and previous boards and the firmware on the 8U2 |
||
117 | // on the Uno and Mega 2560. |
||
118 | if (baud == 57600) |
||
119 | use_u2x = false; |
||
120 | #endif |
||
121 | |||
122 | if (use_u2x) { |
||
123 | *_ucsra = 1 << _u2x; |
||
124 | ubrr = (F_CPU / 4 / baud - 1) / 2; |
||
125 | } else { |
||
126 | *_ucsra = 0; |
||
127 | ubrr = (F_CPU / 8 / baud - 1) / 2; |
||
128 | } |
||
129 | |||
130 | *_ubrrh = ubrr >> 8; |
||
131 | *_ubrrl = ubrr; |
||
132 | } |
||
133 | |||
134 | *_ucsrb |= _portEnableBits; |
||
135 | } |
||
136 | |||
137 | void FastSerial::end() |
||
138 | { |
||
139 | *_ucsrb &= ~(_portEnableBits | _portTxBits); |
||
140 | |||
141 | _freeBuffer(_rxBuffer); |
||
142 | _freeBuffer(_txBuffer); |
||
143 | _open = false; |
||
144 | } |
||
145 | |||
146 | int FastSerial::available(void) |
||
147 | { |
||
148 | if (!_open) |
||
149 | return (-1); |
||
150 | return ((_rxBuffer->head - _rxBuffer->tail) & _rxBuffer->mask); |
||
151 | } |
||
152 | |||
153 | int FastSerial::txspace(void) |
||
154 | { |
||
155 | if (!_open) |
||
156 | return (-1); |
||
157 | return ((_txBuffer->mask+1) - ((_txBuffer->head - _txBuffer->tail) & _txBuffer->mask)); |
||
158 | } |
||
159 | |||
160 | int FastSerial::read(void) |
||
161 | { |
||
162 | uint8_t c; |
||
163 | |||
164 | // if the head and tail are equal, the buffer is empty |
||
165 | if (!_open || (_rxBuffer->head == _rxBuffer->tail)) |
||
166 | return (-1); |
||
167 | |||
168 | // pull character from tail |
||
169 | c = _rxBuffer->bytes[_rxBuffer->tail]; |
||
170 | _rxBuffer->tail = (_rxBuffer->tail + 1) & _rxBuffer->mask; |
||
171 | |||
172 | return (c); |
||
173 | } |
||
174 | |||
175 | int FastSerial::peek(void) |
||
176 | { |
||
177 | |||
178 | // if the head and tail are equal, the buffer is empty |
||
179 | if (!_open || (_rxBuffer->head == _rxBuffer->tail)) |
||
180 | return (-1); |
||
181 | |||
182 | // pull character from tail |
||
183 | return (_rxBuffer->bytes[_rxBuffer->tail]); |
||
184 | } |
||
185 | |||
186 | void FastSerial::flush(void) |
||
187 | { |
||
188 | // don't reverse this or there may be problems if the RX interrupt |
||
189 | // occurs after reading the value of _rxBuffer->head but before writing |
||
190 | // the value to _rxBuffer->tail; the previous value of head |
||
191 | // may be written to tail, making it appear as if the buffer |
||
192 | // don't reverse this or there may be problems if the RX interrupt |
||
193 | // occurs after reading the value of head but before writing |
||
194 | // the value to tail; the previous value of rx_buffer_head |
||
195 | // may be written to tail, making it appear as if the buffer |
||
196 | // were full, not empty. |
||
197 | _rxBuffer->head = _rxBuffer->tail; |
||
198 | |||
199 | // don't reverse this or there may be problems if the TX interrupt |
||
200 | // occurs after reading the value of _txBuffer->tail but before writing |
||
201 | // the value to _txBuffer->head. |
||
202 | _txBuffer->tail = _txBuffer->head; |
||
203 | } |
||
204 | |||
205 | #if defined(ARDUINO) && ARDUINO >= 100 |
||
206 | size_t FastSerial::write(uint8_t c) |
||
207 | { |
||
208 | uint16_t i; |
||
209 | |||
210 | if (!_open) // drop bytes if not open |
||
211 | return 0; |
||
212 | |||
213 | // wait for room in the tx buffer |
||
214 | i = (_txBuffer->head + 1) & _txBuffer->mask; |
||
215 | |||
216 | // if the port is set into non-blocking mode, then drop the byte |
||
217 | // if there isn't enough room for it in the transmit buffer |
||
218 | if (_nonblocking_writes && i == _txBuffer->tail) { |
||
219 | return 0; |
||
220 | } |
||
221 | |||
222 | while (i == _txBuffer->tail) |
||
223 | ; |
||
224 | |||
225 | // add byte to the buffer |
||
226 | _txBuffer->bytes[_txBuffer->head] = c; |
||
227 | _txBuffer->head = i; |
||
228 | |||
229 | // enable the data-ready interrupt, as it may be off if the buffer is empty |
||
230 | *_ucsrb |= _portTxBits; |
||
231 | |||
232 | // return number of bytes written (always 1) |
||
233 | return 1; |
||
234 | } |
||
235 | #else |
||
236 | void FastSerial::write(uint8_t c) |
||
237 | { |
||
238 | uint16_t i; |
||
239 | |||
240 | if (!_open) // drop bytes if not open |
||
241 | return; |
||
242 | |||
243 | // wait for room in the tx buffer |
||
244 | i = (_txBuffer->head + 1) & _txBuffer->mask; |
||
245 | while (i == _txBuffer->tail) |
||
246 | ; |
||
247 | |||
248 | // add byte to the buffer |
||
249 | _txBuffer->bytes[_txBuffer->head] = c; |
||
250 | _txBuffer->head = i; |
||
251 | |||
252 | // enable the data-ready interrupt, as it may be off if the buffer is empty |
||
253 | *_ucsrb |= _portTxBits; |
||
254 | } |
||
255 | #endif |
||
256 | |||
257 | // Buffer management /////////////////////////////////////////////////////////// |
||
258 | |||
259 | bool FastSerial::_allocBuffer(Buffer *buffer, unsigned int size) |
||
260 | { |
||
261 | uint16_t mask; |
||
262 | uint8_t shift; |
||
263 | |||
264 | // init buffer state |
||
265 | buffer->head = buffer->tail = 0; |
||
266 | |||
267 | // Compute the power of 2 greater or equal to the requested buffer size |
||
268 | // and then a mask to simplify wrapping operations. Using __builtin_clz |
||
269 | // would seem to make sense, but it uses a 256(!) byte table. |
||
270 | // Note that we ignore requests for more than BUFFER_MAX space. |
||
271 | for (shift = 1; (1U << shift) < min(_max_buffer_size, size); shift++) |
||
272 | ; |
||
273 | mask = (1 << shift) - 1; |
||
274 | |||
275 | // If the descriptor already has a buffer allocated we need to take |
||
276 | // care of it. |
||
277 | if (buffer->bytes) { |
||
278 | |||
279 | // If the allocated buffer is already the correct size then |
||
280 | // we have nothing to do |
||
281 | if (buffer->mask == mask) |
||
282 | return true; |
||
283 | |||
284 | // Dispose of the old buffer. |
||
285 | free(buffer->bytes); |
||
286 | } |
||
287 | buffer->mask = mask; |
||
288 | |||
289 | // allocate memory for the buffer - if this fails, we fail. |
||
290 | buffer->bytes = (uint8_t *) malloc(buffer->mask + 1); |
||
291 | |||
292 | return (buffer->bytes != NULL); |
||
293 | } |
||
294 | |||
295 | void FastSerial::_freeBuffer(Buffer *buffer) |
||
296 | { |
||
297 | buffer->head = buffer->tail = 0; |
||
298 | buffer->mask = 0; |
||
299 | if (NULL != buffer->bytes) { |
||
300 | free(buffer->bytes); |
||
301 | buffer->bytes = NULL; |
||
302 | } |
||
303 | } |
||
304 |