소스 검색

Merge pull request #8082 from thinkyhead/bf2_xon_xoff_due

[2.0.x] Arduino Due XON/XOFF implementation
Scott Lahteine 7 년 전
부모
커밋
c1c3ca6f8a
No account linked to committer's email address

+ 6
- 2
Marlin/src/HAL/HAL_AVR/MarlinSerial.cpp 파일 보기

@@ -84,7 +84,7 @@
84 84
     // Currently looking for: M108, M112, M410
85 85
     // If you alter the parser please don't forget to update the capabilities in Conditionals_post.h
86 86
 
87
-    FORCE_INLINE void emergency_parser(const unsigned char c) {
87
+    FORCE_INLINE void emergency_parser(const uint8_t c) {
88 88
 
89 89
       static e_parser_state state = state_RESET;
90 90
 
@@ -169,13 +169,16 @@
169 169
   #endif // EMERGENCY_PARSER
170 170
 
171 171
   FORCE_INLINE void store_rxd_char() {
172
+
172 173
     const ring_buffer_pos_t h = rx_buffer.head,
173 174
                             i = (ring_buffer_pos_t)(h + 1) & (ring_buffer_pos_t)(RX_BUFFER_SIZE - 1);
174 175
 
176
+    // Read the character
177
+    const uint8_t c = M_UDRx;
178
+
175 179
     // If the character is to be stored at the index just before the tail
176 180
     // (such that the head would advance to the current tail), the buffer is
177 181
     // critical, so don't write the character or advance the head.
178
-    const char c = M_UDRx;
179 182
     if (i != rx_buffer.tail) {
180 183
       rx_buffer.buffer[h] = c;
181 184
       rx_buffer.head = i;
@@ -194,6 +197,7 @@
194 197
     #endif
195 198
 
196 199
     #if ENABLED(SERIAL_XON_XOFF)
200
+
197 201
       // for high speed transfers, we can use XON/XOFF protocol to do
198 202
       // software handshake and avoid overruns.
199 203
       if ((xon_xoff_state & XON_XOFF_CHAR_MASK) == XON_CHAR) {

+ 29
- 46
Marlin/src/HAL/HAL_DUE/HAL_Due.h 파일 보기

@@ -29,37 +29,35 @@
29 29
 #ifndef _HAL_DUE_H
30 30
 #define _HAL_DUE_H
31 31
 
32
-// --------------------------------------------------------------------------
33
-// Includes
34
-// --------------------------------------------------------------------------
35
-
36 32
 #include <stdint.h>
37 33
 
38 34
 #include "Arduino.h"
39 35
 
40 36
 #include "fastio_Due.h"
41 37
 #include "watchdog_Due.h"
42
-
43 38
 #include "HAL_timers_Due.h"
44 39
 
45
-// --------------------------------------------------------------------------
40
+//
46 41
 // Defines
47
-// --------------------------------------------------------------------------
42
+//
48 43
 
49 44
 #if SERIAL_PORT == -1
50 45
   #define MYSERIAL SerialUSB
51 46
 #elif SERIAL_PORT == 0
52
-  #define MYSERIAL Serial
47
+  #define MYSERIAL customizedSerial
53 48
 #elif SERIAL_PORT == 1
54
-  #define MYSERIAL Serial1
49
+  #define MYSERIAL customizedSerial
55 50
 #elif SERIAL_PORT == 2
56
-  #define MYSERIAL Serial2
51
+  #define MYSERIAL customizedSerial
57 52
 #elif SERIAL_PORT == 3
58
-  #define MYSERIAL Serial3
53
+  #define MYSERIAL customizedSerial
59 54
 #endif
60 55
 
61 56
 #define _BV(bit) (1 << (bit))
62 57
 
58
+// We need the previous define before the include, or compilation bombs...
59
+#include "MarlinSerial_Due.h"
60
+
63 61
 #ifndef analogInputToDigitalPin
64 62
   #define analogInputToDigitalPin(p) ((p < 12u) ? (p) + 54u : -1)
65 63
 #endif
@@ -102,46 +100,43 @@ typedef int8_t pin_t;
102 100
 // Public Variables
103 101
 // --------------------------------------------------------------------------
104 102
 
105
-/** result of last ADC conversion */
106
-extern uint16_t HAL_adc_result;
103
+extern uint16_t HAL_adc_result;     // result of last ADC conversion
107 104
 
108
-// --------------------------------------------------------------------------
109
-// Public functions
110
-// --------------------------------------------------------------------------
111
-
112
-// Disable interrupts
113
-void cli(void);
114
-
115
-// Enable interrupts
116
-void sei(void);
117
-
118
-/** clear reset reason */
119
-void HAL_clear_reset_source (void);
105
+void cli(void);                     // Disable interrupts
106
+void sei(void);                     // Enable interrupts
120 107
 
121
-/** reset reason */
122
-uint8_t HAL_get_reset_source (void);
108
+void HAL_clear_reset_source(void);  // clear reset reason
109
+uint8_t HAL_get_reset_source(void); // get reset reason
123 110
 
124 111
 void _delay_ms(const int delay);
125 112
 
126 113
 int freeMemory(void);
127 114
 
128
-// SPI: Extended functions which take a channel number (hardware SPI only)
129
-/** Write single byte to specified SPI channel */
115
+/**
116
+ * SPI: Extended functions taking a channel number (hardware SPI only)
117
+ */
118
+
119
+// Write single byte to specified SPI channel
130 120
 void spiSend(uint32_t chan, byte b);
131
-/** Write buffer to specified SPI channel */
121
+
122
+// Write buffer to specified SPI channel
132 123
 void spiSend(uint32_t chan, const uint8_t* buf, size_t n);
133
-/** Read single byte from specified SPI channel */
124
+
125
+// Read single byte from specified SPI channel
134 126
 uint8_t spiRec(uint32_t chan);
135 127
 
128
+/**
129
+ * EEPROM
130
+ */
136 131
 
137
-// EEPROM
138 132
 void eeprom_write_byte(unsigned char *pos, unsigned char value);
139 133
 unsigned char eeprom_read_byte(unsigned char *pos);
140 134
 void eeprom_read_block (void *__dst, const void *__src, size_t __n);
141 135
 void eeprom_update_block (const void *__src, void *__dst, size_t __n);
142 136
 
143
-
144
-// ADC
137
+/**
138
+ * ADC
139
+ */
145 140
 
146 141
 #define HAL_ANALOG_SELECT(pin)
147 142
 
@@ -150,20 +145,13 @@ inline void HAL_adc_init(void) {}//todo
150 145
 #define HAL_START_ADC(pin)  HAL_adc_start_conversion(pin)
151 146
 #define HAL_READ_ADC        HAL_adc_result
152 147
 
153
-
154 148
 void HAL_adc_start_conversion(const uint8_t adc_pin);
155
-
156 149
 uint16_t HAL_adc_get_result(void);
157
-
158
-//
159 150
 uint16_t HAL_getAdcReading(uint8_t chan);
160
-
161 151
 void HAL_startAdcConversion(uint8_t chan);
162 152
 uint8_t HAL_pinToAdcChannel(int pin);
163
-
164 153
 uint16_t HAL_getAdcFreerun(uint8_t chan, bool wait_for_conversion = false);
165 154
 //uint16_t HAL_getAdcSuperSample(uint8_t chan);
166
-
167 155
 void HAL_enable_AdcFreerun(void);
168 156
 //void HAL_disable_AdcFreerun(uint8_t chan);
169 157
 
@@ -171,9 +159,4 @@ void HAL_enable_AdcFreerun(void);
171 159
 #define GET_PIN_MAP_INDEX(pin) pin
172 160
 #define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval)
173 161
 
174
-// --------------------------------------------------------------------------
175
-//
176
-// --------------------------------------------------------------------------
177
-
178 162
 #endif // _HAL_DUE_H
179
-

+ 95
- 0
Marlin/src/HAL/HAL_DUE/InterruptVectors_Due.cpp 파일 보기

@@ -0,0 +1,95 @@
1
+/**
2
+ * Marlin 3D Printer Firmware
3
+ * Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
+ *
5
+ * Based on Sprinter and grbl.
6
+ * Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
7
+ *
8
+ * This program is free software: you can redistribute it and/or modify
9
+ * it under the terms of the GNU General Public License as published by
10
+ * the Free Software Foundation, either version 3 of the License, or
11
+ * (at your option) any later version.
12
+ *
13
+ * This program is distributed in the hope that it will be useful,
14
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
15
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
16
+ * GNU General Public License for more details.
17
+ *
18
+ * You should have received a copy of the GNU General Public License
19
+ * along with this program.  If not, see <http://www.gnu.org/licenses/>.
20
+ *
21
+ */
22
+
23
+/**
24
+ * InterruptVectors_Due.cpp - This module relocates the Interrupt vector table to SRAM,
25
+ *  allowing to register new interrupt handlers at runtime. Specially valuable and needed
26
+ * because Arduino runtime allocates some interrupt handlers that we NEED to override to
27
+ * properly support extended functionality, as for example, USB host or USB device (MSD, MTP)
28
+ * and custom serial port handlers, and we don't actually want to modify and/or recompile the
29
+ * Arduino runtime. We just want to run as much as possible on Stock Arduino
30
+ *
31
+ * Copyright (c) 2017 Eduardo José Tagle. All right reserved
32
+ */
33
+#ifdef ARDUINO_ARCH_SAM
34
+
35
+#include "HAL_Due.h"
36
+#include "InterruptVectors_Due.h"
37
+
38
+/* The relocated Exception/Interrupt Table - Must be aligned to 128bytes,
39
+   as bits 0-6 on VTOR register are reserved and must be set to 0 */
40
+__attribute__ ((aligned(128)))
41
+static DeviceVectors ram_tab = { NULL };
42
+
43
+/**
44
+ * This function checks if the exception/interrupt table is already in SRAM or not.
45
+ * If it is not, then it copies the ROM table to the SRAM and relocates the table
46
+ * by reprogramming the NVIC registers
47
+ */
48
+static pfnISR_Handler* get_relocated_table_addr(void) {
49
+  // Get the address of the interrupt/exception table
50
+  uint32_t isrtab = SCB->VTOR;
51
+
52
+  // If already relocated, we are done!
53
+  if (isrtab >= IRAM0_ADDR)
54
+    return (pfnISR_Handler*)isrtab;
55
+
56
+  // Get the address of the table stored in FLASH
57
+  const pfnISR_Handler* romtab = (const pfnISR_Handler*)isrtab;
58
+
59
+  // Copy it to SRAM
60
+  memcpy(&ram_tab, romtab, sizeof(ram_tab));
61
+
62
+  // Disable global interrupts
63
+  CRITICAL_SECTION_START;
64
+
65
+  // Set the vector table base address to the SRAM copy
66
+  SCB->VTOR = (uint32_t)(&ram_tab);
67
+
68
+  // Reenable interrupts
69
+  CRITICAL_SECTION_END;
70
+
71
+  // Return the address of the table
72
+  return (pfnISR_Handler*)(&ram_tab);
73
+}
74
+
75
+pfnISR_Handler install_isr(IRQn_Type irq, pfnISR_Handler newHandler) {
76
+  // Get the address of the relocated table
77
+  const pfnISR_Handler *isrtab = get_relocated_table_addr();
78
+
79
+  // Disable global interrupts
80
+  CRITICAL_SECTION_START;
81
+
82
+  // Get the original handler
83
+  pfnISR_Handler oldHandler = isrtab[irq + 16];
84
+
85
+  // Install the new one
86
+  isrtab[irq + 16] = newHandler;
87
+
88
+  // Reenable interrupts
89
+  CRITICAL_SECTION_END;
90
+
91
+  // Return the original one
92
+  return oldHandler;
93
+}
94
+
95
+#endif

+ 52
- 0
Marlin/src/HAL/HAL_DUE/InterruptVectors_Due.h 파일 보기

@@ -0,0 +1,52 @@
1
+/**
2
+ * Marlin 3D Printer Firmware
3
+ * Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
+ *
5
+ * Based on Sprinter and grbl.
6
+ * Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
7
+ *
8
+ * This program is free software: you can redistribute it and/or modify
9
+ * it under the terms of the GNU General Public License as published by
10
+ * the Free Software Foundation, either version 3 of the License, or
11
+ * (at your option) any later version.
12
+ *
13
+ * This program is distributed in the hope that it will be useful,
14
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
15
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
16
+ * GNU General Public License for more details.
17
+ *
18
+ * You should have received a copy of the GNU General Public License
19
+ * along with this program.  If not, see <http://www.gnu.org/licenses/>.
20
+ *
21
+ */
22
+
23
+/**
24
+ * InterruptVectors_Due.h
25
+ *
26
+ * Copyright (c) 2017 Eduardo José Tagle. All right reserved
27
+ *
28
+ * This module relocates the Interrupt vector table to SRAM, allowing new
29
+ * interrupt handlers to be added at runtime. This is required because the
30
+ * Arduino runtime steals interrupt handlers that Marlin MUST use to support
31
+ * extended functionality such as USB hosts and USB devices (MSD, MTP) and
32
+ * custom serial port handlers. Rather than modifying and/or recompiling the
33
+ * Arduino runtime, We just want to run as much as possible on Stock Arduino.
34
+ *
35
+ * Copyright (c) 2017 Eduardo José Tagle. All right reserved
36
+ */
37
+
38
+#ifndef INTERRUPTVECTORS_DUE_H
39
+#define INTERRUPTVECTORS_DUE_H
40
+
41
+#include "../../inc/MarlinConfig.h"
42
+
43
+#ifdef ARDUINO_ARCH_SAM
44
+
45
+// ISR handler type
46
+typedef void (*pfnISR_Handler)(void);
47
+
48
+// Install a new interrupt vector handler for the given irq, returning the old one
49
+pfnISR_Handler install_isr(IRQn_Type irq, pfnISR_Handler newHandler);
50
+
51
+#endif // ARDUINO_ARCH_SAM
52
+#endif // INTERRUPTVECTORS_DUE_H

+ 680
- 0
Marlin/src/HAL/HAL_DUE/MarlinSerial_Due.cpp 파일 보기

@@ -0,0 +1,680 @@
1
+/**
2
+ * Marlin 3D Printer Firmware
3
+ * Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
+ *
5
+ * Based on Sprinter and grbl.
6
+ * Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
7
+ *
8
+ * This program is free software: you can redistribute it and/or modify
9
+ * it under the terms of the GNU General Public License as published by
10
+ * the Free Software Foundation, either version 3 of the License, or
11
+ * (at your option) any later version.
12
+ *
13
+ * This program is distributed in the hope that it will be useful,
14
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
15
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
16
+ * GNU General Public License for more details.
17
+ *
18
+ * You should have received a copy of the GNU General Public License
19
+ * along with this program.  If not, see <http://www.gnu.org/licenses/>.
20
+ *
21
+ */
22
+
23
+/**
24
+ * MarlinSerial_Due.cpp - Hardware serial library for Arduino DUE
25
+ * Copyright (c) 2017 Eduardo José Tagle. All right reserved
26
+ * Based on MarlinSerial for AVR, copyright (c) 2006 Nicholas Zambetti.  All right reserved.
27
+ */
28
+#ifdef ARDUINO_ARCH_SAM
29
+
30
+#include "../../inc/MarlinConfig.h"
31
+
32
+#include "MarlinSerial_Due.h"
33
+#include "InterruptVectors_Due.h"
34
+#include "../../Marlin.h"
35
+
36
+// Based on selected port, use the proper configuration
37
+#if SERIAL_PORT == 0
38
+  #define HWUART UART
39
+  #define HWUART_IRQ UART_IRQn
40
+  #define HWUART_IRQ_ID ID_UART
41
+#elif SERIAL_PORT == 1
42
+  #define HWUART USART0
43
+  #define HWUART_IRQ USART0_IRQn
44
+  #define HWUART_IRQ_ID ID_USART0
45
+#elif SERIAL_PORT == 2
46
+  #define HWUART USART1
47
+  #define HWUART_IRQ USART1_IRQn
48
+  #define HWUART_IRQ_ID ID_USART1
49
+#elif SERIAL_PORT == 3
50
+  #define HWUART USART3
51
+  #define HWUART_IRQ USART3_IRQn
52
+  #define HWUART_IRQ_ID ID_USART3
53
+#endif
54
+
55
+struct ring_buffer_r {
56
+  unsigned char buffer[RX_BUFFER_SIZE];
57
+  volatile ring_buffer_pos_t head, tail;
58
+};
59
+
60
+#if TX_BUFFER_SIZE > 0
61
+  struct ring_buffer_t {
62
+    unsigned char buffer[TX_BUFFER_SIZE];
63
+    volatile uint8_t head, tail;
64
+  };
65
+#endif
66
+
67
+ring_buffer_r rx_buffer = { { 0 }, 0, 0 };
68
+#if TX_BUFFER_SIZE > 0
69
+  ring_buffer_t tx_buffer = { { 0 }, 0, 0 };
70
+  static bool _written;
71
+#endif
72
+
73
+#if ENABLED(SERIAL_XON_XOFF)
74
+  constexpr uint8_t XON_XOFF_CHAR_SENT = 0x80;  // XON / XOFF Character was sent
75
+  constexpr uint8_t XON_XOFF_CHAR_MASK = 0x1F;  // XON / XOFF character to send
76
+  // XON / XOFF character definitions
77
+  constexpr uint8_t XON_CHAR  = 17;
78
+  constexpr uint8_t XOFF_CHAR = 19;
79
+  uint8_t xon_xoff_state = XON_XOFF_CHAR_SENT | XON_CHAR;
80
+
81
+  // Validate that RX buffer size is at least 4096 bytes- According to several experiments, on
82
+  // the original Arduino Due that uses a ATmega16U2 as USB to serial bridge, due to the introduced
83
+  // latencies, at least 2959 bytes of RX buffering (when transmitting at 250kbits/s) are required
84
+  // to avoid overflows.
85
+
86
+  #if RX_BUFFER_SIZE < 4096
87
+    #error Arduino DUE requires at least 4096 bytes of RX buffer to avoid buffer overflows when using XON/XOFF handshake
88
+  #endif
89
+#endif
90
+
91
+#if ENABLED(SERIAL_STATS_DROPPED_RX)
92
+  uint8_t rx_dropped_bytes = 0;
93
+#endif
94
+
95
+#if ENABLED(SERIAL_STATS_MAX_RX_QUEUED)
96
+  ring_buffer_pos_t rx_max_enqueued = 0;
97
+#endif
98
+
99
+// A SW memory barrier, to ensure GCC does not overoptimize loops
100
+#define sw_barrier() asm volatile("": : :"memory");
101
+
102
+#if ENABLED(EMERGENCY_PARSER)
103
+
104
+  #include "../../module/stepper.h"
105
+
106
+  // Currently looking for: M108, M112, M410
107
+  // If you alter the parser please don't forget to update the capabilities in Conditionals_post.h
108
+
109
+  FORCE_INLINE void emergency_parser(const uint8_t c) {
110
+
111
+    static e_parser_state state = state_RESET;
112
+
113
+    switch (state) {
114
+    case state_RESET:
115
+      switch (c) {
116
+        case ' ': break;
117
+        case 'N': state = state_N;      break;
118
+        case 'M': state = state_M;      break;
119
+        default: state = state_IGNORE;
120
+      }
121
+      break;
122
+
123
+    case state_N:
124
+      switch (c) {
125
+        case '0': case '1': case '2':
126
+        case '3': case '4': case '5':
127
+        case '6': case '7': case '8':
128
+        case '9': case '-': case ' ':   break;
129
+        case 'M': state = state_M;      break;
130
+        default:  state = state_IGNORE;
131
+      }
132
+      break;
133
+
134
+    case state_M:
135
+      switch (c) {
136
+        case ' ': break;
137
+        case '1': state = state_M1;     break;
138
+        case '4': state = state_M4;     break;
139
+        default: state = state_IGNORE;
140
+      }
141
+      break;
142
+
143
+    case state_M1:
144
+      switch (c) {
145
+        case '0': state = state_M10;    break;
146
+        case '1': state = state_M11;    break;
147
+        default: state = state_IGNORE;
148
+      }
149
+      break;
150
+
151
+    case state_M10:
152
+      state = (c == '8') ? state_M108 : state_IGNORE;
153
+      break;
154
+
155
+    case state_M11:
156
+      state = (c == '2') ? state_M112 : state_IGNORE;
157
+      break;
158
+
159
+    case state_M4:
160
+      state = (c == '1') ? state_M41 : state_IGNORE;
161
+      break;
162
+
163
+    case state_M41:
164
+      state = (c == '0') ? state_M410 : state_IGNORE;
165
+      break;
166
+
167
+    case state_IGNORE:
168
+      if (c == '\n') state = state_RESET;
169
+      break;
170
+
171
+    default:
172
+      if (c == '\n') {
173
+        switch (state) {
174
+          case state_M108:
175
+          wait_for_user = wait_for_heatup = false;
176
+          break;
177
+          case state_M112:
178
+          kill(PSTR(MSG_KILLED));
179
+          break;
180
+          case state_M410:
181
+          quickstop_stepper();
182
+          break;
183
+          default:
184
+          break;
185
+        }
186
+        state = state_RESET;
187
+      }
188
+    }
189
+  }
190
+
191
+#endif // EMERGENCY_PARSER
192
+
193
+FORCE_INLINE void store_rxd_char() {
194
+
195
+  const ring_buffer_pos_t h = rx_buffer.head,
196
+                          i = (ring_buffer_pos_t)(h + 1) & (ring_buffer_pos_t)(RX_BUFFER_SIZE - 1);
197
+
198
+    // Read the character
199
+  const uint8_t c = HWUART->UART_RHR;
200
+
201
+  // If the character is to be stored at the index just before the tail
202
+  // (such that the head would advance to the current tail), the buffer is
203
+  // critical, so don't write the character or advance the head.
204
+  if (i != rx_buffer.tail) {
205
+    rx_buffer.buffer[h] = c;
206
+    rx_buffer.head = i;
207
+  }
208
+  #if ENABLED(SERIAL_STATS_DROPPED_RX)
209
+    else if (!++rx_dropped_bytes) ++rx_dropped_bytes;
210
+  #endif
211
+
212
+#if ENABLED(SERIAL_STATS_MAX_RX_QUEUED)
213
+  // calculate count of bytes stored into the RX buffer
214
+  ring_buffer_pos_t rx_count = (ring_buffer_pos_t)(rx_buffer.head - rx_buffer.tail) & (ring_buffer_pos_t)(RX_BUFFER_SIZE - 1);
215
+  // Keep track of the maximum count of enqueued bytes
216
+  NOLESS(rx_max_enqueued, rx_count);
217
+#endif
218
+
219
+#if ENABLED(SERIAL_XON_XOFF)
220
+
221
+  // for high speed transfers, we can use XON/XOFF protocol to do
222
+  // software handshake and avoid overruns.
223
+  if ((xon_xoff_state & XON_XOFF_CHAR_MASK) == XON_CHAR) {
224
+
225
+    // calculate count of bytes stored into the RX buffer
226
+    ring_buffer_pos_t rx_count = (ring_buffer_pos_t)(rx_buffer.head - rx_buffer.tail) & (ring_buffer_pos_t)(RX_BUFFER_SIZE - 1);
227
+
228
+    // if we are above 12.5% of RX buffer capacity, send XOFF before
229
+    // we run out of RX buffer space .. We need 325 bytes @ 250kbits/s to
230
+    // let the host react and stop sending bytes. This translates to 13mS
231
+    // propagation time.
232
+    if (rx_count >= (RX_BUFFER_SIZE) / 8) {
233
+      // If TX interrupts are disabled and data register is empty,
234
+      // just write the byte to the data register and be done. This
235
+      // shortcut helps significantly improve the effective datarate
236
+      // at high (>500kbit/s) bitrates, where interrupt overhead
237
+      // becomes a slowdown.
238
+      if (!(HWUART->UART_IMR & UART_IMR_TXRDY) && (HWUART->UART_SR & UART_SR_TXRDY)) {
239
+        // Send an XOFF character
240
+        HWUART->UART_THR = XOFF_CHAR;
241
+
242
+        // And remember it was sent
243
+        xon_xoff_state = XOFF_CHAR | XON_XOFF_CHAR_SENT;
244
+      }
245
+      else {
246
+        // TX interrupts disabled, but buffer still not empty ... or
247
+        // TX interrupts enabled. Reenable TX ints and schedule XOFF
248
+        // character to be sent
249
+        #if TX_BUFFER_SIZE > 0
250
+          HWUART->UART_IER = UART_IER_TXRDY;
251
+          xon_xoff_state = XOFF_CHAR;
252
+        #else
253
+          // We are not using TX interrupts, we will have to send this manually
254
+          while (!(HWUART->UART_SR & UART_SR_TXRDY)) { sw_barrier(); };
255
+          HWUART->UART_THR = XOFF_CHAR;
256
+          // And remember we already sent it
257
+          xon_xoff_state = XOFF_CHAR | XON_XOFF_CHAR_SENT;
258
+        #endif
259
+      }
260
+    }
261
+  }
262
+#endif // SERIAL_XON_XOFF
263
+
264
+#if ENABLED(EMERGENCY_PARSER)
265
+  emergency_parser(c);
266
+#endif
267
+}
268
+
269
+#if TX_BUFFER_SIZE > 0
270
+
271
+  FORCE_INLINE void _tx_thr_empty_irq(void) {
272
+    // If interrupts are enabled, there must be more data in the output
273
+    // buffer.
274
+
275
+    #if ENABLED(SERIAL_XON_XOFF)
276
+      // Do a priority insertion of an XON/XOFF char, if needed.
277
+      const uint8_t state = xon_xoff_state;
278
+      if (!(state & XON_XOFF_CHAR_SENT)) {
279
+        HWUART->UART_THR = state & XON_XOFF_CHAR_MASK;
280
+        xon_xoff_state = state | XON_XOFF_CHAR_SENT;
281
+      }
282
+      else
283
+    #endif
284
+      { // Send the next byte
285
+        const uint8_t t = tx_buffer.tail, c = tx_buffer.buffer[t];
286
+        tx_buffer.tail = (t + 1) & (TX_BUFFER_SIZE - 1);
287
+        HWUART->UART_THR = c;
288
+      }
289
+
290
+    // Disable interrupts if the buffer is empty
291
+    if (tx_buffer.head == tx_buffer.tail)
292
+      HWUART->UART_IDR = UART_IDR_TXRDY;
293
+  }
294
+
295
+#endif // TX_BUFFER_SIZE
296
+
297
+static void UART_ISR(void) {
298
+  uint32_t status = HWUART->UART_SR;
299
+
300
+  // Did we receive data?
301
+  if (status & UART_SR_RXRDY)
302
+    store_rxd_char();
303
+
304
+  #if TX_BUFFER_SIZE > 0
305
+    // Do we have something to send, and TX interrupts are enabled (meaning something to send) ?
306
+    if ((status & UART_SR_TXRDY) && (HWUART->UART_IMR & UART_IMR_TXRDY))
307
+      _tx_thr_empty_irq();
308
+  #endif
309
+
310
+  // Acknowledge errors
311
+  if ((status & UART_SR_OVRE) || (status & UART_SR_FRAME)) {
312
+    // TODO: error reporting outside ISR
313
+    HWUART->UART_CR = UART_CR_RSTSTA;
314
+  }
315
+}
316
+
317
+// Public Methods
318
+
319
+void MarlinSerial::begin(const long baud_setting) {
320
+
321
+  // Disable UART interrupt in NVIC
322
+  NVIC_DisableIRQ( HWUART_IRQ );
323
+
324
+  // Disable clock
325
+  pmc_disable_periph_clk( HWUART_IRQ_ID );
326
+
327
+  // Configure PMC
328
+  pmc_enable_periph_clk( HWUART_IRQ_ID );
329
+
330
+  // Disable PDC channel
331
+  HWUART->UART_PTCR = UART_PTCR_RXTDIS | UART_PTCR_TXTDIS;
332
+
333
+  // Reset and disable receiver and transmitter
334
+  HWUART->UART_CR = UART_CR_RSTRX | UART_CR_RSTTX | UART_CR_RXDIS | UART_CR_TXDIS;
335
+
336
+  // Configure mode: 8bit, No parity, 1 bit stop
337
+  HWUART->UART_MR = UART_MR_CHMODE_NORMAL | US_MR_CHRL_8_BIT | US_MR_NBSTOP_1_BIT | UART_MR_PAR_NO;
338
+
339
+  // Configure baudrate (asynchronous, no oversampling)
340
+  HWUART->UART_BRGR = (SystemCoreClock / (baud_setting << 4));
341
+
342
+  // Configure interrupts
343
+  HWUART->UART_IDR = 0xFFFFFFFF;
344
+  HWUART->UART_IER = UART_IER_RXRDY | UART_IER_OVRE | UART_IER_FRAME;
345
+
346
+  // Install interrupt handler
347
+  install_isr(HWUART_IRQ, UART_ISR);
348
+
349
+  // Enable UART interrupt in NVIC
350
+  NVIC_EnableIRQ(HWUART_IRQ);
351
+
352
+  // Enable receiver and transmitter
353
+  HWUART->UART_CR = UART_CR_RXEN | UART_CR_TXEN;
354
+
355
+  #if TX_BUFFER_SIZE > 0
356
+    _written = false;
357
+  #endif
358
+}
359
+
360
+void MarlinSerial::end() {
361
+  // Disable UART interrupt in NVIC
362
+  NVIC_DisableIRQ( HWUART_IRQ );
363
+
364
+  pmc_disable_periph_clk( HWUART_IRQ_ID );
365
+}
366
+
367
+void MarlinSerial::checkRx(void) {
368
+  if (HWUART->UART_SR & UART_SR_RXRDY) {
369
+    CRITICAL_SECTION_START;
370
+    store_rxd_char();
371
+    CRITICAL_SECTION_END;
372
+  }
373
+}
374
+
375
+int MarlinSerial::peek(void) {
376
+  CRITICAL_SECTION_START;
377
+  const int v = rx_buffer.head == rx_buffer.tail ? -1 : rx_buffer.buffer[rx_buffer.tail];
378
+  CRITICAL_SECTION_END;
379
+  return v;
380
+}
381
+
382
+int MarlinSerial::read(void) {
383
+  int v;
384
+  CRITICAL_SECTION_START;
385
+  const ring_buffer_pos_t t = rx_buffer.tail;
386
+  if (rx_buffer.head == t)
387
+    v = -1;
388
+  else {
389
+    v = rx_buffer.buffer[t];
390
+    rx_buffer.tail = (ring_buffer_pos_t)(t + 1) & (RX_BUFFER_SIZE - 1);
391
+
392
+  #if ENABLED(SERIAL_XON_XOFF)
393
+    if ((xon_xoff_state & XON_XOFF_CHAR_MASK) == XOFF_CHAR) {
394
+      // Get count of bytes in the RX buffer
395
+      ring_buffer_pos_t rx_count = (ring_buffer_pos_t)(rx_buffer.head - rx_buffer.tail) & (ring_buffer_pos_t)(RX_BUFFER_SIZE - 1);
396
+      // When below 10% of RX buffer capacity, send XON before
397
+      // running out of RX buffer bytes
398
+      if (rx_count < (RX_BUFFER_SIZE) / 10) {
399
+        xon_xoff_state = XON_CHAR | XON_XOFF_CHAR_SENT;
400
+        CRITICAL_SECTION_END;       // End critical section before returning!
401
+        writeNoHandshake(XON_CHAR);
402
+        return v;
403
+      }
404
+    }
405
+  #endif
406
+  }
407
+  CRITICAL_SECTION_END;
408
+  return v;
409
+}
410
+
411
+ring_buffer_pos_t MarlinSerial::available(void) {
412
+  CRITICAL_SECTION_START;
413
+  const ring_buffer_pos_t h = rx_buffer.head, t = rx_buffer.tail;
414
+  CRITICAL_SECTION_END;
415
+  return (ring_buffer_pos_t)(RX_BUFFER_SIZE + h - t) & (RX_BUFFER_SIZE - 1);
416
+}
417
+
418
+void MarlinSerial::flush(void) {
419
+  // Don't change this order of operations. If the RX interrupt occurs between
420
+  // reading rx_buffer_head and updating rx_buffer_tail, the previous rx_buffer_head
421
+  // may be written to rx_buffer_tail, making the buffer appear full rather than empty.
422
+  CRITICAL_SECTION_START;
423
+  rx_buffer.head = rx_buffer.tail;
424
+  CRITICAL_SECTION_END;
425
+
426
+#if ENABLED(SERIAL_XON_XOFF)
427
+  if ((xon_xoff_state & XON_XOFF_CHAR_MASK) == XOFF_CHAR) {
428
+    xon_xoff_state = XON_CHAR | XON_XOFF_CHAR_SENT;
429
+    writeNoHandshake(XON_CHAR);
430
+  }
431
+#endif
432
+}
433
+
434
+#if TX_BUFFER_SIZE > 0
435
+  uint8_t MarlinSerial::availableForWrite(void) {
436
+    CRITICAL_SECTION_START;
437
+    const uint8_t h = tx_buffer.head, t = tx_buffer.tail;
438
+    CRITICAL_SECTION_END;
439
+    return (uint8_t)(TX_BUFFER_SIZE + h - t) & (TX_BUFFER_SIZE - 1);
440
+  }
441
+
442
+  void MarlinSerial::write(const uint8_t c) {
443
+    #if ENABLED(SERIAL_XON_XOFF)
444
+      const uint8_t state = xon_xoff_state;
445
+      if (!(state & XON_XOFF_CHAR_SENT)) {
446
+        // Send 2 chars: XON/XOFF, then a user-specified char
447
+        writeNoHandshake(state & XON_XOFF_CHAR_MASK);
448
+        xon_xoff_state = state | XON_XOFF_CHAR_SENT;
449
+      }
450
+    #endif
451
+    writeNoHandshake(c);
452
+  }
453
+
454
+  void MarlinSerial::writeNoHandshake(const uint8_t c) {
455
+    _written = true;
456
+    CRITICAL_SECTION_START;
457
+    bool emty = (tx_buffer.head == tx_buffer.tail);
458
+    CRITICAL_SECTION_END;
459
+    // If the buffer and the data register is empty, just write the byte
460
+    // to the data register and be done. This shortcut helps
461
+    // significantly improve the effective datarate at high (>
462
+    // 500kbit/s) bitrates, where interrupt overhead becomes a slowdown.
463
+    if (emty && (HWUART->UART_SR & UART_SR_TXRDY)) {
464
+      CRITICAL_SECTION_START;
465
+        HWUART->UART_THR = c;
466
+        HWUART->UART_IER = UART_IER_TXRDY;
467
+      CRITICAL_SECTION_END;
468
+      return;
469
+    }
470
+    const uint8_t i = (tx_buffer.head + 1) & (TX_BUFFER_SIZE - 1);
471
+
472
+    // If the output buffer is full, there's nothing for it other than to
473
+    // wait for the interrupt handler to empty it a bit
474
+    while (i == tx_buffer.tail) {
475
+      if (__get_PRIMASK()) {
476
+        // Interrupts are disabled, so we'll have to poll the data
477
+        // register empty flag ourselves. If it is set, pretend an
478
+        // interrupt has happened and call the handler to free up
479
+        // space for us.
480
+        if (HWUART->UART_SR & UART_SR_TXRDY)
481
+          _tx_thr_empty_irq();
482
+      }
483
+      else {
484
+        // nop, the interrupt handler will free up space for us
485
+      }
486
+      sw_barrier();
487
+    }
488
+
489
+    tx_buffer.buffer[tx_buffer.head] = c;
490
+    { CRITICAL_SECTION_START;
491
+        tx_buffer.head = i;
492
+        HWUART->UART_IER = UART_IER_TXRDY;
493
+      CRITICAL_SECTION_END;
494
+    }
495
+    return;
496
+  }
497
+
498
+  void MarlinSerial::flushTX(void) {
499
+    // TX
500
+    // If we have never written a byte, no need to flush.
501
+    if (!_written)
502
+      return;
503
+
504
+    while ((HWUART->UART_IMR & UART_IMR_TXRDY) || !(HWUART->UART_SR & UART_SR_TXEMPTY)) {
505
+      if (__get_PRIMASK())
506
+        if ((HWUART->UART_SR & UART_SR_TXRDY))
507
+          _tx_thr_empty_irq();
508
+      sw_barrier();
509
+    }
510
+    // If we get here, nothing is queued anymore (TX interrupts are disabled) and
511
+    // the hardware finished tranmission (TXEMPTY is set).
512
+  }
513
+
514
+#else // TX_BUFFER_SIZE == 0
515
+
516
+  void MarlinSerial::write(const uint8_t c) {
517
+    #if ENABLED(SERIAL_XON_XOFF)
518
+      // Do a priority insertion of an XON/XOFF char, if needed.
519
+      const uint8_t state = xon_xoff_state;
520
+      if (!(state & XON_XOFF_CHAR_SENT)) {
521
+        writeNoHandshake(state & XON_XOFF_CHAR_MASK);
522
+        xon_xoff_state = state | XON_XOFF_CHAR_SENT;
523
+      }
524
+    #endif
525
+    writeNoHandshake(c);
526
+  }
527
+
528
+  void MarlinSerial::writeNoHandshake(const uint8_t c) {
529
+    while (!(HWUART->UART_SR & UART_SR_TXRDY)) { sw_barrier(); };
530
+    HWUART->UART_THR = c;
531
+  }
532
+
533
+#endif // TX_BUFFER_SIZE == 0
534
+
535
+/**
536
+* Imports from print.h
537
+*/
538
+
539
+void MarlinSerial::print(char c, int base) {
540
+  print((long)c, base);
541
+}
542
+
543
+void MarlinSerial::print(unsigned char b, int base) {
544
+  print((unsigned long)b, base);
545
+}
546
+
547
+void MarlinSerial::print(int n, int base) {
548
+  print((long)n, base);
549
+}
550
+
551
+void MarlinSerial::print(unsigned int n, int base) {
552
+  print((unsigned long)n, base);
553
+}
554
+
555
+void MarlinSerial::print(long n, int base) {
556
+  if (base == 0)
557
+    write(n);
558
+  else if (base == 10) {
559
+    if (n < 0) {
560
+      print('-');
561
+      n = -n;
562
+    }
563
+    printNumber(n, 10);
564
+  }
565
+  else
566
+    printNumber(n, base);
567
+}
568
+
569
+void MarlinSerial::print(unsigned long n, int base) {
570
+  if (base == 0) write(n);
571
+  else printNumber(n, base);
572
+}
573
+
574
+void MarlinSerial::print(double n, int digits) {
575
+  printFloat(n, digits);
576
+}
577
+
578
+void MarlinSerial::println(void) {
579
+  print('\r');
580
+  print('\n');
581
+}
582
+
583
+void MarlinSerial::println(const String& s) {
584
+  print(s);
585
+  println();
586
+}
587
+
588
+void MarlinSerial::println(const char c[]) {
589
+  print(c);
590
+  println();
591
+}
592
+
593
+void MarlinSerial::println(char c, int base) {
594
+  print(c, base);
595
+  println();
596
+}
597
+
598
+void MarlinSerial::println(unsigned char b, int base) {
599
+  print(b, base);
600
+  println();
601
+}
602
+
603
+void MarlinSerial::println(int n, int base) {
604
+  print(n, base);
605
+  println();
606
+}
607
+
608
+void MarlinSerial::println(unsigned int n, int base) {
609
+  print(n, base);
610
+  println();
611
+}
612
+
613
+void MarlinSerial::println(long n, int base) {
614
+  print(n, base);
615
+  println();
616
+}
617
+
618
+void MarlinSerial::println(unsigned long n, int base) {
619
+  print(n, base);
620
+  println();
621
+}
622
+
623
+void MarlinSerial::println(double n, int digits) {
624
+  print(n, digits);
625
+  println();
626
+}
627
+
628
+// Private Methods
629
+
630
+void MarlinSerial::printNumber(unsigned long n, uint8_t base) {
631
+  if (n) {
632
+    unsigned char buf[8 * sizeof(long)]; // Enough space for base 2
633
+    int8_t i = 0;
634
+    while (n) {
635
+      buf[i++] = n % base;
636
+      n /= base;
637
+    }
638
+    while (i--)
639
+      print((char)(buf[i] + (buf[i] < 10 ? '0' : 'A' - 10)));
640
+  }
641
+  else
642
+    print('0');
643
+}
644
+
645
+void MarlinSerial::printFloat(double number, uint8_t digits) {
646
+  // Handle negative numbers
647
+  if (number < 0.0) {
648
+    print('-');
649
+    number = -number;
650
+  }
651
+
652
+  // Round correctly so that print(1.999, 2) prints as "2.00"
653
+  double rounding = 0.5;
654
+  for (uint8_t i = 0; i < digits; ++i)
655
+    rounding *= 0.1;
656
+
657
+  number += rounding;
658
+
659
+  // Extract the integer part of the number and print it
660
+  unsigned long int_part = (unsigned long)number;
661
+  double remainder = number - (double)int_part;
662
+  print(int_part);
663
+
664
+  // Print the decimal point, but only if there are digits beyond
665
+  if (digits) {
666
+    print('.');
667
+    // Extract digits from the remainder one at a time
668
+    while (digits--) {
669
+      remainder *= 10.0;
670
+      int toPrint = int(remainder);
671
+      print(toPrint);
672
+      remainder -= toPrint;
673
+    }
674
+  }
675
+}
676
+
677
+// Preinstantiate
678
+MarlinSerial customizedSerial;
679
+
680
+#endif // ARDUINO_ARCH_SAM

+ 142
- 0
Marlin/src/HAL/HAL_DUE/MarlinSerial_Due.h 파일 보기

@@ -0,0 +1,142 @@
1
+/**
2
+ * Marlin 3D Printer Firmware
3
+ * Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
+ *
5
+ * Based on Sprinter and grbl.
6
+ * Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
7
+ *
8
+ * This program is free software: you can redistribute it and/or modify
9
+ * it under the terms of the GNU General Public License as published by
10
+ * the Free Software Foundation, either version 3 of the License, or
11
+ * (at your option) any later version.
12
+ *
13
+ * This program is distributed in the hope that it will be useful,
14
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
15
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
16
+ * GNU General Public License for more details.
17
+ *
18
+ * You should have received a copy of the GNU General Public License
19
+ * along with this program.  If not, see <http://www.gnu.org/licenses/>.
20
+ *
21
+ */
22
+
23
+/**
24
+ * MarlinSerial_Due.h - Hardware serial library for Arduino DUE
25
+ * Copyright (c) 2017 Eduardo José Tagle. All right reserved
26
+ * Based on MarlinSerial for AVR, copyright (c) 2006 Nicholas Zambetti.  All right reserved.
27
+ */
28
+
29
+#ifndef MARLINSERIAL_DUE_H
30
+#define MARLINSERIAL_DUE_H
31
+
32
+#include "../../inc/MarlinConfig.h"
33
+
34
+#include <WString.h>
35
+
36
+#ifndef SERIAL_PORT
37
+  #define SERIAL_PORT 0
38
+#endif
39
+
40
+#define DEC 10
41
+#define HEX 16
42
+#define OCT 8
43
+#define BIN 2
44
+#define BYTE 0
45
+
46
+// Define constants and variables for buffering incoming serial data.  We're
47
+// using a ring buffer (I think), in which rx_buffer_head is the index of the
48
+// location to which to write the next incoming character and rx_buffer_tail
49
+// is the index of the location from which to read.
50
+// 256 is the max limit due to uint8_t head and tail. Use only powers of 2. (...,16,32,64,128,256)
51
+#ifndef RX_BUFFER_SIZE
52
+  #define RX_BUFFER_SIZE 128
53
+#endif
54
+#ifndef TX_BUFFER_SIZE
55
+  #define TX_BUFFER_SIZE 32
56
+#endif
57
+
58
+#if ENABLED(SERIAL_XON_XOFF) && RX_BUFFER_SIZE < 1024
59
+  #error "XON/XOFF requires RX_BUFFER_SIZE >= 1024 for reliable transfers without drops."
60
+#endif
61
+
62
+#if !IS_POWER_OF_2(RX_BUFFER_SIZE) || RX_BUFFER_SIZE < 2
63
+  #error "RX_BUFFER_SIZE must be a power of 2 greater than 1."
64
+#endif
65
+
66
+#if TX_BUFFER_SIZE && (TX_BUFFER_SIZE < 2 || TX_BUFFER_SIZE > 256 || !IS_POWER_OF_2(TX_BUFFER_SIZE))
67
+  #error "TX_BUFFER_SIZE must be 0 or a power of 2 greater than 1."
68
+#endif
69
+
70
+#if RX_BUFFER_SIZE > 256
71
+  typedef uint16_t ring_buffer_pos_t;
72
+#else
73
+  typedef uint8_t ring_buffer_pos_t;
74
+#endif
75
+
76
+#if ENABLED(SERIAL_STATS_DROPPED_RX)
77
+  extern uint8_t rx_dropped_bytes;
78
+#endif
79
+
80
+#if ENABLED(SERIAL_STATS_MAX_RX_QUEUED)
81
+  extern ring_buffer_pos_t rx_max_enqueued;
82
+#endif
83
+
84
+class MarlinSerial {
85
+
86
+public:
87
+  MarlinSerial() {};
88
+  static void begin(const long);
89
+  static void end();
90
+  static int peek(void);
91
+  static int read(void);
92
+  static void flush(void);
93
+  static ring_buffer_pos_t available(void);
94
+  static void checkRx(void);
95
+  static void write(const uint8_t c);
96
+  #if TX_BUFFER_SIZE > 0
97
+    static uint8_t availableForWrite(void);
98
+    static void flushTX(void);
99
+  #endif
100
+  static void writeNoHandshake(const uint8_t c);
101
+
102
+  #if ENABLED(SERIAL_STATS_DROPPED_RX)
103
+    FORCE_INLINE static uint32_t dropped() { return rx_dropped_bytes; }
104
+  #endif
105
+
106
+  #if ENABLED(SERIAL_STATS_MAX_RX_QUEUED)
107
+    FORCE_INLINE static ring_buffer_pos_t rxMaxEnqueued() { return rx_max_enqueued; }
108
+  #endif
109
+
110
+  static FORCE_INLINE void write(const char* str) { while (*str) write(*str++); }
111
+  static FORCE_INLINE void write(const uint8_t* buffer, size_t size) { while (size--) write(*buffer++); }
112
+  static FORCE_INLINE void print(const String& s) { for (int i = 0; i < (int)s.length(); i++) write(s[i]); }
113
+  static FORCE_INLINE void print(const char* str) { write(str); }
114
+
115
+  static void print(char, int = BYTE);
116
+  static void print(unsigned char, int = BYTE);
117
+  static void print(int, int = DEC);
118
+  static void print(unsigned int, int = DEC);
119
+  static void print(long, int = DEC);
120
+  static void print(unsigned long, int = DEC);
121
+  static void print(double, int = 2);
122
+
123
+  static void println(const String& s);
124
+  static void println(const char[]);
125
+  static void println(char, int = BYTE);
126
+  static void println(unsigned char, int = BYTE);
127
+  static void println(int, int = DEC);
128
+  static void println(unsigned int, int = DEC);
129
+  static void println(long, int = DEC);
130
+  static void println(unsigned long, int = DEC);
131
+  static void println(double, int = 2);
132
+  static void println(void);
133
+  operator bool() { return true; }
134
+
135
+private:
136
+  static void printNumber(unsigned long, const uint8_t);
137
+  static void printFloat(double, uint8_t);
138
+};
139
+
140
+extern MarlinSerial customizedSerial;
141
+
142
+#endif // MARLINSERIAL_DUE_H

+ 23
- 16
Marlin/src/core/serial.h 파일 보기

@@ -25,24 +25,10 @@
25 25
 
26 26
 #include "../inc/MarlinConfig.h"
27 27
 
28
-//todo: HAL: breaks encapsulation
29
-// For AVR only, define a serial interface based on configuration
30
-#ifdef __AVR__
31
-  #ifdef USBCON
32
-    #include "HardwareSerial.h"
33
-    #if ENABLED(BLUETOOTH)
34
-      #define MYSERIAL bluetoothSerial
35
-    #else
36
-      #define MYSERIAL Serial
37
-    #endif // BLUETOOTH
38
-  #else
39
-    #include "../HAL/HAL_AVR/MarlinSerial.h"
40
-    #define MYSERIAL customizedSerial
41
-  #endif
28
+#if HAS_ABL && ENABLED(DEBUG_LEVELING_FEATURE)
29
+  #include "../libs/vector_3.h"
42 30
 #endif
43 31
 
44
-#include "../libs/vector_3.h"
45
-
46 32
 /**
47 33
  * Define debug bit-masks
48 34
  */
@@ -58,6 +44,27 @@ enum DebugFlags {
58 44
   DEBUG_ALL           = 0xFF
59 45
 };
60 46
 
47
+//todo: HAL: breaks encapsulation
48
+// For AVR only, define a serial interface based on configuration
49
+#ifdef __AVR__
50
+  #ifdef USBCON
51
+    #include "HardwareSerial.h"
52
+    #if ENABLED(BLUETOOTH)
53
+      #define MYSERIAL bluetoothSerial
54
+    #else
55
+      #define MYSERIAL Serial
56
+    #endif // BLUETOOTH
57
+  #else
58
+    #include "../HAL/HAL_AVR/MarlinSerial.h"
59
+    #define MYSERIAL customizedSerial
60
+  #endif
61
+#endif
62
+
63
+#ifdef ARDUINO_ARCH_SAM
64
+  // To pull the Serial port definitions and overrides
65
+  #include "../HAL/HAL_DUE/MarlinSerial_Due.h"
66
+#endif
67
+
61 68
 extern uint8_t marlin_debug_flags;
62 69
 #define DEBUGGING(F) (marlin_debug_flags & (DEBUG_## F))
63 70
 

+ 202
- 238
frameworks/CMSIS/LPC1768/driver/debug_frmwrk.c 파일 보기

@@ -1,11 +1,11 @@
1 1
 /**********************************************************************
2
-* $Id$		debug_frmwrk.c				2010-05-21
3
-*//**
4
-* @file		debug_frmwrk.c
5
-* @brief	Contains some utilities that used for debugging through UART
6
-* @version	2.0
7
-* @date		21. May. 2010
8
-* @author	NXP MCU SW Application Team
2
+* $Id$    debug_frmwrk.c        2010-05-21
3
+*
4
+* @file   debug_frmwrk.c
5
+* @brief  Contains some utilities that used for debugging through UART
6
+* @version  2.0
7
+* @date   21. May. 2010
8
+* @author NXP MCU SW Application Team
9 9
 *
10 10
 * Copyright(C) 2010, NXP Semiconductor
11 11
 * All rights reserved.
@@ -37,12 +37,13 @@
37 37
  * otherwise the default FW library configuration file must be included instead
38 38
  */
39 39
 #ifdef __BUILD_WITH_EXAMPLE__
40
-#include "lpc17xx_libcfg.h"
40
+  #include "lpc17xx_libcfg.h"
41 41
 #else
42
-#include "lpc17xx_libcfg_default.h"
43
-#endif /* __BUILD_WITH_EXAMPLE__ */
42
+  #include "lpc17xx_libcfg_default.h"
43
+#endif
44 44
 
45 45
 #ifdef _DBGFWK
46
+
46 47
 /* Debug framework */
47 48
 static Bool debug_frmwrk_initialized = FALSE;
48 49
 
@@ -59,284 +60,247 @@ uint8_t (*_db_get_char)(LPC_UART_TypeDef *UARTx) = UARTGetChar;
59 60
 
60 61
 
61 62
 /*********************************************************************//**
62
- * @brief		Puts a character to UART port
63
- * @param[in]	UARTx	Pointer to UART peripheral
64
- * @param[in]	ch		Character to put
65
- * @return		None
63
+ * @brief   Puts a character to UART port
64
+ * @param[in] UARTx Pointer to UART peripheral
65
+ * @param[in] ch    Character to put
66
+ * @return    None
66 67
  **********************************************************************/
67
-void UARTPutChar (LPC_UART_TypeDef *UARTx, uint8_t ch)
68
-{
68
+void UARTPutChar(LPC_UART_TypeDef *UARTx, uint8_t ch) {
69 69
   if (debug_frmwrk_initialized)
70
-	  UART_Send(UARTx, &ch, 1, BLOCKING);
70
+    UART_Send(UARTx, &ch, 1, BLOCKING);
71 71
 }
72 72
 
73
-
74 73
 /*********************************************************************//**
75
- * @brief		Get a character to UART port
76
- * @param[in]	UARTx	Pointer to UART peripheral
77
- * @return		character value that returned
74
+ * @brief   Get a character to UART port
75
+ * @param[in] UARTx Pointer to UART peripheral
76
+ * @return    character value that returned
78 77
  **********************************************************************/
79
-uint8_t UARTGetChar (LPC_UART_TypeDef *UARTx)
80
-{
78
+uint8_t UARTGetChar(LPC_UART_TypeDef *UARTx) {
81 79
   uint8_t tmp = 0;
82
-  
80
+
83 81
   if (debug_frmwrk_initialized)
84 82
     UART_Receive(UARTx, &tmp, 1, BLOCKING);
85
-    
86
-	return(tmp);
87
-}
88 83
 
84
+  return(tmp);
85
+}
89 86
 
90 87
 /*********************************************************************//**
91
- * @brief		Puts a string to UART port
92
- * @param[in]	UARTx 	Pointer to UART peripheral
93
- * @param[in]	str 	string to put
94
- * @return		None
88
+ * @brief   Puts a string to UART port
89
+ * @param[in] UARTx   Pointer to UART peripheral
90
+ * @param[in] str   string to put
91
+ * @return    None
95 92
  **********************************************************************/
96
-void UARTPuts(LPC_UART_TypeDef *UARTx, const void *str)
97
-{
98
-  uint8_t *s = (uint8_t *) str;
99
-  
100
-  if (!debug_frmwrk_initialized)
101
-    return;
102
-
103
-	while (*s)
104
-	{
105
-		UARTPutChar(UARTx, *s++);
106
-	}
107
-}
93
+void UARTPuts(LPC_UART_TypeDef *UARTx, const void *str) {
94
+  if (!debug_frmwrk_initialized) return;
108 95
 
96
+  uint8_t *s = (uint8_t*)str;
97
+  while (*s) UARTPutChar(UARTx, *s++);
98
+}
109 99
 
110 100
 /*********************************************************************//**
111
- * @brief		Puts a string to UART port and print new line
112
- * @param[in]	UARTx	Pointer to UART peripheral
113
- * @param[in]	str		String to put
114
- * @return		None
101
+ * @brief   Puts a string to UART port and print new line
102
+ * @param[in] UARTx Pointer to UART peripheral
103
+ * @param[in] str   String to put
104
+ * @return    None
115 105
  **********************************************************************/
116
-void UARTPuts_(LPC_UART_TypeDef *UARTx, const void *str)
117
-{
118
-  if (!debug_frmwrk_initialized)
119
-    return;
106
+void UARTPuts_(LPC_UART_TypeDef *UARTx, const void *str) {
107
+  if (!debug_frmwrk_initialized) return;
120 108
 
121
-	UARTPuts (UARTx, str);
122
-	UARTPuts (UARTx, "\n\r");
109
+  UARTPuts (UARTx, str);
110
+  UARTPuts (UARTx, "\n\r");
123 111
 }
124 112
 
125
-
126 113
 /*********************************************************************//**
127
- * @brief		Puts a decimal number to UART port
128
- * @param[in]	UARTx	Pointer to UART peripheral
129
- * @param[in]	decnum	Decimal number (8-bit long)
130
- * @return		None
114
+ * @brief   Puts a decimal number to UART port
115
+ * @param[in] UARTx Pointer to UART peripheral
116
+ * @param[in] decnum  Decimal number (8-bit long)
117
+ * @return    None
131 118
  **********************************************************************/
132
-void UARTPutDec(LPC_UART_TypeDef *UARTx, uint8_t decnum)
133
-{
134
-  if (!debug_frmwrk_initialized)
135
-    return;
136
-
137
-	uint8_t c1=decnum%10;
138
-	uint8_t c2=(decnum/10)%10;
139
-	uint8_t c3=(decnum/100)%10;
140
-	UARTPutChar(UARTx, '0'+c3);
141
-	UARTPutChar(UARTx, '0'+c2);
142
-	UARTPutChar(UARTx, '0'+c1);
119
+void UARTPutDec(LPC_UART_TypeDef *UARTx, uint8_t decnum) {
120
+  if (!debug_frmwrk_initialized) return;
121
+
122
+  uint8_t c1 = decnum%10;
123
+  uint8_t c2 = (decnum /             10) % 10;
124
+  uint8_t c3 = (decnum /            100) % 10;
125
+  UARTPutChar(UARTx, '0'+c3);
126
+  UARTPutChar(UARTx, '0'+c2);
127
+  UARTPutChar(UARTx, '0'+c1);
143 128
 }
144 129
 
145 130
 /*********************************************************************//**
146
- * @brief		Puts a decimal number to UART port
147
- * @param[in]	UARTx	Pointer to UART peripheral
148
- * @param[in]	decnum	Decimal number (8-bit long)
149
- * @return		None
131
+ * @brief   Puts a decimal number to UART port
132
+ * @param[in] UARTx Pointer to UART peripheral
133
+ * @param[in] decnum  Decimal number (8-bit long)
134
+ * @return    None
150 135
  **********************************************************************/
151
-void UARTPutDec16(LPC_UART_TypeDef *UARTx, uint16_t decnum)
152
-{  
153
-  if (!debug_frmwrk_initialized)
154
-    return;
155
-
156
-	uint8_t c1=decnum%10;
157
-	uint8_t c2=(decnum/10)%10;
158
-	uint8_t c3=(decnum/100)%10;
159
-	uint8_t c4=(decnum/1000)%10;
160
-	uint8_t c5=(decnum/10000)%10;
161
-	UARTPutChar(UARTx, '0'+c5);
162
-	UARTPutChar(UARTx, '0'+c4);
163
-	UARTPutChar(UARTx, '0'+c3);
164
-	UARTPutChar(UARTx, '0'+c2);
165
-	UARTPutChar(UARTx, '0'+c1);
136
+void UARTPutDec16(LPC_UART_TypeDef *UARTx, uint16_t decnum) {
137
+  if (!debug_frmwrk_initialized) return;
138
+
139
+  uint8_t c1 = decnum%10;
140
+  uint8_t c2 = (decnum /             10) % 10;
141
+  uint8_t c3 = (decnum /            100) % 10;
142
+  uint8_t c4 = (decnum /           1000) % 10;
143
+  uint8_t c5 = (decnum /          10000) % 10;
144
+  UARTPutChar(UARTx, '0'+c5);
145
+  UARTPutChar(UARTx, '0'+c4);
146
+  UARTPutChar(UARTx, '0'+c3);
147
+  UARTPutChar(UARTx, '0'+c2);
148
+  UARTPutChar(UARTx, '0'+c1);
166 149
 }
167 150
 
168 151
 /*********************************************************************//**
169
- * @brief		Puts a decimal number to UART port
170
- * @param[in]	UARTx	Pointer to UART peripheral
171
- * @param[in]	decnum	Decimal number (8-bit long)
172
- * @return		None
152
+ * @brief   Puts a decimal number to UART port
153
+ * @param[in] UARTx Pointer to UART peripheral
154
+ * @param[in] decnum  Decimal number (8-bit long)
155
+ * @return    None
173 156
  **********************************************************************/
174
-void UARTPutDec32(LPC_UART_TypeDef *UARTx, uint32_t decnum)
175
-{
176
-  if (!debug_frmwrk_initialized)
177
-    return;
178
-
179
-	uint8_t c1=decnum%10;
180
-	uint8_t c2=(decnum/10)%10;
181
-	uint8_t c3=(decnum/100)%10;
182
-	uint8_t c4=(decnum/1000)%10;
183
-	uint8_t c5=(decnum/10000)%10;
184
-	uint8_t c6=(decnum/100000)%10;
185
-	uint8_t c7=(decnum/1000000)%10;
186
-	uint8_t c8=(decnum/10000000)%10;
187
-	uint8_t c9=(decnum/100000000)%10;
188
-	uint8_t c10=(decnum/1000000000)%10;
189
-	UARTPutChar(UARTx, '0'+c10);
190
-	UARTPutChar(UARTx, '0'+c9);
191
-	UARTPutChar(UARTx, '0'+c8);
192
-	UARTPutChar(UARTx, '0'+c7);
193
-	UARTPutChar(UARTx, '0'+c6);
194
-	UARTPutChar(UARTx, '0'+c5);
195
-	UARTPutChar(UARTx, '0'+c4);
196
-	UARTPutChar(UARTx, '0'+c3);
197
-	UARTPutChar(UARTx, '0'+c2);
198
-	UARTPutChar(UARTx, '0'+c1);
157
+void UARTPutDec32(LPC_UART_TypeDef *UARTx, uint32_t decnum) {
158
+  if (!debug_frmwrk_initialized) return;
159
+
160
+  const uint8_t  c1 =  decnum               % 10,
161
+                 c2 = (decnum /         10) % 10,
162
+                 c3 = (decnum /        100) % 10,
163
+                 c4 = (decnum /       1000) % 10,
164
+                 c5 = (decnum /      10000) % 10,
165
+                 c6 = (decnum /     100000) % 10,
166
+                 c7 = (decnum /    1000000) % 10,
167
+                 c8 = (decnum /   10000000) % 10,
168
+                 c9 = (decnum /  100000000) % 10,
169
+                c10 = (decnum / 1000000000) % 10;
170
+  UARTPutChar(UARTx, '0' + c10);
171
+  UARTPutChar(UARTx, '0' +  c9);
172
+  UARTPutChar(UARTx, '0' +  c8);
173
+  UARTPutChar(UARTx, '0' +  c7);
174
+  UARTPutChar(UARTx, '0' +  c6);
175
+  UARTPutChar(UARTx, '0' +  c5);
176
+  UARTPutChar(UARTx, '0' +  c4);
177
+  UARTPutChar(UARTx, '0' +  c3);
178
+  UARTPutChar(UARTx, '0' +  c2);
179
+  UARTPutChar(UARTx, '0' +  c1);
199 180
 }
200 181
 
201 182
 /*********************************************************************//**
202
- * @brief		Puts a hex number to UART port
203
- * @param[in]	UARTx	Pointer to UART peripheral
204
- * @param[in]	hexnum	Hex number (8-bit long)
205
- * @return		None
183
+ * @brief   Puts a hex number to UART port
184
+ * @param[in] UARTx Pointer to UART peripheral
185
+ * @param[in] hexnum  Hex number (8-bit long)
186
+ * @return    None
206 187
  **********************************************************************/
207
-void UARTPutHex (LPC_UART_TypeDef *UARTx, uint8_t hexnum)
208
-{
209
-	uint8_t nibble, i;
210
-  
211
-  if (!debug_frmwrk_initialized)
212
-    return;
213
-
214
-	UARTPuts(UARTx, "0x");
215
-	i = 1;
216
-	do {
217
-		nibble = (hexnum >> (4*i)) & 0x0F;
218
-		UARTPutChar(UARTx, (nibble > 9) ? ('A' + nibble - 10) : ('0' + nibble));
219
-	} while (i--);
188
+void UARTPutHex(LPC_UART_TypeDef *UARTx, uint8_t hexnum) {
189
+  if (!debug_frmwrk_initialized) return;
190
+
191
+  UARTPuts(UARTx, "0x");
192
+  uint8_t nibble, i = 1;
193
+  do {
194
+    nibble = (hexnum >> (4 * i)) & 0x0F;
195
+    UARTPutChar(UARTx, (nibble > 9) ? ('A' + nibble - 10) : ('0' + nibble));
196
+  } while (i--);
220 197
 }
221 198
 
222
-
223 199
 /*********************************************************************//**
224
- * @brief		Puts a hex number to UART port
225
- * @param[in]	UARTx	Pointer to UART peripheral
226
- * @param[in]	hexnum	Hex number (16-bit long)
227
- * @return		None
200
+ * @brief   Puts a hex number to UART port
201
+ * @param[in] UARTx Pointer to UART peripheral
202
+ * @param[in] hexnum  Hex number (16-bit long)
203
+ * @return    None
228 204
  **********************************************************************/
229
-void UARTPutHex16 (LPC_UART_TypeDef *UARTx, uint16_t hexnum)
230
-{
231
-	uint8_t nibble, i;
232
-  
233
-  if (!debug_frmwrk_initialized)
234
-    return;
235
-
236
-	UARTPuts(UARTx, "0x");
237
-	i = 3;
238
-	do {
239
-		nibble = (hexnum >> (4*i)) & 0x0F;
240
-		UARTPutChar(UARTx, (nibble > 9) ? ('A' + nibble - 10) : ('0' + nibble));
241
-	} while (i--);
205
+void UARTPutHex16(LPC_UART_TypeDef *UARTx, uint16_t hexnum) {
206
+  if (!debug_frmwrk_initialized) return;
207
+
208
+  UARTPuts(UARTx, "0x");
209
+  uint8_t nibble, i = 3;
210
+  do {
211
+    nibble = (hexnum >> (4 * i)) & 0x0F;
212
+    UARTPutChar(UARTx, (nibble > 9) ? ('A' + nibble - 10) : ('0' + nibble));
213
+  } while (i--);
242 214
 }
243 215
 
244 216
 /*********************************************************************//**
245
- * @brief		Puts a hex number to UART port
246
- * @param[in]	UARTx	Pointer to UART peripheral
247
- * @param[in]	hexnum	Hex number (32-bit long)
248
- * @return		None
217
+ * @brief   Puts a hex number to UART port
218
+ * @param[in] UARTx Pointer to UART peripheral
219
+ * @param[in] hexnum  Hex number (32-bit long)
220
+ * @return    None
249 221
  **********************************************************************/
250
-void UARTPutHex32 (LPC_UART_TypeDef *UARTx, uint32_t hexnum)
251
-{
252
-  uint8_t nibble, i;
253
-  
254
-  if (!debug_frmwrk_initialized)
255
-    return;
256
-
257
-	UARTPuts(UARTx, "0x");
258
-	i = 7;
259
-	do {
260
-		nibble = (hexnum >> (4*i)) & 0x0F;
261
-		UARTPutChar(UARTx, (nibble > 9) ? ('A' + nibble - 10) : ('0' + nibble));
262
-	} while (i--);
222
+void UARTPutHex32(LPC_UART_TypeDef *UARTx, uint32_t hexnum) {
223
+  if (!debug_frmwrk_initialized) return;
224
+
225
+  UARTPuts(UARTx, "0x");
226
+  uint8_t nibble, i = 7;
227
+  do {
228
+    nibble = (hexnum >> (4 * i)) & 0x0F;
229
+    UARTPutChar(UARTx, (nibble > 9) ? ('A' + nibble - 10) : ('0' + nibble));
230
+  } while (i--);
263 231
 }
264 232
 
265
-///*********************************************************************//**
266
-// * @brief		print function that supports format as same as printf()
267
-// * 				function of <stdio.h> library
268
-// * @param[in]	None
269
-// * @return		None
270
-// **********************************************************************/
271
-//void  _printf (const  char *format, ...)
272
-//{
273
-//    static  char  buffer[512 + 1];
274
-//            va_list     vArgs;
275
-//            char	*tmp;
276
-//    va_start(vArgs, format);
277
-//    vsprintf((char *)buffer, (char const *)format, vArgs);
278
-//    va_end(vArgs);
233
+/*********************************************************************//**
234
+ * @brief   print function that supports format as same as printf()
235
+ *        function of <stdio.h> library
236
+ * @param[in] None
237
+ * @return    None
238
+ **********************************************************************/
239
+//void  _printf (const  char *format, ...) {
240
+//  static  char  buffer[512 + 1];
241
+//          va_list     vArgs;
242
+//          char  *tmp;
243
+//  va_start(vArgs, format);
244
+//  vsprintf((char *)buffer, (char const *)format, vArgs);
245
+//  va_end(vArgs);
279 246
 //
280
-//    _DBG(buffer);
247
+//  _DBG(buffer);
281 248
 //}
282 249
 
283 250
 /*********************************************************************//**
284
- * @brief		Initialize Debug frame work through initializing UART port
285
- * @param[in]	None
286
- * @return		None
251
+ * @brief   Initialize Debug frame work through initializing UART port
252
+ * @param[in] None
253
+ * @return    None
287 254
  **********************************************************************/
288
-void debug_frmwrk_init(void)
289
-{
290
-	UART_CFG_Type UARTConfigStruct;
291
-	PINSEL_CFG_Type PinCfg;
292
-
293
-#if (USED_UART_DEBUG_PORT==0)
294
-	/*
295
-	 * Initialize UART0 pin connect
296
-	 */
297
-	PinCfg.Funcnum = 1;
298
-	PinCfg.OpenDrain = 0;
299
-	PinCfg.Pinmode = 0;
300
-	PinCfg.Pinnum = 2;
301
-	PinCfg.Portnum = 0;
302
-	PINSEL_ConfigPin(&PinCfg);
303
-	PinCfg.Pinnum = 3;
304
-	PINSEL_ConfigPin(&PinCfg);
305
-
306
-#elif (USED_UART_DEBUG_PORT==1)
307
-	/*
308
-	 * Initialize UART1 pin connect
309
-	 */
310
-	PinCfg.Funcnum = 1;
311
-	PinCfg.OpenDrain = 0;
312
-	PinCfg.Pinmode = 0;
313
-	PinCfg.Pinnum = 15;
314
-	PinCfg.Portnum = 0;
315
-	PINSEL_ConfigPin(&PinCfg);
316
-	PinCfg.Pinnum = 16;
317
-	PINSEL_ConfigPin(&PinCfg);
318
-#endif
319
-
320
-	/* Initialize UART Configuration parameter structure to default state:
321
-	 * Baudrate = 9600bps
322
-	 * 8 data bit
323
-	 * 1 Stop bit
324
-	 * None parity
325
-	 */
326
-	UART_ConfigStructInit(&UARTConfigStruct);
327
-
328
-	// Re-configure baudrate to 115200bps
329
-	UARTConfigStruct.Baud_rate = 115200;
330
-
331
-	// Initialize DEBUG_UART_PORT peripheral with given to corresponding parameter
332
-	UART_Init((LPC_UART_TypeDef *)DEBUG_UART_PORT, &UARTConfigStruct);
333
-
334
-	// Enable UART Transmit
335
-	UART_TxCmd((LPC_UART_TypeDef *)DEBUG_UART_PORT, ENABLE);
255
+void debug_frmwrk_init(void) {
256
+  UART_CFG_Type UARTConfigStruct;
257
+  PINSEL_CFG_Type PinCfg;
258
+
259
+  #if (USED_UART_DEBUG_PORT==0)
260
+    /*
261
+     * Initialize UART0 pin connect
262
+     */
263
+    PinCfg.Funcnum = 1;
264
+    PinCfg.OpenDrain = 0;
265
+    PinCfg.Pinmode = 0;
266
+    PinCfg.Pinnum = 2;
267
+    PinCfg.Portnum = 0;
268
+    PINSEL_ConfigPin(&PinCfg);
269
+    PinCfg.Pinnum = 3;
270
+    PINSEL_ConfigPin(&PinCfg);
271
+
272
+  #elif (USED_UART_DEBUG_PORT==1)
273
+    /*
274
+     * Initialize UART1 pin connect
275
+     */
276
+    PinCfg.Funcnum = 1;
277
+    PinCfg.OpenDrain = 0;
278
+    PinCfg.Pinmode = 0;
279
+    PinCfg.Pinnum = 15;
280
+    PinCfg.Portnum = 0;
281
+    PINSEL_ConfigPin(&PinCfg);
282
+    PinCfg.Pinnum = 16;
283
+    PINSEL_ConfigPin(&PinCfg);
284
+  #endif
285
+
286
+  /* Initialize UART Configuration parameter structure to default state:
287
+   * Baudrate = 9600bps
288
+   * 8 data bit
289
+   * 1 Stop bit
290
+   * None parity
291
+   */
292
+  UART_ConfigStructInit(&UARTConfigStruct);
293
+
294
+  // Re-configure baudrate to 115200bps
295
+  UARTConfigStruct.Baud_rate = 115200;
296
+
297
+  // Initialize DEBUG_UART_PORT peripheral with given to corresponding parameter
298
+  UART_Init((LPC_UART_TypeDef *)DEBUG_UART_PORT, &UARTConfigStruct);
299
+
300
+  // Enable UART Transmit
301
+  UART_TxCmd((LPC_UART_TypeDef *)DEBUG_UART_PORT, ENABLE);
336 302
 
337 303
   debug_frmwrk_initialized = TRUE;
338 304
 }
339
-#endif /*_DBGFWK */
340
-
341 305
 
342
-/* --------------------------------- End Of File ------------------------------ */
306
+#endif // _DBGFWK

Loading…
취소
저장