HardwareSerial.cpp
Go to the documentation of this file.
1 /*
2  HardwareSerial.cpp - Hardware serial library for Wiring
3  Copyright (c) 2006 Nicholas Zambetti. All right reserved.
4 
5  This library is free software; you can redistribute it and/or
6  modify it under the terms of the GNU Lesser General Public
7  License as published by the Free Software Foundation; either
8  version 2.1 of the License, or (at your option) any later version.
9 
10  This library is distributed in the hope that it will be useful,
11  but WITHOUT ANY WARRANTY; without even the implied warranty of
12  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
13  Lesser General Public License for more details.
14 
15  You should have received a copy of the GNU Lesser General Public
16  License along with this library; if not, write to the Free Software
17  Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
18 
19  Modified 23 November 2006 by David A. Mellis
20  Modified 28 September 2010 by Mark Sproul
21  Modified 14 August 2012 by Alarus
22  Modified 3 December 2013 by Matthijs Kooijman
23 */
24 
25 #include <stdlib.h>
26 #include <stdio.h>
27 #include <string.h>
28 #include <inttypes.h>
29 #include "Arduino.h"
30 
31 #include "HardwareSerial.h"
32 #include "HardwareSerial_private.h"
33 
34 // this next line disables the entire HardwareSerial.cpp,
35 // this is so I can support Attiny series and any other chip without a uart
36 #if defined(HAVE_HWSERIAL0) || defined(HAVE_HWSERIAL1) || defined(HAVE_HWSERIAL2) || defined(HAVE_HWSERIAL3)
37 
38 // SerialEvent functions are weak, so when the user doesn't define them,
39 // the linker just sets their address to 0 (which is checked below).
40 // The Serialx_available is just a wrapper around Serialx.available(),
41 // but we can refer to it weakly so we don't pull in the entire
42 // HardwareSerial instance if the user doesn't also refer to it.
43 #if defined(HAVE_HWSERIAL0)
44  void serialEvent() __attribute__((weak));
45  bool Serial0_available() __attribute__((weak));
46 #endif
47 
48 #if defined(HAVE_HWSERIAL1)
49  void serialEvent1() __attribute__((weak));
50  bool Serial1_available() __attribute__((weak));
51 #endif
52 
53 #if defined(HAVE_HWSERIAL2)
54  void serialEvent2() __attribute__((weak));
55  bool Serial2_available() __attribute__((weak));
56 #endif
57 
58 #if defined(HAVE_HWSERIAL3)
59  void serialEvent3() __attribute__((weak));
60  bool Serial3_available() __attribute__((weak));
61 #endif
62 
63 void serialEventRun(void)
64 {
65 #if defined(HAVE_HWSERIAL0)
66  if (Serial0_available && serialEvent && Serial0_available()) serialEvent();
67 #endif
68 #if defined(HAVE_HWSERIAL1)
69  if (Serial1_available && serialEvent1 && Serial1_available()) serialEvent1();
70 #endif
71 #if defined(HAVE_HWSERIAL2)
72  if (Serial2_available && serialEvent2 && Serial2_available()) serialEvent2();
73 #endif
74 #if defined(HAVE_HWSERIAL3)
75  if (Serial3_available && serialEvent3 && Serial3_available()) serialEvent3();
76 #endif
77 }
78 
79 // Actual interrupt handlers //////////////////////////////////////////////////////////////
80 
82 {
83  // If interrupts are enabled, there must be more data in the output
84  // buffer. Send the next byte
85  unsigned char c = _tx_buffer[_tx_buffer_tail];
87 
88  *_udr = c;
89 
90  // clear the TXC bit -- "can be cleared by writing a one to its bit
91  // location". This makes sure flush() won't return until the bytes
92  // actually got written
93  sbi(*_ucsra, TXC0);
94 
96  // Buffer empty, so disable interrupts
97  cbi(*_ucsrb, UDRIE0);
98  }
99 }
100 
101 // Public Methods //////////////////////////////////////////////////////////////
102 
103 void HardwareSerial::begin(unsigned long baud, byte config)
104 {
105  // Try u2x mode first
106  uint16_t baud_setting = (F_CPU / 4 / baud - 1) / 2;
107  *_ucsra = 1 << U2X0;
108 
109  // hardcoded exception for 57600 for compatibility with the bootloader
110  // shipped with the Duemilanove and previous boards and the firmware
111  // on the 8U2 on the Uno and Mega 2560. Also, The baud_setting cannot
112  // be > 4095, so switch back to non-u2x mode if the baud rate is too
113  // low.
114  if (((F_CPU == 16000000UL) && (baud == 57600)) || (baud_setting >4095))
115  {
116  *_ucsra = 0;
117  baud_setting = (F_CPU / 8 / baud - 1) / 2;
118  }
119 
120  // assign the baud_setting, a.k.a. ubrr (USART Baud Rate Register)
121  *_ubrrh = baud_setting >> 8;
122  *_ubrrl = baud_setting;
123 
124  _written = false;
125 
126  //set the data bits, parity, and stop bits
127 #if defined(__AVR_ATmega8__)
128  config |= 0x80; // select UCSRC register (shared with UBRRH)
129 #endif
130  *_ucsrc = config;
131 
132  sbi(*_ucsrb, RXEN0);
133  sbi(*_ucsrb, TXEN0);
134  sbi(*_ucsrb, RXCIE0);
135  cbi(*_ucsrb, UDRIE0);
136 }
137 
138 void HardwareSerial::end()
139 {
140  // wait for transmission of outgoing data
141  flush();
142 
143  cbi(*_ucsrb, RXEN0);
144  cbi(*_ucsrb, TXEN0);
145  cbi(*_ucsrb, RXCIE0);
146  cbi(*_ucsrb, UDRIE0);
147 
148  // clear any received data
150 }
151 
153 {
155 }
156 
157 int HardwareSerial::peek(void)
158 {
160  return -1;
161  } else {
162  return _rx_buffer[_rx_buffer_tail];
163  }
164 }
165 
166 int HardwareSerial::read(void)
167 {
168  // if the head isn't ahead of the tail, we don't have any characters
170  return -1;
171  } else {
172  unsigned char c = _rx_buffer[_rx_buffer_tail];
174  return c;
175  }
176 }
177 
179 {
180 #if (SERIAL_TX_BUFFER_SIZE>256)
181  uint8_t oldSREG = SREG;
182  cli();
183 #endif
186 #if (SERIAL_TX_BUFFER_SIZE>256)
187  SREG = oldSREG;
188 #endif
189  if (head >= tail) return SERIAL_TX_BUFFER_SIZE - 1 - head + tail;
190  return tail - head - 1;
191 }
192 
194 {
195  // If we have never written a byte, no need to flush. This special
196  // case is needed since there is no way to force the TXC (transmit
197  // complete) bit to 1 during initialization
198  if (!_written)
199  return;
200 
201  while (bit_is_set(*_ucsrb, UDRIE0) || bit_is_clear(*_ucsra, TXC0)) {
202  if (bit_is_clear(SREG, SREG_I) && bit_is_set(*_ucsrb, UDRIE0))
203  // Interrupts are globally disabled, but the DR empty
204  // interrupt should be enabled, so poll the DR empty flag to
205  // prevent deadlock
206  if (bit_is_set(*_ucsra, UDRE0))
208  }
209  // If we get here, nothing is queued anymore (DRIE is disabled) and
210  // the hardware finished tranmission (TXC is set).
211 }
212 
213 size_t HardwareSerial::write(uint8_t c)
214 {
215  _written = true;
216  // If the buffer and the data register is empty, just write the byte
217  // to the data register and be done. This shortcut helps
218  // significantly improve the effective datarate at high (>
219  // 500kbit/s) bitrates, where interrupt overhead becomes a slowdown.
220  if (_tx_buffer_head == _tx_buffer_tail && bit_is_set(*_ucsra, UDRE0)) {
221  *_udr = c;
222  sbi(*_ucsra, TXC0);
223  return 1;
224  }
226 
227  // If the output buffer is full, there's nothing for it other than to
228  // wait for the interrupt handler to empty it a bit
229  while (i == _tx_buffer_tail) {
230  if (bit_is_clear(SREG, SREG_I)) {
231  // Interrupts are disabled, so we'll have to poll the data
232  // register empty flag ourselves. If it is set, pretend an
233  // interrupt has happened and call the handler to free up
234  // space for us.
235  if(bit_is_set(*_ucsra, UDRE0))
237  } else {
238  // nop, the interrupt handler will free up space for us
239  }
240  }
241 
243  _tx_buffer_head = i;
244 
245  sbi(*_ucsrb, UDRIE0);
246 
247  return 1;
248 }
249 
250 #endif // whole file
volatile uint8_t *const _ucsrb
virtual size_t write(uint8_t)
const GLfloat * c
volatile rx_buffer_index_t _rx_buffer_head
virtual int read(void)
volatile uint8_t *const _ubrrh
volatile tx_buffer_index_t _tx_buffer_head
#define cbi(sfr, bit)
volatile uint8_t *const _ucsrc
uint8_t rx_buffer_index_t
virtual int availableForWrite(void)
virtual void flush(void)
#define SERIAL_TX_BUFFER_SIZE
virtual int available(void)
volatile rx_buffer_index_t _rx_buffer_tail
#define SERIAL_RX_BUFFER_SIZE
void serialEventRun(void) __attribute__((weak))
volatile tx_buffer_index_t _tx_buffer_tail
uint8_t tx_buffer_index_t
unsigned char _rx_buffer[SERIAL_RX_BUFFER_SIZE]
volatile uint8_t *const _udr
unsigned char byte
volatile uint8_t *const _ubrrl
unsigned char _tx_buffer[SERIAL_TX_BUFFER_SIZE]
void _tx_udr_empty_irq(void)
volatile uint8_t *const _ucsra
void begin(unsigned long baud)
#define sbi(sfr, bit)
virtual int peek(void)


arduino_daq
Author(s):
autogenerated on Mon Jun 10 2019 12:46:03