瀏覽代碼

Add support for STM32F7 MCU

Morten 6 年之前
父節點
當前提交
a0246c5c96
共有 32 個檔案被更改,包括 7633 行新增10 行删除
  1. 5
    1
      Marlin/Marlin.ino
  2. 4
    0
      Marlin/src/HAL/HAL.h
  3. 742
    0
      Marlin/src/HAL/HAL_STM32F7/EEPROM_Emul/eeprom_emul.cpp
  4. 118
    0
      Marlin/src/HAL/HAL_STM32F7/EEPROM_Emul/eeprom_emul.h
  5. 146
    0
      Marlin/src/HAL/HAL_STM32F7/EmulatedEeprom.cpp
  6. 143
    0
      Marlin/src/HAL/HAL_STM32F7/HAL_STM32F7.cpp
  7. 236
    0
      Marlin/src/HAL/HAL_STM32F7/HAL_STM32F7.h
  8. 52
    0
      Marlin/src/HAL/HAL_STM32F7/HAL_Servo_STM32F7.cpp
  9. 41
    0
      Marlin/src/HAL/HAL_STM32F7/HAL_Servo_STM32F7.h
  10. 178
    0
      Marlin/src/HAL/HAL_STM32F7/HAL_spi_STM32F7.cpp
  11. 154
    0
      Marlin/src/HAL/HAL_STM32F7/HAL_timers_STM32F7.cpp
  12. 112
    0
      Marlin/src/HAL/HAL_STM32F7/HAL_timers_STM32F7.h
  13. 28
    0
      Marlin/src/HAL/HAL_STM32F7/README.md
  14. 66
    0
      Marlin/src/HAL/HAL_STM32F7/SanityCheck_STM32F7.h
  15. 1035
    0
      Marlin/src/HAL/HAL_STM32F7/TMC2660.cpp
  16. 610
    0
      Marlin/src/HAL/HAL_STM32F7/TMC2660.h
  17. 68
    0
      Marlin/src/HAL/HAL_STM32F7/endstop_interrupts.h
  18. 54
    0
      Marlin/src/HAL/HAL_STM32F7/fastio_STM32F7.h
  19. 82
    0
      Marlin/src/HAL/HAL_STM32F7/persistent_store_impl.cpp
  20. 33
    0
      Marlin/src/HAL/HAL_STM32F7/spi_pins.h
  21. 55
    0
      Marlin/src/HAL/HAL_STM32F7/watchdog_STM32F7.cpp
  22. 33
    0
      Marlin/src/HAL/HAL_STM32F7/watchdog_STM32F7.h
  23. 13
    5
      Marlin/src/HAL/HAL_SanityCheck.h
  24. 4
    0
      Marlin/src/HAL/HAL_endstop_interrupts.h
  25. 7
    2
      Marlin/src/HAL/HAL_spi_pins.h
  26. 1793
    0
      Marlin/src/config/examples/TheBorg/Configuration.h
  27. 1594
    0
      Marlin/src/config/examples/TheBorg/Configuration_adv.h
  28. 6
    0
      Marlin/src/core/boards.h
  29. 6
    1
      Marlin/src/module/stepper_indirection.cpp
  30. 5
    1
      Marlin/src/module/stepper_indirection.h
  31. 2
    0
      Marlin/src/pins/pins.h
  32. 208
    0
      Marlin/src/pins/pins_THE_BORG.h

+ 5
- 1
Marlin/Marlin.ino 查看文件

@@ -50,7 +50,11 @@
50 50
 
51 51
 #if ENABLED(HAVE_TMCDRIVER)
52 52
   #include <SPI.h>
53
-  #include <TMC26XStepper.h>
53
+  #if defined(STM32F7)
54
+    #include "src/HAL/HAL_STM32F7/TMC2660.h"
55
+  #else
56
+    #include <TMC26XStepper.h>
57
+  #endif
54 58
 #endif
55 59
 
56 60
 #if ENABLED(HAVE_TMC2130)

+ 4
- 0
Marlin/src/HAL/HAL.h 查看文件

@@ -48,6 +48,10 @@
48 48
 #elif defined(__STM32F1__) || defined(TARGET_STM32F1)
49 49
   #include "math_32bit.h"
50 50
   #include "HAL_STM32F1/HAL_Stm32f1.h"
51
+#elif defined(STM32F7)
52
+  #define CPU_32_BIT
53
+  #include "math_32bit.h"
54
+  #include "HAL_STM32F7/HAL_STM32F7.h"
51 55
 #else
52 56
   #error "Unsupported Platform!"
53 57
 #endif

+ 742
- 0
Marlin/src/HAL/HAL_STM32F7/EEPROM_Emul/eeprom_emul.cpp 查看文件

@@ -0,0 +1,742 @@
1
+/**
2
+  ******************************************************************************
3
+  * @file    EEPROM/EEPROM_Emulation/src/eeprom.c
4
+  * @author  MCD Application Team
5
+  * @version V1.2.6
6
+  * @date    04-November-2016
7
+  * @brief   This file provides all the EEPROM emulation firmware functions.
8
+  ******************************************************************************
9
+  * @attention
10
+  *
11
+  * <h2><center>&copy; Copyright © 2016 STMicroelectronics International N.V.
12
+  * All rights reserved.</center></h2>
13
+  *
14
+  * Redistribution and use in source and binary forms, with or without
15
+  * modification, are permitted, provided that the following conditions are met:
16
+  *
17
+  * 1. Redistribution of source code must retain the above copyright notice,
18
+  *    this list of conditions and the following disclaimer.
19
+  * 2. Redistributions in binary form must reproduce the above copyright notice,
20
+  *    this list of conditions and the following disclaimer in the documentation
21
+  *    and/or other materials provided with the distribution.
22
+  * 3. Neither the name of STMicroelectronics nor the names of other
23
+  *    contributors to this software may be used to endorse or promote products
24
+  *    derived from this software without specific written permission.
25
+  * 4. This software, including modifications and/or derivative works of this
26
+  *    software, must execute solely and exclusively on microcontroller or
27
+  *    microprocessor devices manufactured by or for STMicroelectronics.
28
+  * 5. Redistribution and use of this software other than as permitted under
29
+  *    this license is void and will automatically terminate your rights under
30
+  *    this license.
31
+  *
32
+  * THIS SOFTWARE IS PROVIDED BY STMICROELECTRONICS AND CONTRIBUTORS "AS IS"
33
+  * AND ANY EXPRESS, IMPLIED OR STATUTORY WARRANTIES, INCLUDING, BUT NOT
34
+  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A
35
+  * PARTICULAR PURPOSE AND NON-INFRINGEMENT OF THIRD PARTY INTELLECTUAL PROPERTY
36
+  * RIGHTS ARE DISCLAIMED TO THE FULLEST EXTENT PERMITTED BY LAW. IN NO EVENT
37
+  * SHALL STMICROELECTRONICS OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
38
+  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
39
+  * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA,
40
+  * OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
41
+  * LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
42
+  * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE,
43
+  * EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
44
+  *
45
+  ******************************************************************************
46
+  */
47
+/** @addtogroup EEPROM_Emulation
48
+  * @{
49
+  */
50
+#ifdef STM32F7
51
+  
52
+/* Includes ------------------------------------------------------------------*/
53
+#include "eeprom_emul.h"
54
+
55
+/* Private typedef -----------------------------------------------------------*/
56
+/* Private define ------------------------------------------------------------*/
57
+/* Private macro -------------------------------------------------------------*/
58
+/* Private variables ---------------------------------------------------------*/
59
+
60
+/* Global variable used to store variable value in read sequence */
61
+uint16_t DataVar = 0;
62
+
63
+/* Virtual address defined by the user: 0xFFFF value is prohibited */
64
+uint16_t VirtAddVarTab[NB_OF_VAR];
65
+
66
+/* Private function prototypes -----------------------------------------------*/
67
+/* Private functions ---------------------------------------------------------*/
68
+static HAL_StatusTypeDef EE_Format(void);
69
+static uint16_t EE_FindValidPage(uint8_t Operation);
70
+static uint16_t EE_VerifyPageFullWriteVariable(uint16_t VirtAddress, uint16_t Data);
71
+static uint16_t EE_PageTransfer(uint16_t VirtAddress, uint16_t Data);
72
+static uint16_t EE_VerifyPageFullyErased(uint32_t Address);
73
+
74
+/**
75
+  * @brief  Restore the pages to a known good state in case of page's status
76
+  *   corruption after a power loss.
77
+  * @param  None.
78
+  * @retval - Flash error code: on write Flash error
79
+  *         - FLASH_COMPLETE: on success
80
+  */
81
+uint16_t EE_Initialise(void)
82
+{
83
+  uint16_t PageStatus0 = 6, PageStatus1 = 6;
84
+  uint16_t VarIdx = 0;
85
+  uint16_t EepromStatus = 0, ReadStatus = 0;
86
+  int16_t x = -1;
87
+  HAL_StatusTypeDef  FlashStatus;
88
+  uint32_t SectorError = 0;
89
+  FLASH_EraseInitTypeDef pEraseInit;
90
+
91
+
92
+  /* Get Page0 status */
93
+  PageStatus0 = (*(__IO uint16_t*)PAGE0_BASE_ADDRESS);
94
+  /* Get Page1 status */
95
+  PageStatus1 = (*(__IO uint16_t*)PAGE1_BASE_ADDRESS);
96
+
97
+  pEraseInit.TypeErase = TYPEERASE_SECTORS;
98
+  pEraseInit.Sector = PAGE0_ID;
99
+  pEraseInit.NbSectors = 1;
100
+  pEraseInit.VoltageRange = VOLTAGE_RANGE;
101
+
102
+  /* Check for invalid header states and repair if necessary */
103
+  switch (PageStatus0)
104
+  {
105
+    case ERASED:
106
+      if (PageStatus1 == VALID_PAGE) /* Page0 erased, Page1 valid */
107
+      {
108
+          /* Erase Page0 */
109
+        if(!EE_VerifyPageFullyErased(PAGE0_BASE_ADDRESS))
110
+        {
111
+          FlashStatus = HAL_FLASHEx_Erase(&pEraseInit, &SectorError);
112
+          /* If erase operation was failed, a Flash error code is returned */
113
+          if (FlashStatus != HAL_OK)
114
+          {
115
+            return FlashStatus;
116
+          }
117
+        }
118
+      }
119
+      else if (PageStatus1 == RECEIVE_DATA) /* Page0 erased, Page1 receive */
120
+      {
121
+        /* Erase Page0 */
122
+        if(!EE_VerifyPageFullyErased(PAGE0_BASE_ADDRESS))
123
+        {
124
+          FlashStatus = HAL_FLASHEx_Erase(&pEraseInit, &SectorError);
125
+          /* If erase operation was failed, a Flash error code is returned */
126
+          if (FlashStatus != HAL_OK)
127
+          {
128
+            return FlashStatus;
129
+          }
130
+        }
131
+        /* Mark Page1 as valid */
132
+        FlashStatus = HAL_FLASH_Program(TYPEPROGRAM_HALFWORD, PAGE1_BASE_ADDRESS, VALID_PAGE);
133
+        /* If program operation was failed, a Flash error code is returned */
134
+        if (FlashStatus != HAL_OK)
135
+        {
136
+          return FlashStatus;
137
+        }
138
+      }
139
+      else /* First EEPROM access (Page0&1 are erased) or invalid state -> format EEPROM */
140
+      {
141
+        /* Erase both Page0 and Page1 and set Page0 as valid page */
142
+        FlashStatus = EE_Format();
143
+        /* If erase/program operation was failed, a Flash error code is returned */
144
+        if (FlashStatus != HAL_OK)
145
+        {
146
+          return FlashStatus;
147
+        }
148
+      }
149
+      break;
150
+
151
+    case RECEIVE_DATA:
152
+      if (PageStatus1 == VALID_PAGE) /* Page0 receive, Page1 valid */
153
+      {
154
+        /* Transfer data from Page1 to Page0 */
155
+        for (VarIdx = 0; VarIdx < NB_OF_VAR; VarIdx++)
156
+        {
157
+          if (( *(__IO uint16_t*)(PAGE0_BASE_ADDRESS + 6)) == VirtAddVarTab[VarIdx])
158
+          {
159
+            x = VarIdx;
160
+          }
161
+          if (VarIdx != x)
162
+          {
163
+            /* Read the last variables' updates */
164
+            ReadStatus = EE_ReadVariable(VirtAddVarTab[VarIdx], &DataVar);
165
+            /* In case variable corresponding to the virtual address was found */
166
+            if (ReadStatus != 0x1)
167
+            {
168
+              /* Transfer the variable to the Page0 */
169
+              EepromStatus = EE_VerifyPageFullWriteVariable(VirtAddVarTab[VarIdx], DataVar);
170
+              /* If program operation was failed, a Flash error code is returned */
171
+              if (EepromStatus != HAL_OK)
172
+              {
173
+                return EepromStatus;
174
+              }
175
+            }
176
+          }
177
+        }
178
+        /* Mark Page0 as valid */
179
+        FlashStatus = HAL_FLASH_Program(TYPEPROGRAM_HALFWORD, PAGE0_BASE_ADDRESS, VALID_PAGE);
180
+        /* If program operation was failed, a Flash error code is returned */
181
+        if (FlashStatus != HAL_OK)
182
+        {
183
+          return FlashStatus;
184
+        }
185
+        pEraseInit.Sector = PAGE1_ID;
186
+        pEraseInit.NbSectors = 1;
187
+        pEraseInit.VoltageRange = VOLTAGE_RANGE;
188
+        /* Erase Page1 */
189
+        if(!EE_VerifyPageFullyErased(PAGE1_BASE_ADDRESS))
190
+        {
191
+          FlashStatus = HAL_FLASHEx_Erase(&pEraseInit, &SectorError);
192
+          /* If erase operation was failed, a Flash error code is returned */
193
+          if (FlashStatus != HAL_OK)
194
+          {
195
+            return FlashStatus;
196
+          }
197
+        }
198
+      }
199
+      else if (PageStatus1 == ERASED) /* Page0 receive, Page1 erased */
200
+      {
201
+        pEraseInit.Sector = PAGE1_ID;
202
+        pEraseInit.NbSectors = 1;
203
+        pEraseInit.VoltageRange = VOLTAGE_RANGE;
204
+        /* Erase Page1 */
205
+        if(!EE_VerifyPageFullyErased(PAGE1_BASE_ADDRESS))
206
+        {
207
+          FlashStatus = HAL_FLASHEx_Erase(&pEraseInit, &SectorError);
208
+          /* If erase operation was failed, a Flash error code is returned */
209
+          if (FlashStatus != HAL_OK)
210
+          {
211
+            return FlashStatus;
212
+          }
213
+        }
214
+        /* Mark Page0 as valid */
215
+        FlashStatus = HAL_FLASH_Program(TYPEPROGRAM_HALFWORD, PAGE0_BASE_ADDRESS, VALID_PAGE);
216
+        /* If program operation was failed, a Flash error code is returned */
217
+        if (FlashStatus != HAL_OK)
218
+        {
219
+          return FlashStatus;
220
+        }
221
+      }
222
+      else /* Invalid state -> format eeprom */
223
+      {
224
+        /* Erase both Page0 and Page1 and set Page0 as valid page */
225
+        FlashStatus = EE_Format();
226
+        /* If erase/program operation was failed, a Flash error code is returned */
227
+        if (FlashStatus != HAL_OK)
228
+        {
229
+          return FlashStatus;
230
+        }
231
+      }
232
+      break;
233
+
234
+    case VALID_PAGE:
235
+      if (PageStatus1 == VALID_PAGE) /* Invalid state -> format eeprom */
236
+      {
237
+        /* Erase both Page0 and Page1 and set Page0 as valid page */
238
+        FlashStatus = EE_Format();
239
+        /* If erase/program operation was failed, a Flash error code is returned */
240
+        if (FlashStatus != HAL_OK)
241
+        {
242
+          return FlashStatus;
243
+        }
244
+      }
245
+      else if (PageStatus1 == ERASED) /* Page0 valid, Page1 erased */
246
+      {
247
+        pEraseInit.Sector = PAGE1_ID;
248
+        pEraseInit.NbSectors = 1;
249
+        pEraseInit.VoltageRange = VOLTAGE_RANGE;
250
+        /* Erase Page1 */
251
+        if(!EE_VerifyPageFullyErased(PAGE1_BASE_ADDRESS))
252
+        {
253
+          FlashStatus = HAL_FLASHEx_Erase(&pEraseInit, &SectorError);
254
+          /* If erase operation was failed, a Flash error code is returned */
255
+          if (FlashStatus != HAL_OK)
256
+          {
257
+            return FlashStatus;
258
+          }
259
+        }
260
+      }
261
+      else /* Page0 valid, Page1 receive */
262
+      {
263
+        /* Transfer data from Page0 to Page1 */
264
+        for (VarIdx = 0; VarIdx < NB_OF_VAR; VarIdx++)
265
+        {
266
+          if ((*(__IO uint16_t*)(PAGE1_BASE_ADDRESS + 6)) == VirtAddVarTab[VarIdx])
267
+          {
268
+            x = VarIdx;
269
+          }
270
+          if (VarIdx != x)
271
+          {
272
+            /* Read the last variables' updates */
273
+            ReadStatus = EE_ReadVariable(VirtAddVarTab[VarIdx], &DataVar);
274
+            /* In case variable corresponding to the virtual address was found */
275
+            if (ReadStatus != 0x1)
276
+            {
277
+              /* Transfer the variable to the Page1 */
278
+              EepromStatus = EE_VerifyPageFullWriteVariable(VirtAddVarTab[VarIdx], DataVar);
279
+              /* If program operation was failed, a Flash error code is returned */
280
+              if (EepromStatus != HAL_OK)
281
+              {
282
+                return EepromStatus;
283
+              }
284
+            }
285
+          }
286
+        }
287
+        /* Mark Page1 as valid */
288
+        FlashStatus = HAL_FLASH_Program(TYPEPROGRAM_HALFWORD, PAGE1_BASE_ADDRESS, VALID_PAGE);
289
+        /* If program operation was failed, a Flash error code is returned */
290
+        if (FlashStatus != HAL_OK)
291
+        {
292
+          return FlashStatus;
293
+        }
294
+        pEraseInit.Sector = PAGE0_ID;
295
+        pEraseInit.NbSectors = 1;
296
+        pEraseInit.VoltageRange = VOLTAGE_RANGE;
297
+        /* Erase Page0 */
298
+        if(!EE_VerifyPageFullyErased(PAGE0_BASE_ADDRESS))
299
+        {
300
+          FlashStatus = HAL_FLASHEx_Erase(&pEraseInit, &SectorError);
301
+          /* If erase operation was failed, a Flash error code is returned */
302
+          if (FlashStatus != HAL_OK)
303
+          {
304
+            return FlashStatus;
305
+          }
306
+        }
307
+      }
308
+      break;
309
+
310
+    default:  /* Any other state -> format eeprom */
311
+      /* Erase both Page0 and Page1 and set Page0 as valid page */
312
+      FlashStatus = EE_Format();
313
+      /* If erase/program operation was failed, a Flash error code is returned */
314
+      if (FlashStatus != HAL_OK)
315
+      {
316
+        return FlashStatus;
317
+      }
318
+      break;
319
+  }
320
+
321
+  return HAL_OK;
322
+}
323
+
324
+/**
325
+  * @brief  Verify if specified page is fully erased.
326
+  * @param  Address: page address
327
+  *   This parameter can be one of the following values:
328
+  *     @arg PAGE0_BASE_ADDRESS: Page0 base address
329
+  *     @arg PAGE1_BASE_ADDRESS: Page1 base address
330
+  * @retval page fully erased status:
331
+  *           - 0: if Page not erased
332
+  *           - 1: if Page erased
333
+  */
334
+uint16_t EE_VerifyPageFullyErased(uint32_t Address)
335
+{
336
+  uint32_t ReadStatus = 1;
337
+  uint16_t AddressValue = 0x5555;
338
+
339
+  /* Check each active page address starting from end */
340
+  while (Address <= PAGE0_END_ADDRESS)
341
+  {
342
+    /* Get the current location content to be compared with virtual address */
343
+    AddressValue = (*(__IO uint16_t*)Address);
344
+
345
+    /* Compare the read address with the virtual address */
346
+    if (AddressValue != ERASED)
347
+    {
348
+
349
+      /* In case variable value is read, reset ReadStatus flag */
350
+      ReadStatus = 0;
351
+
352
+      break;
353
+    }
354
+    /* Next address location */
355
+    Address = Address + 4;
356
+  }
357
+
358
+  /* Return ReadStatus value: (0: Page not erased, 1: Sector erased) */
359
+  return ReadStatus;
360
+}
361
+
362
+/**
363
+  * @brief  Returns the last stored variable data, if found, which correspond to
364
+  *   the passed virtual address
365
+  * @param  VirtAddress: Variable virtual address
366
+  * @param  Data: Global variable contains the read variable value
367
+  * @retval Success or error status:
368
+  *           - 0: if variable was found
369
+  *           - 1: if the variable was not found
370
+  *           - NO_VALID_PAGE: if no valid page was found.
371
+  */
372
+uint16_t EE_ReadVariable(uint16_t VirtAddress, uint16_t* Data)
373
+{
374
+  uint16_t ValidPage = PAGE0;
375
+  uint16_t AddressValue = 0x5555, ReadStatus = 1;
376
+  uint32_t Address = EEPROM_START_ADDRESS, PageStartAddress = EEPROM_START_ADDRESS;
377
+
378
+  /* Get active Page for read operation */
379
+  ValidPage = EE_FindValidPage(READ_FROM_VALID_PAGE);
380
+
381
+  /* Check if there is no valid page */
382
+  if (ValidPage == NO_VALID_PAGE)
383
+  {
384
+    return  NO_VALID_PAGE;
385
+  }
386
+
387
+  /* Get the valid Page start Address */
388
+  PageStartAddress = (uint32_t)(EEPROM_START_ADDRESS + (uint32_t)(ValidPage * PAGE_SIZE));
389
+
390
+  /* Get the valid Page end Address */
391
+  Address = (uint32_t)((EEPROM_START_ADDRESS - 2) + (uint32_t)((1 + ValidPage) * PAGE_SIZE));
392
+
393
+  /* Check each active page address starting from end */
394
+  while (Address > (PageStartAddress + 2))
395
+  {
396
+    /* Get the current location content to be compared with virtual address */
397
+    AddressValue = (*(__IO uint16_t*)Address);
398
+
399
+    /* Compare the read address with the virtual address */
400
+    if (AddressValue == VirtAddress)
401
+    {
402
+      /* Get content of Address-2 which is variable value */
403
+      *Data = (*(__IO uint16_t*)(Address - 2));
404
+
405
+      /* In case variable value is read, reset ReadStatus flag */
406
+      ReadStatus = 0;
407
+
408
+      break;
409
+    }
410
+    else
411
+    {
412
+      /* Next address location */
413
+      Address = Address - 4;
414
+    }
415
+  }
416
+
417
+  /* Return ReadStatus value: (0: variable exist, 1: variable doesn't exist) */
418
+  return ReadStatus;
419
+}
420
+
421
+/**
422
+  * @brief  Writes/upadtes variable data in EEPROM.
423
+  * @param  VirtAddress: Variable virtual address
424
+  * @param  Data: 16 bit data to be written
425
+  * @retval Success or error status:
426
+  *           - FLASH_COMPLETE: on success
427
+  *           - PAGE_FULL: if valid page is full
428
+  *           - NO_VALID_PAGE: if no valid page was found
429
+  *           - Flash error code: on write Flash error
430
+  */
431
+uint16_t EE_WriteVariable(uint16_t VirtAddress, uint16_t Data)
432
+{
433
+  uint16_t Status = 0;
434
+
435
+  /* Write the variable virtual address and value in the EEPROM */
436
+  Status = EE_VerifyPageFullWriteVariable(VirtAddress, Data);
437
+
438
+  /* In case the EEPROM active page is full */
439
+  if (Status == PAGE_FULL)
440
+  {
441
+    /* Perform Page transfer */
442
+    Status = EE_PageTransfer(VirtAddress, Data);
443
+  }
444
+
445
+  /* Return last operation status */
446
+  return Status;
447
+}
448
+
449
+/**
450
+  * @brief  Erases PAGE and PAGE1 and writes VALID_PAGE header to PAGE
451
+  * @param  None
452
+  * @retval Status of the last operation (Flash write or erase) done during
453
+  *         EEPROM formating
454
+  */
455
+static HAL_StatusTypeDef EE_Format(void)
456
+{
457
+  HAL_StatusTypeDef FlashStatus = HAL_OK;
458
+  uint32_t SectorError = 0;
459
+  FLASH_EraseInitTypeDef pEraseInit;
460
+
461
+  pEraseInit.TypeErase = FLASH_TYPEERASE_SECTORS;
462
+  pEraseInit.Sector = PAGE0_ID;
463
+  pEraseInit.NbSectors = 1;
464
+  pEraseInit.VoltageRange = VOLTAGE_RANGE;
465
+  /* Erase Page0 */
466
+  if(!EE_VerifyPageFullyErased(PAGE0_BASE_ADDRESS))
467
+  {
468
+    FlashStatus = HAL_FLASHEx_Erase(&pEraseInit, &SectorError);
469
+    /* If erase operation was failed, a Flash error code is returned */
470
+    if (FlashStatus != HAL_OK)
471
+    {
472
+      return FlashStatus;
473
+    }
474
+  }
475
+  /* Set Page0 as valid page: Write VALID_PAGE at Page0 base address */
476
+  FlashStatus = HAL_FLASH_Program(TYPEPROGRAM_HALFWORD, PAGE0_BASE_ADDRESS, VALID_PAGE);
477
+  /* If program operation was failed, a Flash error code is returned */
478
+  if (FlashStatus != HAL_OK)
479
+  {
480
+    return FlashStatus;
481
+  }
482
+
483
+  pEraseInit.Sector = PAGE1_ID;
484
+  /* Erase Page1 */
485
+  if(!EE_VerifyPageFullyErased(PAGE1_BASE_ADDRESS))
486
+  {
487
+    FlashStatus = HAL_FLASHEx_Erase(&pEraseInit, &SectorError);
488
+    /* If erase operation was failed, a Flash error code is returned */
489
+    if (FlashStatus != HAL_OK)
490
+    {
491
+      return FlashStatus;
492
+    }
493
+  }
494
+
495
+  return HAL_OK;
496
+}
497
+
498
+/**
499
+  * @brief  Find valid Page for write or read operation
500
+  * @param  Operation: operation to achieve on the valid page.
501
+  *   This parameter can be one of the following values:
502
+  *     @arg READ_FROM_VALID_PAGE: read operation from valid page
503
+  *     @arg WRITE_IN_VALID_PAGE: write operation from valid page
504
+  * @retval Valid page number (PAGE or PAGE1) or NO_VALID_PAGE in case
505
+  *   of no valid page was found
506
+  */
507
+static uint16_t EE_FindValidPage(uint8_t Operation)
508
+{
509
+  uint16_t PageStatus0 = 6, PageStatus1 = 6;
510
+
511
+  /* Get Page0 actual status */
512
+  PageStatus0 = (*(__IO uint16_t*)PAGE0_BASE_ADDRESS);
513
+
514
+  /* Get Page1 actual status */
515
+  PageStatus1 = (*(__IO uint16_t*)PAGE1_BASE_ADDRESS);
516
+
517
+  /* Write or read operation */
518
+  switch (Operation)
519
+  {
520
+    case WRITE_IN_VALID_PAGE:   /* ---- Write operation ---- */
521
+      if (PageStatus1 == VALID_PAGE)
522
+      {
523
+        /* Page0 receiving data */
524
+        if (PageStatus0 == RECEIVE_DATA)
525
+        {
526
+          return PAGE0;         /* Page0 valid */
527
+        }
528
+        else
529
+        {
530
+          return PAGE1;         /* Page1 valid */
531
+        }
532
+      }
533
+      else if (PageStatus0 == VALID_PAGE)
534
+      {
535
+        /* Page1 receiving data */
536
+        if (PageStatus1 == RECEIVE_DATA)
537
+        {
538
+          return PAGE1;         /* Page1 valid */
539
+        }
540
+        else
541
+        {
542
+          return PAGE0;         /* Page0 valid */
543
+        }
544
+      }
545
+      else
546
+      {
547
+        return NO_VALID_PAGE;   /* No valid Page */
548
+      }
549
+
550
+    case READ_FROM_VALID_PAGE:  /* ---- Read operation ---- */
551
+      if (PageStatus0 == VALID_PAGE)
552
+      {
553
+        return PAGE0;           /* Page0 valid */
554
+      }
555
+      else if (PageStatus1 == VALID_PAGE)
556
+      {
557
+        return PAGE1;           /* Page1 valid */
558
+      }
559
+      else
560
+      {
561
+        return NO_VALID_PAGE ;  /* No valid Page */
562
+      }
563
+
564
+    default:
565
+      return PAGE0;             /* Page0 valid */
566
+  }
567
+}
568
+
569
+/**
570
+  * @brief  Verify if active page is full and Writes variable in EEPROM.
571
+  * @param  VirtAddress: 16 bit virtual address of the variable
572
+  * @param  Data: 16 bit data to be written as variable value
573
+  * @retval Success or error status:
574
+  *           - FLASH_COMPLETE: on success
575
+  *           - PAGE_FULL: if valid page is full
576
+  *           - NO_VALID_PAGE: if no valid page was found
577
+  *           - Flash error code: on write Flash error
578
+  */
579
+static uint16_t EE_VerifyPageFullWriteVariable(uint16_t VirtAddress, uint16_t Data)
580
+{
581
+  HAL_StatusTypeDef FlashStatus = HAL_OK;
582
+  uint16_t ValidPage = PAGE0;
583
+  uint32_t Address = EEPROM_START_ADDRESS, PageEndAddress = EEPROM_START_ADDRESS+PAGE_SIZE;
584
+
585
+  /* Get valid Page for write operation */
586
+  ValidPage = EE_FindValidPage(WRITE_IN_VALID_PAGE);
587
+
588
+  /* Check if there is no valid page */
589
+  if (ValidPage == NO_VALID_PAGE)
590
+  {
591
+    return  NO_VALID_PAGE;
592
+  }
593
+
594
+  /* Get the valid Page start Address */
595
+  Address = (uint32_t)(EEPROM_START_ADDRESS + (uint32_t)(ValidPage * PAGE_SIZE));
596
+
597
+  /* Get the valid Page end Address */
598
+  PageEndAddress = (uint32_t)((EEPROM_START_ADDRESS - 1) + (uint32_t)((ValidPage + 1) * PAGE_SIZE));
599
+
600
+  /* Check each active page address starting from begining */
601
+  while (Address < PageEndAddress)
602
+  {
603
+    /* Verify if Address and Address+2 contents are 0xFFFFFFFF */
604
+    if ((*(__IO uint32_t*)Address) == 0xFFFFFFFF)
605
+    {
606
+      /* Set variable data */
607
+      FlashStatus = HAL_FLASH_Program(TYPEPROGRAM_HALFWORD, Address, Data);
608
+      /* If program operation was failed, a Flash error code is returned */
609
+      if (FlashStatus != HAL_OK)
610
+      {
611
+        return FlashStatus;
612
+      }
613
+      /* Set variable virtual address */
614
+      FlashStatus = HAL_FLASH_Program(TYPEPROGRAM_HALFWORD, Address + 2, VirtAddress);
615
+      /* Return program operation status */
616
+      return FlashStatus;
617
+    }
618
+    else
619
+    {
620
+      /* Next address location */
621
+      Address = Address + 4;
622
+    }
623
+  }
624
+
625
+  /* Return PAGE_FULL in case the valid page is full */
626
+  return PAGE_FULL;
627
+}
628
+
629
+/**
630
+  * @brief  Transfers last updated variables data from the full Page to
631
+  *   an empty one.
632
+  * @param  VirtAddress: 16 bit virtual address of the variable
633
+  * @param  Data: 16 bit data to be written as variable value
634
+  * @retval Success or error status:
635
+  *           - FLASH_COMPLETE: on success
636
+  *           - PAGE_FULL: if valid page is full
637
+  *           - NO_VALID_PAGE: if no valid page was found
638
+  *           - Flash error code: on write Flash error
639
+  */
640
+static uint16_t EE_PageTransfer(uint16_t VirtAddress, uint16_t Data)
641
+{
642
+  HAL_StatusTypeDef FlashStatus = HAL_OK;
643
+  uint32_t NewPageAddress = EEPROM_START_ADDRESS;
644
+  uint16_t OldPageId=0;
645
+  uint16_t ValidPage = PAGE0, VarIdx = 0;
646
+  uint16_t EepromStatus = 0, ReadStatus = 0;
647
+  uint32_t SectorError = 0;
648
+  FLASH_EraseInitTypeDef pEraseInit;
649
+
650
+  /* Get active Page for read operation */
651
+  ValidPage = EE_FindValidPage(READ_FROM_VALID_PAGE);
652
+
653
+  if (ValidPage == PAGE1)       /* Page1 valid */
654
+  {
655
+    /* New page address where variable will be moved to */
656
+    NewPageAddress = PAGE0_BASE_ADDRESS;
657
+
658
+    /* Old page ID where variable will be taken from */
659
+    OldPageId = PAGE1_ID;
660
+  }
661
+  else if (ValidPage == PAGE0)  /* Page0 valid */
662
+  {
663
+    /* New page address  where variable will be moved to */
664
+    NewPageAddress = PAGE1_BASE_ADDRESS;
665
+
666
+    /* Old page ID where variable will be taken from */
667
+    OldPageId = PAGE0_ID;
668
+  }
669
+  else
670
+  {
671
+    return NO_VALID_PAGE;       /* No valid Page */
672
+  }
673
+
674
+  /* Set the new Page status to RECEIVE_DATA status */
675
+  FlashStatus = HAL_FLASH_Program(TYPEPROGRAM_HALFWORD, NewPageAddress, RECEIVE_DATA);
676
+  /* If program operation was failed, a Flash error code is returned */
677
+  if (FlashStatus != HAL_OK)
678
+  {
679
+    return FlashStatus;
680
+  }
681
+
682
+  /* Write the variable passed as parameter in the new active page */
683
+  EepromStatus = EE_VerifyPageFullWriteVariable(VirtAddress, Data);
684
+  /* If program operation was failed, a Flash error code is returned */
685
+  if (EepromStatus != HAL_OK)
686
+  {
687
+    return EepromStatus;
688
+  }
689
+
690
+  /* Transfer process: transfer variables from old to the new active page */
691
+  for (VarIdx = 0; VarIdx < NB_OF_VAR; VarIdx++)
692
+  {
693
+    if (VirtAddVarTab[VarIdx] != VirtAddress)  /* Check each variable except the one passed as parameter */
694
+    {
695
+      /* Read the other last variable updates */
696
+      ReadStatus = EE_ReadVariable(VirtAddVarTab[VarIdx], &DataVar);
697
+      /* In case variable corresponding to the virtual address was found */
698
+      if (ReadStatus != 0x1)
699
+      {
700
+        /* Transfer the variable to the new active page */
701
+        EepromStatus = EE_VerifyPageFullWriteVariable(VirtAddVarTab[VarIdx], DataVar);
702
+        /* If program operation was failed, a Flash error code is returned */
703
+        if (EepromStatus != HAL_OK)
704
+        {
705
+          return EepromStatus;
706
+        }
707
+      }
708
+    }
709
+  }
710
+
711
+  pEraseInit.TypeErase = TYPEERASE_SECTORS;
712
+  pEraseInit.Sector = OldPageId;
713
+  pEraseInit.NbSectors = 1;
714
+  pEraseInit.VoltageRange = VOLTAGE_RANGE;
715
+
716
+  /* Erase the old Page: Set old Page status to ERASED status */
717
+  FlashStatus = HAL_FLASHEx_Erase(&pEraseInit, &SectorError);
718
+  /* If erase operation was failed, a Flash error code is returned */
719
+  if (FlashStatus != HAL_OK)
720
+  {
721
+    return FlashStatus;
722
+  }
723
+
724
+  /* Set new Page status to VALID_PAGE status */
725
+  FlashStatus = HAL_FLASH_Program(TYPEPROGRAM_HALFWORD, NewPageAddress, VALID_PAGE);
726
+  /* If program operation was failed, a Flash error code is returned */
727
+  if (FlashStatus != HAL_OK)
728
+  {
729
+    return FlashStatus;
730
+  }
731
+
732
+  /* Return last operation flash status */
733
+  return FlashStatus;
734
+}
735
+
736
+#endif // STM32F7
737
+
738
+/**
739
+  * @}
740
+  */
741
+
742
+/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/

+ 118
- 0
Marlin/src/HAL/HAL_STM32F7/EEPROM_Emul/eeprom_emul.h 查看文件

@@ -0,0 +1,118 @@
1
+/**
2
+  ******************************************************************************
3
+  * @file    EEPROM/EEPROM_Emulation/inc/eeprom.h
4
+  * @author  MCD Application Team
5
+  * @version V1.2.6
6
+  * @date    04-November-2016
7
+  * @brief   This file contains all the functions prototypes for the EEPROM
8
+  *          emulation firmware library.
9
+  ******************************************************************************
10
+  * @attention
11
+  *
12
+  * <h2><center>&copy; Copyright © 2016 STMicroelectronics International N.V.
13
+  * All rights reserved.</center></h2>
14
+  *
15
+  * Redistribution and use in source and binary forms, with or without
16
+  * modification, are permitted, provided that the following conditions are met:
17
+  *
18
+  * 1. Redistribution of source code must retain the above copyright notice,
19
+  *    this list of conditions and the following disclaimer.
20
+  * 2. Redistributions in binary form must reproduce the above copyright notice,
21
+  *    this list of conditions and the following disclaimer in the documentation
22
+  *    and/or other materials provided with the distribution.
23
+  * 3. Neither the name of STMicroelectronics nor the names of other
24
+  *    contributors to this software may be used to endorse or promote products
25
+  *    derived from this software without specific written permission.
26
+  * 4. This software, including modifications and/or derivative works of this
27
+  *    software, must execute solely and exclusively on microcontroller or
28
+  *    microprocessor devices manufactured by or for STMicroelectronics.
29
+  * 5. Redistribution and use of this software other than as permitted under
30
+  *    this license is void and will automatically terminate your rights under
31
+  *    this license.
32
+  *
33
+  * THIS SOFTWARE IS PROVIDED BY STMICROELECTRONICS AND CONTRIBUTORS "AS IS"
34
+  * AND ANY EXPRESS, IMPLIED OR STATUTORY WARRANTIES, INCLUDING, BUT NOT
35
+  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A
36
+  * PARTICULAR PURPOSE AND NON-INFRINGEMENT OF THIRD PARTY INTELLECTUAL PROPERTY
37
+  * RIGHTS ARE DISCLAIMED TO THE FULLEST EXTENT PERMITTED BY LAW. IN NO EVENT
38
+  * SHALL STMICROELECTRONICS OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
39
+  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
40
+  * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA,
41
+  * OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
42
+  * LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
43
+  * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE,
44
+  * EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
45
+  *
46
+  ******************************************************************************
47
+  */
48
+
49
+/* Define to prevent recursive inclusion -------------------------------------*/
50
+#ifndef __EEEPROM_EMUL_H
51
+#define __EEEPROM_EMUL_H
52
+
53
+// --------------------------------------------------------------------------
54
+// Includes
55
+// --------------------------------------------------------------------------
56
+#include "../../../inc/MarlinConfig.h"
57
+#include "../../HAL.h"
58
+
59
+/* Exported constants --------------------------------------------------------*/
60
+/* EEPROM emulation firmware error codes */
61
+#define EE_OK      (uint32_t)HAL_OK
62
+#define EE_ERROR   (uint32_t)HAL_ERROR
63
+#define EE_BUSY    (uint32_t)HAL_BUSY
64
+#define EE_TIMEOUT (uint32_t)HAL_TIMEOUT
65
+
66
+/* Define the size of the sectors to be used */
67
+#define PAGE_SIZE               (uint32_t)0x4000  /* Page size = 16KByte */
68
+
69
+/* Device voltage range supposed to be [2.7V to 3.6V], the operation will
70
+   be done by word  */
71
+#define VOLTAGE_RANGE           (uint8_t)VOLTAGE_RANGE_3
72
+
73
+/* EEPROM start address in Flash */
74
+#define EEPROM_START_ADDRESS  ((uint32_t)0x08100000) /* EEPROM emulation start address:
75
+                                                  from sector2 : after 16KByte of used
76
+                                                  Flash memory */
77
+
78
+/* Pages 0 and 1 base and end addresses */
79
+#define PAGE0_BASE_ADDRESS    ((uint32_t)(EEPROM_START_ADDRESS + 0x0000))
80
+#define PAGE0_END_ADDRESS     ((uint32_t)(EEPROM_START_ADDRESS + (PAGE_SIZE - 1)))
81
+#define PAGE0_ID               FLASH_SECTOR_1
82
+
83
+#define PAGE1_BASE_ADDRESS    ((uint32_t)(EEPROM_START_ADDRESS + 0x4000))
84
+#define PAGE1_END_ADDRESS     ((uint32_t)(EEPROM_START_ADDRESS + (2 * PAGE_SIZE - 1)))
85
+#define PAGE1_ID               FLASH_SECTOR_2
86
+
87
+/* Used Flash pages for EEPROM emulation */
88
+#define PAGE0                 ((uint16_t)0x0000)
89
+#define PAGE1                 ((uint16_t)0x0001) /* Page nb between PAGE0_BASE_ADDRESS & PAGE1_BASE_ADDRESS*/
90
+
91
+/* No valid page define */
92
+#define NO_VALID_PAGE         ((uint16_t)0x00AB)
93
+
94
+/* Page status definitions */
95
+#define ERASED                ((uint16_t)0xFFFF)     /* Page is empty */
96
+#define RECEIVE_DATA          ((uint16_t)0xEEEE)     /* Page is marked to receive data */
97
+#define VALID_PAGE            ((uint16_t)0x0000)     /* Page containing valid data */
98
+
99
+/* Valid pages in read and write defines */
100
+#define READ_FROM_VALID_PAGE  ((uint8_t)0x00)
101
+#define WRITE_IN_VALID_PAGE   ((uint8_t)0x01)
102
+
103
+/* Page full define */
104
+#define PAGE_FULL             ((uint8_t)0x80)
105
+
106
+/* Variables' number */
107
+#define NB_OF_VAR             ((uint16_t)4096)
108
+
109
+/* Exported types ------------------------------------------------------------*/
110
+/* Exported macro ------------------------------------------------------------*/
111
+/* Exported functions ------------------------------------------------------- */
112
+uint16_t EE_Initialise(void);
113
+uint16_t EE_ReadVariable(uint16_t VirtAddress, uint16_t* Data);
114
+uint16_t EE_WriteVariable(uint16_t VirtAddress, uint16_t Data);
115
+
116
+#endif /* __EEEPROM_H */
117
+
118
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

+ 146
- 0
Marlin/src/HAL/HAL_STM32F7/EmulatedEeprom.cpp 查看文件

@@ -0,0 +1,146 @@
1
+/**
2
+ * Marlin 3D Printer Firmware
3
+ * Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
+ *
5
+ * This program is free software: you can redistribute it and/or modify
6
+ * it under the terms of the GNU General Public License as published by
7
+ * the Free Software Foundation, either version 3 of the License, or
8
+ * (at your option) any later version.
9
+ *
10
+ * This program 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
13
+ * GNU General Public License for more details.
14
+ *
15
+ * You should have received a copy of the GNU General Public License
16
+ * along with this program.  If not, see <http://www.gnu.org/licenses/>.
17
+ *
18
+ */
19
+
20
+#ifdef STM32F7
21
+ 
22
+/**
23
+ * Description: functions for I2C connected external EEPROM.
24
+ * Not platform dependent.
25
+ */
26
+
27
+#include "../../inc/MarlinConfig.h"
28
+
29
+// --------------------------------------------------------------------------
30
+// Includes
31
+// --------------------------------------------------------------------------
32
+
33
+#include "../HAL.h"
34
+#include "EEPROM_Emul/eeprom_emul.h"
35
+
36
+
37
+// --------------------------------------------------------------------------
38
+// Externals
39
+// --------------------------------------------------------------------------
40
+
41
+// --------------------------------------------------------------------------
42
+// Local defines
43
+// --------------------------------------------------------------------------
44
+
45
+// --------------------------------------------------------------------------
46
+// Types
47
+// --------------------------------------------------------------------------
48
+
49
+// --------------------------------------------------------------------------
50
+// Variables
51
+// --------------------------------------------------------------------------
52
+
53
+// --------------------------------------------------------------------------
54
+// Public Variables
55
+// --------------------------------------------------------------------------
56
+
57
+// --------------------------------------------------------------------------
58
+// Private Variables
59
+// --------------------------------------------------------------------------
60
+static bool eeprom_initialised = false;
61
+// --------------------------------------------------------------------------
62
+// Function prototypes
63
+// --------------------------------------------------------------------------
64
+
65
+// --------------------------------------------------------------------------
66
+// Private functions
67
+// --------------------------------------------------------------------------
68
+
69
+// --------------------------------------------------------------------------
70
+// Public functions
71
+// --------------------------------------------------------------------------
72
+
73
+// FLASH_FLAG_PGSERR (Programming Sequence Error) was renamed to
74
+// FLASH_FLAG_ERSERR (Erasing Sequence Error) in STM32F7
75
+#define FLASH_FLAG_PGSERR FLASH_FLAG_ERSERR
76
+
77
+// --------------------------------------------------------------------------
78
+// EEPROM
79
+// --------------------------------------------------------------------------
80
+
81
+
82
+void eeprom_init() {
83
+  if(!eeprom_initialised) {
84
+    HAL_FLASH_Unlock();
85
+
86
+    __HAL_FLASH_CLEAR_FLAG(FLASH_FLAG_EOP | FLASH_FLAG_OPERR | FLASH_FLAG_WRPERR |FLASH_FLAG_PGAERR | FLASH_FLAG_PGPERR | FLASH_FLAG_PGSERR);
87
+
88
+    /* EEPROM Init */
89
+    if(EE_Initialise() != EE_OK)
90
+    {
91
+      while(1) {
92
+        HAL_Delay(1);
93
+      }
94
+    }
95
+
96
+    HAL_FLASH_Lock();
97
+    eeprom_initialised = true;
98
+  }
99
+
100
+}
101
+
102
+void eeprom_write_byte(unsigned char *pos, unsigned char value) {
103
+  uint16_t eeprom_address = (unsigned) pos;
104
+
105
+  eeprom_init();
106
+
107
+  HAL_FLASH_Unlock();
108
+  __HAL_FLASH_CLEAR_FLAG(FLASH_FLAG_EOP | FLASH_FLAG_OPERR | FLASH_FLAG_WRPERR |FLASH_FLAG_PGAERR | FLASH_FLAG_PGPERR | FLASH_FLAG_PGSERR);
109
+  if(EE_WriteVariable(eeprom_address, (uint16_t) value) != EE_OK) {
110
+    while(1) {
111
+      HAL_Delay(1);
112
+    }
113
+  }
114
+  HAL_FLASH_Lock();
115
+}
116
+
117
+unsigned char eeprom_read_byte(unsigned char *pos) {
118
+  uint16_t data = 0xFF;
119
+  uint16_t eeprom_address = (unsigned) pos;
120
+
121
+  eeprom_init();
122
+
123
+  if(EE_ReadVariable(eeprom_address, &data) != EE_OK) {
124
+    return (char) data;
125
+  }
126
+  return (char)data;
127
+}
128
+
129
+void eeprom_read_block (void *__dst, const void *__src, size_t __n) {
130
+  uint16_t data = 0xFF;
131
+  uint16_t eeprom_address = (unsigned) __src;
132
+
133
+  eeprom_init();
134
+
135
+  for(uint8_t c = 0; c < __n; c++) {
136
+    EE_ReadVariable(eeprom_address+c, &data);
137
+    *((uint8_t*)__dst + c) = data;
138
+  }
139
+}
140
+
141
+void eeprom_update_block (const void *__src, void *__dst, size_t __n) {
142
+
143
+}
144
+
145
+#endif // STM32F7
146
+

+ 143
- 0
Marlin/src/HAL/HAL_STM32F7/HAL_STM32F7.cpp 查看文件

@@ -0,0 +1,143 @@
1
+/**
2
+ * Marlin 3D Printer Firmware
3
+ *
4
+ * Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
5
+ * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
6
+ * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com
7
+ * Copyright (c) 2017 Victor Perez
8
+ *
9
+ * This program is free software: you can redistribute it and/or modify
10
+ * it under the terms of the GNU General Public License as published by
11
+ * the Free Software Foundation, either version 3 of the License, or
12
+ * (at your option) any later version.
13
+ *
14
+ * This program is distributed in the hope that it will be useful,
15
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
16
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
17
+ * GNU General Public License for more details.
18
+ *
19
+ * You should have received a copy of the GNU General Public License
20
+ * along with this program.  If not, see <http://www.gnu.org/licenses/>.
21
+ *
22
+ */
23
+
24
+
25
+#ifdef STM32F7
26
+
27
+// --------------------------------------------------------------------------
28
+// Includes
29
+// --------------------------------------------------------------------------
30
+
31
+#include "../HAL.h"
32
+
33
+//#include <Wire.h>
34
+
35
+// --------------------------------------------------------------------------
36
+// Externals
37
+// --------------------------------------------------------------------------
38
+
39
+// --------------------------------------------------------------------------
40
+// Local defines
41
+// --------------------------------------------------------------------------
42
+
43
+// --------------------------------------------------------------------------
44
+// Types
45
+// --------------------------------------------------------------------------
46
+
47
+// --------------------------------------------------------------------------
48
+// Variables
49
+// --------------------------------------------------------------------------
50
+
51
+// --------------------------------------------------------------------------
52
+// Public Variables
53
+// --------------------------------------------------------------------------
54
+
55
+uint16_t HAL_adc_result;
56
+
57
+// --------------------------------------------------------------------------
58
+// Private Variables
59
+// --------------------------------------------------------------------------
60
+
61
+// --------------------------------------------------------------------------
62
+// Function prototypes
63
+// --------------------------------------------------------------------------
64
+
65
+// --------------------------------------------------------------------------
66
+// Private functions
67
+// --------------------------------------------------------------------------
68
+
69
+// --------------------------------------------------------------------------
70
+// Public functions
71
+// --------------------------------------------------------------------------
72
+
73
+/* VGPV Done with defines
74
+// disable interrupts
75
+void cli(void) { noInterrupts(); }
76
+
77
+// enable interrupts
78
+void sei(void) { interrupts(); }
79
+*/
80
+
81
+void HAL_clear_reset_source(void) { __HAL_RCC_CLEAR_RESET_FLAGS(); }
82
+
83
+uint8_t HAL_get_reset_source (void) {
84
+ if(__HAL_RCC_GET_FLAG(RCC_FLAG_IWDGRST) != RESET)
85
+  return RST_WATCHDOG;
86
+
87
+ if(__HAL_RCC_GET_FLAG(RCC_FLAG_SFTRST) != RESET)
88
+   return RST_SOFTWARE;
89
+
90
+ if(__HAL_RCC_GET_FLAG(RCC_FLAG_PINRST) != RESET)
91
+   return RST_EXTERNAL;
92
+
93
+ if(__HAL_RCC_GET_FLAG(RCC_FLAG_PORRST) != RESET)
94
+   return RST_POWER_ON;
95
+  
96
+  return 0;
97
+}
98
+
99
+void _delay_ms(const int delay_ms) { delay(delay_ms); }
100
+
101
+extern "C" {
102
+  extern unsigned int _ebss; // end of bss section
103
+}
104
+
105
+
106
+
107
+// return free memory between end of heap (or end bss) and whatever is current
108
+
109
+/*
110
+#include "wirish/syscalls.c"
111
+//extern caddr_t _sbrk(int incr);
112
+#ifndef CONFIG_HEAP_END
113
+extern char _lm_heap_end;
114
+#define CONFIG_HEAP_END ((caddr_t)&_lm_heap_end)
115
+#endif
116
+
117
+extern "C" {
118
+  static int freeMemory() {
119
+    char top = 't';
120
+    return &top - reinterpret_cast<char*>(sbrk(0));
121
+  }
122
+  int freeMemory() {
123
+    int free_memory;
124
+    int heap_end = (int)_sbrk(0);
125
+    free_memory = ((int)&free_memory) - ((int)heap_end);
126
+    return free_memory;
127
+  }
128
+}
129
+*/
130
+
131
+// --------------------------------------------------------------------------
132
+// ADC
133
+// --------------------------------------------------------------------------
134
+
135
+void HAL_adc_start_conversion(const uint8_t adc_pin) {
136
+  HAL_adc_result = analogRead(adc_pin);
137
+}
138
+
139
+uint16_t HAL_adc_get_result(void) {
140
+  return HAL_adc_result;
141
+}
142
+
143
+#endif // STM32F7

+ 236
- 0
Marlin/src/HAL/HAL_STM32F7/HAL_STM32F7.h 查看文件

@@ -0,0 +1,236 @@
1
+/**
2
+ * Marlin 3D Printer Firmware
3
+ *
4
+ * Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
5
+ * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
6
+ * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com
7
+ * Copyright (c) 2017 Victor Perez
8
+ *
9
+ * This program is free software: you can redistribute it and/or modify
10
+ * it under the terms of the GNU General Public License as published by
11
+ * the Free Software Foundation, either version 3 of the License, or
12
+ * (at your option) any later version.
13
+ *
14
+ * This program is distributed in the hope that it will be useful,
15
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
16
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
17
+ * GNU General Public License for more details.
18
+ *
19
+ * You should have received a copy of the GNU General Public License
20
+ * along with this program.  If not, see <http://www.gnu.org/licenses/>.
21
+ *
22
+ */
23
+
24
+
25
+
26
+#ifndef _HAL_STM32F7_H
27
+#define _HAL_STM32F7_H
28
+
29
+#undef DEBUG_NONE
30
+
31
+#ifndef vsnprintf_P
32
+  #define vsnprintf_P vsnprintf
33
+#endif
34
+
35
+// --------------------------------------------------------------------------
36
+// Includes
37
+// --------------------------------------------------------------------------
38
+
39
+#include <stdint.h>
40
+
41
+#include "Arduino.h"
42
+
43
+#include "fastio_STM32F7.h"
44
+#include "watchdog_STM32F7.h"
45
+
46
+#include "HAL_timers_STM32F7.h"
47
+
48
+
49
+// --------------------------------------------------------------------------
50
+// Defines
51
+// --------------------------------------------------------------------------
52
+
53
+//Serial override
54
+//extern HalSerial usb_serial;
55
+
56
+#if !WITHIN(SERIAL_PORT, -1, 6)
57
+  #error "SERIAL_PORT must be from -1 to 6"
58
+#endif
59
+#if SERIAL_PORT == -1
60
+  #define MYSERIAL0 SerialUSB	
61
+#elif SERIAL_PORT == 1
62
+  #define MYSERIAL0 SerialUART1
63
+#elif SERIAL_PORT == 2
64
+  #define MYSERIAL0 SerialUART2
65
+#elif SERIAL_PORT == 3
66
+  #define MYSERIAL0 SerialUART3
67
+#elif SERIAL_PORT == 4
68
+  #define MYSERIAL0 SerialUART4
69
+#elif SERIAL_PORT == 5
70
+  #define MYSERIAL0 SerialUART5
71
+#elif SERIAL_PORT == 6
72
+  #define MYSERIAL0 SerialUART6
73
+#endif
74
+
75
+#ifdef SERIAL_PORT_2
76
+  #if !WITHIN(SERIAL_PORT_2, -1, 6)
77
+    #error "SERIAL_PORT_2 must be from -1 to 6"
78
+  #elif SERIAL_PORT_2 == SERIAL_PORT
79
+    #error "SERIAL_PORT_2 must be different than SERIAL_PORT"
80
+  #endif
81
+  #define NUM_SERIAL 2
82
+  #if SERIAL_PORT_2 == -1 
83
+    #define MYSERIAL1 SerialUSB
84
+  #elif SERIAL_PORT_2 == 1
85
+    #define MYSERIAL1 SerialUART1
86
+  #elif SERIAL_PORT_2 == 2
87
+    #define MYSERIAL1 SerialUART2
88
+  #elif SERIAL_PORT_2 == 3
89
+    #define MYSERIAL1 SerialUART3
90
+  #elif SERIAL_PORT_2 == 4
91
+    #define MYSERIAL1 SerialUART4
92
+  #elif SERIAL_PORT_2 == 5
93
+    #define MYSERIAL1 SerialUART5
94
+  #elif SERIAL_PORT_2 == 6
95
+    #define MYSERIAL1 SerialUART6
96
+  #endif
97
+#else
98
+  #define NUM_SERIAL 1
99
+#endif
100
+
101
+#define _BV(bit) 	(1 << (bit))
102
+
103
+/**
104
+ * TODO: review this to return 1 for pins that are not analog input
105
+ */
106
+#ifndef analogInputToDigitalPin
107
+  #define analogInputToDigitalPin(p) (p)
108
+#endif
109
+
110
+#define CRITICAL_SECTION_START	noInterrupts();
111
+#define CRITICAL_SECTION_END    interrupts();
112
+
113
+// On AVR this is in math.h?
114
+#define square(x) ((x)*(x))
115
+
116
+#ifndef strncpy_P
117
+  #define strncpy_P(dest, src, num) strncpy((dest), (src), (num))
118
+#endif
119
+
120
+// Fix bug in pgm_read_ptr
121
+#undef pgm_read_ptr
122
+#define pgm_read_ptr(addr) (*(addr))
123
+
124
+#define RST_POWER_ON   1
125
+#define RST_EXTERNAL   2
126
+#define RST_BROWN_OUT  4
127
+#define RST_WATCHDOG   8
128
+#define RST_JTAG       16
129
+#define RST_SOFTWARE   32
130
+#define RST_BACKUP     64
131
+
132
+// --------------------------------------------------------------------------
133
+// Types
134
+// --------------------------------------------------------------------------
135
+
136
+typedef int8_t pin_t;
137
+
138
+// --------------------------------------------------------------------------
139
+// Public Variables
140
+// --------------------------------------------------------------------------
141
+
142
+/** result of last ADC conversion */
143
+extern uint16_t HAL_adc_result;
144
+
145
+// --------------------------------------------------------------------------
146
+// Public functions
147
+// --------------------------------------------------------------------------
148
+
149
+// Disable interrupts
150
+#define cli() do {  DISABLE_TEMPERATURE_INTERRUPT(); DISABLE_STEPPER_DRIVER_INTERRUPT(); } while(0)
151
+
152
+// Enable interrupts
153
+#define sei() do {  ENABLE_TEMPERATURE_INTERRUPT(); ENABLE_STEPPER_DRIVER_INTERRUPT(); } while(0)
154
+
155
+// Memory related
156
+#define __bss_end __bss_end__
157
+
158
+/** clear reset reason */
159
+void HAL_clear_reset_source (void);
160
+
161
+/** reset reason */
162
+uint8_t HAL_get_reset_source (void);
163
+
164
+void _delay_ms(const int delay);
165
+
166
+/*
167
+extern "C" {
168
+  int freeMemory(void);
169
+}
170
+*/
171
+
172
+extern "C" char* _sbrk(int incr);
173
+/*
174
+static int freeMemory() {
175
+  volatile int top;
176
+  top = (int)((char*)&top - reinterpret_cast<char*>(_sbrk(0)));
177
+  return top;
178
+}
179
+*/
180
+static int freeMemory() {
181
+  volatile char top;
182
+  return &top - reinterpret_cast<char*>(_sbrk(0));
183
+}
184
+
185
+// SPI: Extended functions which take a channel number (hardware SPI only)
186
+/** Write single byte to specified SPI channel */
187
+void spiSend(uint32_t chan, byte b);
188
+/** Write buffer to specified SPI channel */
189
+void spiSend(uint32_t chan, const uint8_t* buf, size_t n);
190
+/** Read single byte from specified SPI channel */
191
+uint8_t spiRec(uint32_t chan);
192
+
193
+
194
+// EEPROM
195
+
196
+/**
197
+ * TODO: Write all this eeprom stuff. Can emulate eeprom in flash as last resort.
198
+ * Wire library should work for i2c eeproms.
199
+ */
200
+void eeprom_write_byte(unsigned char *pos, unsigned char value);
201
+unsigned char eeprom_read_byte(unsigned char *pos);
202
+void eeprom_read_block (void *__dst, const void *__src, size_t __n);
203
+void eeprom_update_block (const void *__src, void *__dst, size_t __n);
204
+
205
+// ADC
206
+
207
+#define HAL_ANALOG_SELECT(pin) pinMode(pin, INPUT)
208
+
209
+inline void HAL_adc_init(void) {}
210
+
211
+#define HAL_START_ADC(pin)  HAL_adc_start_conversion(pin)
212
+#define HAL_READ_ADC        HAL_adc_result
213
+
214
+void HAL_adc_start_conversion(const uint8_t adc_pin);
215
+
216
+uint16_t HAL_adc_get_result(void);
217
+
218
+/* Todo: Confirm none of this is needed.
219
+uint16_t HAL_getAdcReading(uint8_t chan);
220
+
221
+void HAL_startAdcConversion(uint8_t chan);
222
+uint8_t HAL_pinToAdcChannel(int pin);
223
+
224
+uint16_t HAL_getAdcFreerun(uint8_t chan, bool wait_for_conversion = false);
225
+//uint16_t HAL_getAdcSuperSample(uint8_t chan);
226
+
227
+void HAL_enable_AdcFreerun(void);
228
+//void HAL_disable_AdcFreerun(uint8_t chan);
229
+
230
+*/
231
+
232
+#define GET_PIN_MAP_PIN(index) index
233
+#define GET_PIN_MAP_INDEX(pin) pin
234
+#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval)
235
+
236
+#endif // _HAL_STM32F7_H

+ 52
- 0
Marlin/src/HAL/HAL_STM32F7/HAL_Servo_STM32F7.cpp 查看文件

@@ -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
+ * Copyright (C) 2017 Victor Perez
8
+ *
9
+ * This program is free software: you can redistribute it and/or modify
10
+ * it under the terms of the GNU General Public License as published by
11
+ * the Free Software Foundation, either version 3 of the License, or
12
+ * (at your option) any later version.
13
+ *
14
+ * This program is distributed in the hope that it will be useful,
15
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
16
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
17
+ * GNU General Public License for more details.
18
+ *
19
+ * You should have received a copy of the GNU General Public License
20
+ * along with this program.  If not, see <http://www.gnu.org/licenses/>.
21
+ *
22
+ */
23
+
24
+#ifdef STM32F7
25
+
26
+#include "../../../src/inc/MarlinConfig.h"
27
+
28
+#if HAS_SERVOS
29
+
30
+#include "HAL_Servo_STM32F7.h"
31
+
32
+int8_t libServo::attach(const int pin) {
33
+  if (this->servoIndex >= MAX_SERVOS) return -1;
34
+  return Servo::attach(pin);
35
+}
36
+
37
+int8_t libServo::attach(const int pin, const int min, const int max) {
38
+  return Servo::attach(pin, min, max);
39
+}
40
+
41
+void libServo::move(const int value) {
42
+  if (this->attach(0) >= 0) {
43
+    this->write(value);
44
+    delay(SERVO_DELAY);
45
+    #if ENABLED(DEACTIVATE_SERVOS_AFTER_MOVE)
46
+      this->detach();
47
+    #endif
48
+  }
49
+}
50
+#endif // HAS_SERVOS
51
+
52
+#endif // STM32F7

+ 41
- 0
Marlin/src/HAL/HAL_STM32F7/HAL_Servo_STM32F7.h 查看文件

@@ -0,0 +1,41 @@
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
+ * Copyright (C) 2017 Victor Perez
8
+ *
9
+ * This program is free software: you can redistribute it and/or modify
10
+ * it under the terms of the GNU General Public License as published by
11
+ * the Free Software Foundation, either version 3 of the License, or
12
+ * (at your option) any later version.
13
+ *
14
+ * This program is distributed in the hope that it will be useful,
15
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
16
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
17
+ * GNU General Public License for more details.
18
+ *
19
+ * You should have received a copy of the GNU General Public License
20
+ * along with this program.  If not, see <http://www.gnu.org/licenses/>.
21
+ *
22
+ */
23
+
24
+#ifndef HAL_SERVO_STM32F7_H
25
+#define HAL_SERVO_STM32F7_H
26
+
27
+#include <../../libraries/Servo/src/Servo.h>
28
+
29
+// Inherit and expand on the official library
30
+class libServo : public Servo {
31
+public:
32
+    int8_t attach(const int pin);
33
+    int8_t attach(const int pin, const int min, const int max);
34
+    void move(const int value);
35
+private:
36
+    uint16_t min_ticks;
37
+    uint16_t max_ticks;
38
+    uint8_t servoIndex;               // index into the channel data for this servo
39
+};
40
+
41
+#endif // HAL_SERVO_STM32F7_H

+ 178
- 0
Marlin/src/HAL/HAL_STM32F7/HAL_spi_STM32F7.cpp 查看文件

@@ -0,0 +1,178 @@
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
+ * Copyright (C) 2017 Victor Perez
8
+ *
9
+ * This program is free software: you can redistribute it and/or modify
10
+ * it under the terms of the GNU General Public License as published by
11
+ * the Free Software Foundation, either version 3 of the License, or
12
+ * (at your option) any later version.
13
+ *
14
+ * This program is distributed in the hope that it will be useful,
15
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
16
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
17
+ * GNU General Public License for more details.
18
+ *
19
+ * You should have received a copy of the GNU General Public License
20
+ * along with this program.  If not, see <http://www.gnu.org/licenses/>.
21
+ *
22
+ */
23
+
24
+/**
25
+ * Software SPI functions originally from Arduino Sd2Card Library
26
+ * Copyright (C) 2009 by William Greiman
27
+ */
28
+
29
+/**
30
+ * Adapted to the STM32F7 HAL
31
+ */
32
+
33
+#ifdef STM32F7
34
+
35
+// --------------------------------------------------------------------------
36
+// Includes
37
+// --------------------------------------------------------------------------
38
+
39
+#include "../HAL.h"
40
+//#include "../SPI.h"
41
+#include "SPI.h"
42
+//#include <SPI.h>
43
+#include "pins_arduino.h"
44
+#include "spi_pins.h"
45
+#include "../../core/macros.h"
46
+
47
+
48
+// --------------------------------------------------------------------------
49
+// Public Variables
50
+// --------------------------------------------------------------------------
51
+
52
+static SPISettings spiConfig;
53
+
54
+// --------------------------------------------------------------------------
55
+// Public functions
56
+// --------------------------------------------------------------------------
57
+
58
+#if ENABLED(SOFTWARE_SPI)
59
+  // --------------------------------------------------------------------------
60
+  // Software SPI
61
+  // --------------------------------------------------------------------------
62
+  #error "Software SPI not supported for STM32F7. Use hardware SPI."
63
+
64
+#else
65
+
66
+// --------------------------------------------------------------------------
67
+// Hardware SPI
68
+// --------------------------------------------------------------------------
69
+
70
+/**
71
+ * VGPV SPI speed start and F_CPU/2, by default 72/2 = 36Mhz
72
+ */
73
+
74
+/**
75
+ * @brief  Begin SPI port setup
76
+ *
77
+ * @return Nothing
78
+ *
79
+ * @details Only configures SS pin since libmaple creates and initialize the SPI object
80
+ */
81
+void spiBegin(void) {
82
+  #if !PIN_EXISTS(SS)
83
+    #error SS_PIN not defined!
84
+  #endif
85
+ 
86
+  SET_OUTPUT(SS_PIN);
87
+  WRITE(SS_PIN, HIGH);
88
+  
89
+}
90
+
91
+
92
+
93
+/** Configure SPI for specified SPI speed */
94
+void spiInit(uint8_t spiRate) {
95
+  // Use datarates Marlin uses
96
+  uint32_t clock;
97
+  switch (spiRate) {
98
+  case SPI_FULL_SPEED:    clock = 20000000; break;	//13.9mhz=20000000	6.75mhz=10000000	3.38mhz=5000000	.833mhz=1000000
99
+  case SPI_HALF_SPEED:    clock =  5000000; break;
100
+  case SPI_QUARTER_SPEED: clock =  2500000; break;
101
+  case SPI_EIGHTH_SPEED:  clock =  1250000; break;
102
+  case SPI_SPEED_5:       clock =   625000; break;
103
+  case SPI_SPEED_6:       clock =   300000; break;
104
+  default:
105
+    clock = 4000000; // Default from the SPI libarary
106
+  }
107
+  spiConfig = SPISettings(clock, MSBFIRST, SPI_MODE0);
108
+  SPI.begin();
109
+}
110
+
111
+
112
+
113
+/**
114
+ * @brief  Receives a single byte from the SPI port.
115
+ *
116
+ * @return Byte received
117
+ *
118
+ * @details
119
+ */
120
+uint8_t spiRec(void) {
121
+  SPI.beginTransaction(spiConfig);
122
+  uint8_t returnByte = SPI.transfer(0xFF);
123
+  SPI.endTransaction();
124
+  return returnByte;
125
+}
126
+
127
+/**
128
+ * @brief  Receives a number of bytes from the SPI port to a buffer
129
+ *
130
+ * @param  buf   Pointer to starting address of buffer to write to.
131
+ * @param  nbyte Number of bytes to receive.
132
+ * @return Nothing
133
+ *
134
+ * @details Uses DMA
135
+ */
136
+
137
+
138
+void spiRead(uint8_t* buf, uint16_t nbyte) {
139
+  SPI.beginTransaction(spiConfig);
140
+  SPI.dmaTransfer(0, const_cast<uint8_t*>(buf), nbyte);
141
+  SPI.endTransaction();
142
+}
143
+
144
+/**
145
+ * @brief  Sends a single byte on SPI port
146
+ *
147
+ * @param  b Byte to send
148
+ *
149
+ * @details
150
+ */
151
+void spiSend(uint8_t b) {
152
+  SPI.beginTransaction(spiConfig);
153
+  SPI.transfer(b);
154
+  SPI.endTransaction();
155
+}
156
+
157
+/**
158
+ * @brief  Write token and then write from 512 byte buffer to SPI (for SD card)
159
+ *
160
+ * @param  buf   Pointer with buffer start address
161
+ * @return Nothing
162
+ *
163
+ * @details Use DMA
164
+ */
165
+ 
166
+
167
+void spiSendBlock(uint8_t token, const uint8_t* buf) {
168
+  SPI.beginTransaction(spiConfig);
169
+  SPI.transfer(token);
170
+  SPI.dmaSend(const_cast<uint8_t*>(buf), 512);
171
+  SPI.endTransaction();
172
+}
173
+
174
+
175
+
176
+#endif // SOFTWARE_SPI
177
+
178
+#endif // STM32F7

+ 154
- 0
Marlin/src/HAL/HAL_STM32F7/HAL_timers_STM32F7.cpp 查看文件

@@ -0,0 +1,154 @@
1
+/**
2
+ * Marlin 3D Printer Firmware
3
+ *
4
+ * Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
5
+ * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
6
+ * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com
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
+#ifdef STM32F7
25
+// --------------------------------------------------------------------------
26
+// Includes
27
+// --------------------------------------------------------------------------
28
+
29
+#include "../HAL.h"
30
+
31
+#include "HAL_timers_STM32F7.h"
32
+
33
+// --------------------------------------------------------------------------
34
+// Externals
35
+// --------------------------------------------------------------------------
36
+
37
+// --------------------------------------------------------------------------
38
+// Local defines
39
+// --------------------------------------------------------------------------
40
+
41
+#define NUM_HARDWARE_TIMERS 2
42
+
43
+//#define PRESCALER 1
44
+// --------------------------------------------------------------------------
45
+// Types
46
+// --------------------------------------------------------------------------
47
+
48
+
49
+// --------------------------------------------------------------------------
50
+// Public Variables
51
+// --------------------------------------------------------------------------
52
+
53
+// --------------------------------------------------------------------------
54
+// Private Variables
55
+// --------------------------------------------------------------------------
56
+
57
+tTimerConfig timerConfig[NUM_HARDWARE_TIMERS];
58
+
59
+// --------------------------------------------------------------------------
60
+// Function prototypes
61
+// --------------------------------------------------------------------------
62
+
63
+// --------------------------------------------------------------------------
64
+// Private functions
65
+// --------------------------------------------------------------------------
66
+
67
+// --------------------------------------------------------------------------
68
+// Public functions
69
+// --------------------------------------------------------------------------
70
+
71
+
72
+bool timers_initialised[NUM_HARDWARE_TIMERS] = {false};
73
+
74
+void HAL_timer_start(uint8_t timer_num, uint32_t frequency) {
75
+
76
+  if(!timers_initialised[timer_num]) {
77
+    switch (timer_num) {
78
+      case STEP_TIMER_NUM:
79
+      //STEPPER TIMER TIM5 //use a 32bit timer 
80
+      __HAL_RCC_TIM5_CLK_ENABLE();
81
+      timerConfig[0].timerdef.Instance               = TIM5;
82
+      timerConfig[0].timerdef.Init.Prescaler         = (STEPPER_TIMER_PRESCALE);
83
+      timerConfig[0].timerdef.Init.CounterMode       = TIM_COUNTERMODE_UP;
84
+      timerConfig[0].timerdef.Init.ClockDivision     = TIM_CLOCKDIVISION_DIV1;
85
+      timerConfig[0].IRQ_Id = TIM5_IRQn;
86
+      timerConfig[0].callback = (uint32_t)TC5_Handler;
87
+      HAL_NVIC_SetPriority(timerConfig[0].IRQ_Id, 1, 0);
88
+      pinMode(STEPPER_ENABLE_PIN,OUTPUT);
89
+      digitalWrite(STEPPER_ENABLE_PIN,LOW);
90
+      break;
91
+    case TEMP_TIMER_NUM:
92
+      //TEMP TIMER TIM7 // any available 16bit Timer (1 already used for PWM)
93
+      __HAL_RCC_TIM7_CLK_ENABLE();
94
+      timerConfig[1].timerdef.Instance               = TIM7;
95
+      timerConfig[1].timerdef.Init.Prescaler         = (TEMP_TIMER_PRESCALE); 
96
+      timerConfig[1].timerdef.Init.CounterMode       = TIM_COUNTERMODE_UP;   
97
+      timerConfig[1].timerdef.Init.ClockDivision     = TIM_CLOCKDIVISION_DIV1;
98
+      timerConfig[1].IRQ_Id = TIM7_IRQn;
99
+      timerConfig[1].callback = (uint32_t)TC7_Handler;
100
+      HAL_NVIC_SetPriority(timerConfig[1].IRQ_Id, 2, 0);
101
+      break;
102
+    }
103
+    timers_initialised[timer_num] = true;
104
+  }
105
+
106
+  timerConfig[timer_num].timerdef.Init.Period =  ((HAL_TIMER_RATE / timerConfig[timer_num].timerdef.Init.Prescaler) / (frequency)) - 1;
107
+
108
+  if(HAL_TIM_Base_Init(&timerConfig[timer_num].timerdef)  == HAL_OK ){
109
+    HAL_TIM_Base_Start_IT(&timerConfig[timer_num].timerdef);
110
+  } 
111
+
112
+}
113
+
114
+//forward the interrupt
115
+extern "C" void TIM5_IRQHandler()
116
+{
117
+    ((void(*)(void))timerConfig[0].callback)();
118
+}
119
+extern "C" void TIM7_IRQHandler()
120
+{
121
+    ((void(*)(void))timerConfig[1].callback)();
122
+}
123
+
124
+void HAL_timer_set_count (uint8_t timer_num, uint32_t count) {
125
+  __HAL_TIM_SetAutoreload(&timerConfig[timer_num].timerdef, count);
126
+}
127
+
128
+void HAL_timer_set_current_count (uint8_t timer_num, uint32_t count) {
129
+  __HAL_TIM_SetAutoreload(&timerConfig[timer_num].timerdef, count);
130
+}
131
+
132
+void HAL_timer_enable_interrupt (uint8_t timer_num) {
133
+  HAL_NVIC_EnableIRQ(timerConfig[timer_num].IRQ_Id);
134
+}
135
+
136
+void HAL_timer_disable_interrupt (uint8_t timer_num) {
137
+  HAL_NVIC_DisableIRQ(timerConfig[timer_num].IRQ_Id);
138
+}
139
+
140
+hal_timer_t HAL_timer_get_count (uint8_t timer_num) {
141
+  return __HAL_TIM_GetAutoreload(&timerConfig[timer_num].timerdef);
142
+}
143
+
144
+uint32_t HAL_timer_get_current_count(uint8_t timer_num) {
145
+  return __HAL_TIM_GetCounter(&timerConfig[timer_num].timerdef);
146
+}
147
+
148
+void HAL_timer_isr_prologue (uint8_t timer_num) {
149
+  if (__HAL_TIM_GET_FLAG(&timerConfig[timer_num].timerdef, TIM_FLAG_UPDATE) == SET) {
150
+    __HAL_TIM_CLEAR_FLAG(&timerConfig[timer_num].timerdef, TIM_FLAG_UPDATE);
151
+  }
152
+}
153
+
154
+#endif 

+ 112
- 0
Marlin/src/HAL/HAL_STM32F7/HAL_timers_STM32F7.h 查看文件

@@ -0,0 +1,112 @@
1
+/**
2
+ * Marlin 3D Printer Firmware
3
+ *
4
+ * Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
5
+ * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
6
+ * Copyright (c) 2017 Victor Perez
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
+
25
+#ifndef _HAL_TIMERS_STM32F7_H
26
+#define _HAL_TIMERS_STM32F7_H
27
+
28
+// --------------------------------------------------------------------------
29
+// Includes
30
+// --------------------------------------------------------------------------
31
+
32
+#include <stdint.h>
33
+
34
+// --------------------------------------------------------------------------
35
+// Defines
36
+// --------------------------------------------------------------------------
37
+
38
+
39
+#define FORCE_INLINE __attribute__((always_inline)) inline
40
+
41
+#define hal_timer_t uint32_t	//hal_timer_t uint32_t		//TODO: One is 16-bit, one 32-bit - does this need to be checked?
42
+#define HAL_TIMER_TYPE_MAX 0xFFFF	
43
+
44
+#define STEP_TIMER_NUM 0  // index of timer to use for stepper
45
+#define TEMP_TIMER_NUM 1  // index of timer to use for temperature
46
+
47
+#define HAL_TIMER_RATE         (HAL_RCC_GetSysClockFreq()/2)  // frequency of timer peripherals
48
+#define STEPPER_TIMER_PRESCALE 54            // was 40,prescaler for setting stepper timer, 2Mhz
49
+#define HAL_STEPPER_TIMER_RATE (HAL_TIMER_RATE / STEPPER_TIMER_PRESCALE)   // frequency of stepper timer (HAL_TIMER_RATE / STEPPER_TIMER_PRESCALE)
50
+#define HAL_TICKS_PER_US       ((HAL_STEPPER_TIMER_RATE) / 1000000) // stepper timer ticks per us
51
+
52
+#define PULSE_TIMER_NUM STEP_TIMER_NUM
53
+#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE
54
+
55
+#define TEMP_TIMER_PRESCALE     1000 // prescaler for setting Temp timer, 72Khz
56
+#define TEMP_TIMER_FREQUENCY    1000 // temperature interrupt frequency
57
+
58
+#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt (STEP_TIMER_NUM)
59
+#define DISABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_disable_interrupt (STEP_TIMER_NUM)
60
+
61
+#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt (TEMP_TIMER_NUM)
62
+#define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt (TEMP_TIMER_NUM)
63
+
64
+#define HAL_ENABLE_ISRs() do { if (thermalManager.in_temp_isr)DISABLE_TEMPERATURE_INTERRUPT(); else ENABLE_TEMPERATURE_INTERRUPT(); ENABLE_STEPPER_DRIVER_INTERRUPT(); } while(0)
65
+// TODO change this
66
+
67
+
68
+extern void TC5_Handler();
69
+extern void TC7_Handler();
70
+#define HAL_STEP_TIMER_ISR  void TC5_Handler()
71
+#define HAL_TEMP_TIMER_ISR  void TC7_Handler()
72
+
73
+// --------------------------------------------------------------------------
74
+// Types
75
+// --------------------------------------------------------------------------
76
+
77
+typedef struct {
78
+  TIM_HandleTypeDef timerdef;
79
+  IRQn_Type   IRQ_Id;
80
+  uint32_t callback;
81
+} tTimerConfig;
82
+
83
+// --------------------------------------------------------------------------
84
+// Public Variables
85
+// --------------------------------------------------------------------------
86
+
87
+//extern const tTimerConfig timerConfig[];
88
+
89
+
90
+
91
+// --------------------------------------------------------------------------
92
+// Public functions
93
+// --------------------------------------------------------------------------
94
+
95
+void HAL_timer_start (uint8_t timer_num, uint32_t frequency);
96
+void HAL_timer_enable_interrupt(uint8_t timer_num);
97
+void HAL_timer_disable_interrupt(uint8_t timer_num);
98
+
99
+
100
+
101
+void HAL_timer_set_count (uint8_t timer_num, uint32_t count);
102
+hal_timer_t HAL_timer_get_count (uint8_t timer_num);
103
+uint32_t HAL_timer_get_current_count(uint8_t timer_num);
104
+
105
+void HAL_timer_set_current_count (uint8_t timer_num, uint32_t count);		//New
106
+/*FORCE_INLINE static void HAL_timer_set_current_count(const uint8_t timer_num, const hal_timer_t count) {
107
+  // To do ??
108
+}*/
109
+
110
+void HAL_timer_isr_prologue (uint8_t timer_num);
111
+
112
+#endif // _HAL_TIMERS_STM32F7_H

+ 28
- 0
Marlin/src/HAL/HAL_STM32F7/README.md 查看文件

@@ -0,0 +1,28 @@
1
+# This HAL is for the STM32F765 board "The Borg" used with STM32Generic Arduino core by danieleff.
2
+
3
+# Original core is located at: 
4
+
5
+https://github.com/danieleff/STM32GENERIC
6
+
7
+but i have not committed the changes needed for the Borg there yet, so please use:
8
+
9
+https://github.com/Spawn32/STM32GENERIC 
10
+
11
+Unzip it into [Arduino]/hardware folder
12
+
13
+
14
+Download the latest GNU ARM Embedded Toolchain: 
15
+
16
+https://developer.arm.com/open-source/gnu-toolchain/gnu-rm/downloads
17
+
18
+(The one in Arduino dosen't support STM32F7).
19
+
20
+Change compiler.path in platform.txt to point to that you downloaded.
21
+
22
+# This HAL is in development.
23
+# Currently only tested on "The Borg".
24
+
25
+You will also need the latest Arduino 1.9.0-beta or newer.
26
+
27
+This HAL is a modified version of Chris Barr's Picoprint STM32F4 HAL, so shouldn't be to hard to get it to work on a F4.
28
+

+ 66
- 0
Marlin/src/HAL/HAL_STM32F7/SanityCheck_STM32F7.h 查看文件

@@ -0,0 +1,66 @@
1
+/**
2
+ * Marlin 3D Printer Firmware
3
+ * Copyright (C) 2016, 2017 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
+ * Test Re-ARM specific configuration values for errors at compile-time.
25
+ */
26
+#if ENABLED(SPINDLE_LASER_ENABLE)
27
+  #if !PIN_EXISTS(SPINDLE_LASER_ENABLE)
28
+    #error "SPINDLE_LASER_ENABLE requires SPINDLE_LASER_ENABLE_PIN."
29
+  #elif SPINDLE_DIR_CHANGE && !PIN_EXISTS(SPINDLE_DIR)
30
+    #error "SPINDLE_DIR_PIN not defined."
31
+  #elif ENABLED(SPINDLE_LASER_PWM) && PIN_EXISTS(SPINDLE_LASER_PWM)
32
+    #if !PWM_PIN(SPINDLE_LASER_PWM_PIN)
33
+      #error "SPINDLE_LASER_PWM_PIN not assigned to a PWM pin."
34
+    #elif !(SPINDLE_LASER_PWM_PIN == 4 || SPINDLE_LASER_PWM_PIN == 6 || SPINDLE_LASER_PWM_PIN == 11)
35
+      #error "SPINDLE_LASER_PWM_PIN must use SERVO0, SERVO1 or SERVO3 connector"
36
+    #elif SPINDLE_LASER_POWERUP_DELAY < 1
37
+      #error "SPINDLE_LASER_POWERUP_DELAY must be greater than 0."
38
+    #elif SPINDLE_LASER_POWERDOWN_DELAY < 1
39
+      #error "SPINDLE_LASER_POWERDOWN_DELAY must be greater than 0."
40
+    #elif !defined(SPINDLE_LASER_PWM_INVERT)
41
+      #error "SPINDLE_LASER_PWM_INVERT missing."
42
+    #elif !defined(SPEED_POWER_SLOPE) || !defined(SPEED_POWER_INTERCEPT) || !defined(SPEED_POWER_MIN) || !defined(SPEED_POWER_MAX)
43
+      #error "SPINDLE_LASER_PWM equation constant(s) missing."
44
+    #elif PIN_EXISTS(CASE_LIGHT) && SPINDLE_LASER_PWM_PIN == CASE_LIGHT_PIN
45
+      #error "SPINDLE_LASER_PWM_PIN is used by CASE_LIGHT_PIN."
46
+    #elif PIN_EXISTS(E0_AUTO_FAN) && SPINDLE_LASER_PWM_PIN == E0_AUTO_FAN_PIN
47
+      #error "SPINDLE_LASER_PWM_PIN is used by E0_AUTO_FAN_PIN."
48
+    #elif PIN_EXISTS(E1_AUTO_FAN) && SPINDLE_LASER_PWM_PIN == E1_AUTO_FAN_PIN
49
+      #error "SPINDLE_LASER_PWM_PIN is used by E1_AUTO_FAN_PIN."
50
+    #elif PIN_EXISTS(E2_AUTO_FAN) && SPINDLE_LASER_PWM_PIN == E2_AUTO_FAN_PIN
51
+      #error "SPINDLE_LASER_PWM_PIN is used by E2_AUTO_FAN_PIN."
52
+    #elif PIN_EXISTS(E3_AUTO_FAN) && SPINDLE_LASER_PWM_PIN == E3_AUTO_FAN_PIN
53
+      #error "SPINDLE_LASER_PWM_PIN is used by E3_AUTO_FAN_PIN."
54
+    #elif PIN_EXISTS(E4_AUTO_FAN) && SPINDLE_LASER_PWM_PIN == E4_AUTO_FAN_PIN
55
+      #error "SPINDLE_LASER_PWM_PIN is used by E4_AUTO_FAN_PIN."
56
+    #elif PIN_EXISTS(FAN) && SPINDLE_LASER_PWM_PIN == FAN_PIN
57
+      #error "SPINDLE_LASER_PWM_PIN is used FAN_PIN."
58
+    #elif PIN_EXISTS(FAN1) && SPINDLE_LASER_PWM_PIN == FAN1_PIN
59
+      #error "SPINDLE_LASER_PWM_PIN is used FAN1_PIN."
60
+    #elif PIN_EXISTS(FAN2) && SPINDLE_LASER_PWM_PIN == FAN2_PIN
61
+      #error "SPINDLE_LASER_PWM_PIN is used FAN2_PIN."
62
+    #elif PIN_EXISTS(CONTROLLERFAN) && SPINDLE_LASER_PWM_PIN == CONTROLLERFAN_PIN
63
+      #error "SPINDLE_LASER_PWM_PIN is used by CONTROLLERFAN_PIN."
64
+    #endif
65
+  #endif
66
+#endif // SPINDLE_LASER_ENABLE

+ 1035
- 0
Marlin/src/HAL/HAL_STM32F7/TMC2660.cpp
文件差異過大導致無法顯示
查看文件


+ 610
- 0
Marlin/src/HAL/HAL_STM32F7/TMC2660.h 查看文件

@@ -0,0 +1,610 @@
1
+/*
2
+ TMC26XStepper.cpp - - TMC26X Stepper library for Wiring/Arduino
3
+ 
4
+ based on the stepper library by Tom Igoe, et. al.
5
+
6
+ Copyright (c) 2011, Interactive Matter, Marcus Nowotny
7
+ 
8
+ Permission is hereby granted, free of charge, to any person obtaining a copy
9
+ of this software and associated documentation files (the "Software"), to deal
10
+ in the Software without restriction, including without limitation the rights
11
+ to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
12
+ copies of the Software, and to permit persons to whom the Software is
13
+ furnished to do so, subject to the following conditions:
14
+ 
15
+ The above copyright notice and this permission notice shall be included in
16
+ all copies or substantial portions of the Software.
17
+ 
18
+ THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
19
+ IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
20
+ FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
21
+ AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
22
+ LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
23
+ OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
24
+ THE SOFTWARE.
25
+
26
+ */
27
+
28
+
29
+
30
+#include "../../inc/MarlinConfig.h"
31
+
32
+// ensure this library description is only included once
33
+#ifndef TMC26XStepper_h
34
+#define TMC26XStepper_h
35
+
36
+//! return value for TMC26XStepper.getOverTemperature() if there is a overtemperature situation in the TMC chip
37
+/*!
38
+ * This warning indicates that the TCM chip is too warm. 
39
+ * It is still working but some parameters may be inferior. 
40
+ * You should do something against it.
41
+ */
42
+#define TMC26X_OVERTEMPERATURE_PREWARING 1
43
+//! return value for TMC26XStepper.getOverTemperature() if there is a overtemperature shutdown in the TMC chip
44
+/*!
45
+ * This warning indicates that the TCM chip is too warm to operate and has shut down to prevent damage. 
46
+ * It will stop working until it cools down again.
47
+ * If you encouter this situation you must do something against it. Like reducing the current or improving the PCB layout 
48
+ * and/or heat management.
49
+ */
50
+#define TMC26X_OVERTEMPERATURE_SHUTDOWN 2
51
+
52
+//which values can be read out
53
+/*!
54
+ * Selects to readout the microstep position from the motor.
55
+ *\sa readStatus()
56
+ */
57
+#define TMC26X_READOUT_POSITION 0
58
+/*!
59
+ * Selects to read out the StallGuard value of the motor.
60
+ *\sa readStatus()
61
+ */
62
+#define TMC26X_READOUT_STALLGUARD 1
63
+/*!
64
+ * Selects to read out the current current setting (acc. to CoolStep) and the upper bits of the StallGuard value from the motor.
65
+ *\sa readStatus(), setCurrent()
66
+ */
67
+#define TMC26X_READOUT_CURRENT 3
68
+
69
+/*!
70
+ * Define to set the minimum current for CoolStep operation to 1/2 of the selected CS minium.
71
+ *\sa setCoolStepConfiguration()
72
+ */
73
+#define COOL_STEP_HALF_CS_LIMIT 0
74
+/*!
75
+ * Define to set the minimum current for CoolStep operation to 1/4 of the selected CS minium.
76
+ *\sa setCoolStepConfiguration()
77
+ */
78
+#define COOL_STEP_QUARTDER_CS_LIMIT 1
79
+
80
+/*!
81
+ * \class TMC26XStepper
82
+ * \brief Class representing a TMC26X stepper driver
83
+ * 
84
+ * In order to use one fo those drivers in your Arduino code you have to create an object of that class:
85
+ * \code
86
+ * TMC26XStepper stepper = TMC26XStepper(200,1,2,3,500);
87
+ * \endcode
88
+ * see TMC26XStepper(int number_of_steps, int cs_pin, int dir_pin, int step_pin, unsigned int rms_current)
89
+ *
90
+ * Keep in mind that you need to start the driver with start() in order to get the TMC26X configured.
91
+ * 
92
+ * The most important function is the move(). It checks if the motor has to do a step or not.
93
+ * It is important that you call move() as often as possible in your Arduino loop() routine. I suggest
94
+ * to use a very fast loop routine and always call it at the beginning or the end.
95
+ *
96
+ * In order to move you have to provide a movement speed with setSpeed(). The speed is a positive value setting
97
+ * the rotations per minute.
98
+ *
99
+ * To really move the motor you have to call step() to tell the driver to move the motor the given number 
100
+ * of steps in the given direction. Positive values move the motor in one direction, negative values in the other direction.
101
+ *
102
+ * You can check with isMoving() if the mototr is still moving or stop it  apruptely with stop().
103
+ */
104
+class TMC26XStepper {
105
+  public:
106
+    /*!
107
+     * \brief creates a new represenatation of a stepper motor connected to a TMC26X stepper driver
108
+     *
109
+     * This is the main constructor. If in doubt use this. You must provide all parameters as described below.
110
+     *
111
+     * \param number_of_steps the number of steps the motor has per rotation.
112
+     * \param cs_pin The Arduino pin you have connected the Cient Select Pin (!CS) of the TMC26X for SPI
113
+     * \param dir_pin the number of the Arduino pin the Direction input of the TMC26X is connected
114
+     * \param step_pin the number of the Arduino pin the step pin of the TMC26X driver is connected.
115
+     * \param rms_current the maximum current to privide to the motor in mA (!). A value of 200 would send up to 200mA to the motor
116
+     * \param resistor the current sense resistor in milli Ohm, defaults to ,15 Ohm ( or 150 milli Ohm) as in the TMC260 Arduino Shield
117
+     *
118
+     * Keep in mind that you must also call TMC26XStepper.start() in order to configure the stepper driver for use.
119
+     *
120
+     * By default the Constant Off Time chopper is used, see TCM262Stepper.setConstantOffTimeChopper() for details. 
121
+     * This should work on most motors (YMMV). You may want to configure and use the Spread Cycle Chopper, see  setSpreadCycleChopper().
122
+     *
123
+     * By default a microstepping of 1/32th is used to provide a smooth motor run, while still giving a good progression per step.
124
+     * You can select a different stepping with setMicrosteps() to aa different value.
125
+     * \sa start(), setMicrosteps()
126
+     */
127
+	TMC26XStepper(int number_of_steps, int cs_pin, int dir_pin, int step_pin, unsigned int current, unsigned int resistor=100);	//resistor=150
128
+	
129
+    /*!
130
+     * \brief configures and starts the TMC26X stepper driver. Before you called this function the stepper driver is in nonfunctional mode.
131
+     *
132
+     * This routine configures the TMC26X stepper driver for the given values via SPI. 
133
+     * Most member functions are non functional if the driver has not been started.
134
+     * Therefore it is best to call this in your Arduino setup() function.
135
+     */
136
+	void start();
137
+    
138
+    /*!
139
+     * \brief resets the stepper in unconfigured mode.
140
+     *
141
+     * This routine enables you to call start again. It does not change anything 
142
+     * in the internal stepper configuration or the desired configuration.
143
+     * It just marks the stepper as not yet startet. You do not have to reconfigure
144
+     * the stepper to start it again, but it is not reset to any factory settings
145
+     * this has to be configured back by yourself.
146
+     * (Hint: Normally you do not need this function)
147
+     */
148
+	void un_start();
149
+
150
+
151
+    /*!
152
+     * \brief Sets the rotation speed in revolutions per minute.
153
+     * \param whatSpeed the desired speed in rotations per minute.
154
+     */
155
+    void setSpeed(unsigned int whatSpeed);
156
+    
157
+    /*!
158
+     * \brief reads out the currently selected speed in revolutions per minute.
159
+     * \sa setSpeed()
160
+     */
161
+    unsigned int getSpeed(void);
162
+
163
+    /*!
164
+     * \brief Set the number of microsteps in 2^i values (rounded) up to 256
165
+     *
166
+     * This method set's the number of microsteps per step in 2^i interval.
167
+     * This means you can select 1, 2, 4, 16, 32, 64, 128 or 256 as valid microsteps.
168
+     * If you give any other value it will be rounded to the next smaller number (3 would give a microstepping of 2).
169
+     * You can always check the current microstepping with getMicrosteps(). 
170
+     */ 
171
+	void setMicrosteps(int number_of_steps);
172
+    
173
+	/*!
174
+     * \brief returns the effective current number of microsteps selected.
175
+     *
176
+     * This function always returns the effective number of microsteps. 
177
+     * This can be a bit different than the micro steps set in setMicrosteps() since it is rounded to 2^i.
178
+     *
179
+     * \sa setMicrosteps()
180
+     */
181
+	int getMicrosteps(void);
182
+
183
+    /*!
184
+     * \brief Initiate a movement for the given number of steps. Positive numbers move in one, negative numbers in the other direction.
185
+     *
186
+     * \param number_of_steps The number of steps to move the motor.
187
+     * \return 0 if the motor was not moving and moves now. -1 if the motor is moving and the new steps could not be set.
188
+     *
189
+     * If the previous movement is not finished yet the function will return -1 and not change the steps to move the motor.
190
+	 * If the motor does not move it return 0
191
+     *
192
+     * The direction of the movement is indicated by the sign of the steps parameter. It is not determinable if positive values are right 
193
+     * or left This depends on the internal construction of the motor and how you connected it to the stepper driver.
194
+     *
195
+     * You can always verify with isMoving() or even use stop() to stop the motor before giving it new step directions.
196
+     * \sa isMoving(), getStepsLeft(), stop()
197
+     */
198
+    char step(int number_of_steps);
199
+    
200
+    /*!
201
+     * \brief Central movement method, must be called as often as possible in the lopp function and is very fast.
202
+     *
203
+     * This routine checks if the motor still has to move, if the waiting delay has passed to send a new step command to the motor 
204
+     * and manages the number of steps yet to move to fulfill the current move command.
205
+     *
206
+     * This function is implemented to be as fast as possible to call it as often as possible in your loop routine.
207
+     * The more regurlarly you call this function the better. In both senses of 'regularly': Calling it as often as
208
+     * possible is not a bad idea and if you even manage that the intervals you call this function are not too irregular helps too.
209
+     *
210
+     * You can call this routine even if you know that the motor is not miving. It introduces just a very small penalty in your code.
211
+     * You must not call isMoving() to determine if you need to call this function, since taht is done internally already and only 
212
+     * slows down you code.
213
+     * 
214
+     * How often you call this function directly influences your top miving speed for the motor. It may be a good idea to call this
215
+     * from an timer overflow interrupt to ensure proper calling.
216
+     * \sa step()
217
+     */
218
+    char move(void);
219
+
220
+    /*!
221
+     * \brief checks if the motor still has to move to fulfill the last movement command.
222
+     * \return 0 if the motor stops, -1 if the motor is moving.
223
+     *
224
+     * This method can be used to determine if the motor is ready for new movements.
225
+     *\sa step(), move()
226
+     */
227
+    char isMoving(void);
228
+    
229
+    /*!
230
+     * \brief Get the number of steps left in the current movement.
231
+     * \return The number of steps left in the movement. This number is always positive.
232
+     */
233
+    unsigned int getStepsLeft(void);
234
+    
235
+    /*!
236
+     * \brief Stops the motor regardless if it moves or not.
237
+     * \return -1 if the motor was moving and is really stoped or 0 if it was not moving at all.
238
+     *
239
+     * This method directly and apruptely stops the motor and may be used as an emergency stop.
240
+     */
241
+    char stop(void);
242
+    
243
+    /*!
244
+     * \brief Sets and configure the classical Constant Off Timer Chopper
245
+     * \param constant_off_time The off time setting controls the minimum chopper frequency. For most applications an off time within the range of 5μs to 20μs will fit. Setting this parameter to zero completely disables all driver transistors and the motor can free-wheel. 0: chopper off, 1:15: off time setting (1 will work with minimum blank time of 24 clocks)
246
+     * \param blank_time Selects the comparator blank time. This time needs to safely cover the switching event and the duration of the ringing on the sense resistor. For most low current drivers, a setting of 1 or 2 is good. For high current applications with large MOSFETs, a setting of 2 or 3 will be required. 0 (min setting) … (3) amx setting
247
+     * \param fast_decay_time_setting Fast decay time setting. Controls the portion of fast decay for each chopper cycle. 0: slow decay only, 1…15: duration of fast decay phase
248
+     * \param sine_wave_offset Sine wave offset. Controls the sine wave offset. A positive offset corrects for zero crossing error. -3…-1: negative offset, 0: no offset,1…12: positive offset
249
+     * \param use_curreent_comparator Selects usage of the current comparator for termination of the fast decay cycle. If current comparator is enabled, it terminates the fast decay cycle in case the current reaches a higher negative value than the actual positive value. (0 disable, -1 enable).
250
+     *
251
+     * The classic constant off time chopper uses a fixed portion of fast decay following each on phase. 
252
+     * While the duration of the on time is determined by the chopper comparator, the fast decay time needs 
253
+     * to be set by the user in a way, that the current decay is enough for the driver to be able to follow 
254
+     * the falling slope of the sine wave, and on the other hand it should not be too long, in order to minimize 
255
+     * motor current ripple and power dissipation. This best can be tuned using an oscilloscope or 
256
+     * trying out motor smoothness at different velocities. A good starting value is a fast decay time setting 
257
+     * similar to the slow decay time setting.
258
+     * After tuning of the fast decay time, the offset should be determined, in order to have a smooth zero transition. 
259
+     * This is necessary, because the fast decay phase leads to the absolute value of the motor current being lower 
260
+     * than the target current (see figure 17). If the zero offset is too low, the motor stands still for a short 
261
+     * moment during current zero crossing, if it is set too high, it makes a larger microstep.
262
+     * Typically, a positive offset setting is required for optimum operation.
263
+     *
264
+     * \sa setSpreadCycleChoper() for other alternatives.
265
+     * \sa setRandomOffTime() for spreading the noise over a wider spectrum
266
+     */
267
+	void setConstantOffTimeChopper(char constant_off_time, char blank_time, char fast_decay_time_setting, char sine_wave_offset, unsigned char use_current_comparator);
268
+    
269
+    /*!
270
+     * \brief Sets and configures with spread cycle chopper.
271
+     * \param constant_off_time The off time setting controls the minimum chopper frequency. For most applications an off time within the range of 5μs to 20μs will fit. Setting this parameter to zero completely disables all driver transistors and the motor can free-wheel. 0: chopper off, 1:15: off time setting (1 will work with minimum blank time of 24 clocks)
272
+     * \param blank_time Selects the comparator blank time. This time needs to safely cover the switching event and the duration of the ringing on the sense resistor. For most low current drivers, a setting of 1 or 2 is good. For high current applications with large MOSFETs, a setting of 2 or 3 will be required. 0 (min setting) … (3) amx setting
273
+     * \param hysteresis_start Hysteresis start setting. Please remark, that this value is an offset to the hysteresis end value. 1 … 8
274
+     * \param hysteresis_end Hysteresis end setting. Sets the hysteresis end value after a number of decrements. Decrement interval time is controlled by hysteresis_decrement. The sum hysteresis_start + hysteresis_end must be <16. At a current setting CS of max. 30 (amplitude reduced to 240), the sum is not limited.
275
+     * \param hysteresis_decrement Hysteresis decrement setting. This setting determines the slope of the hysteresis during on time and during fast decay time. 0 (fast decrement) … 3 (slow decrement).
276
+     *
277
+     * The spreadCycle chopper scheme (pat.fil.) is a precise and simple to use chopper principle, which automatically determines 
278
+     * the optimum fast decay portion for the motor. Anyhow, a number of settings can be made in order to optimally fit the driver 
279
+     * to the motor.
280
+     * Each chopper cycle is comprised of an on-phase, a slow decay phase, a fast decay phase and a second slow decay phase.
281
+     * The slow decay phases limit the maximum chopper frequency and are important for low motor and driver power dissipation. 
282
+     * The hysteresis start setting limits the chopper frequency by forcing the driver to introduce a minimum amount of 
283
+     * current ripple into the motor coils. The motor inductivity determines the ability to follow a changing motor current. 
284
+     * The duration of the on- and fast decay phase needs to cover at least the blank time, because the current comparator is 
285
+     * disabled during this time.
286
+     * 
287
+     * \sa setRandomOffTime() for spreading the noise over a wider spectrum
288
+     */
289
+	void setSpreadCycleChopper(char constant_off_time, char blank_time, char hysteresis_start, char hysteresis_end, char hysteresis_decrement);
290
+
291
+	/*!
292
+     * \brief Use random off time for noise reduction (0 for off, -1 for on).
293
+     * \param value 0 for off, -1 for on
294
+     *
295
+     * In a constant off time chopper scheme both coil choppers run freely, i.e. are not synchronized. 
296
+     * The frequency of each chopper mainly depends on the coil current and the position dependant motor coil inductivity, 
297
+     * thus it depends on the microstep position. With some motors a slightly audible beat can occur between the chopper 
298
+     * frequencies, especially when they are near to each other. This typically occurs at a few microstep positions within 
299
+     * each quarter wave. 
300
+     * This effect normally is not audible when compared to mechanical noise generated by ball bearings, 
301
+     * etc. Further factors which can cause a similar effect are a poor layout of sense resistor GND connection.
302
+     * In order to minimize the effect of a beat between both chopper frequencies, an internal random generator is provided. 
303
+     * It modulates the slow decay time setting when switched on. The random off time feature further spreads the chopper spectrum,
304
+     * reducing electromagnetic emission on single frequencies.
305
+     */
306
+	void setRandomOffTime(char value);
307
+    
308
+	/*!
309
+     * \brief set the maximum motor current in mA (1000 is 1 Amp)
310
+     * Keep in mind this is the maximum peak Current. The RMS current will be 1/sqrt(2) smaller. The actual current can also be smaller
311
+     * by employing CoolStep.
312
+     * \param current the maximum motor current in mA
313
+     * \sa getCurrent(), getCurrentCurrent()
314
+     */
315
+	void setCurrent(unsigned int current);
316
+    
317
+    /*!
318
+     * \brief readout the motor maximum current in mA (1000 is an Amp)
319
+     * This is the maximum current. to get the current current - which may be affected by CoolStep us getCurrentCurrent()
320
+     *\return the maximum motor current in milli amps
321
+     * \sa getCurrentCurrent()
322
+     */
323
+    unsigned int getCurrent(void);
324
+    
325
+	/*!
326
+     * \brief set the StallGuard threshold in order to get sensible StallGuard readings.
327
+     * \param stall_guard_threshold -64 … 63 the StallGuard threshold
328
+     * \param stall_guard_filter_enabled 0 if the filter is disabled, -1 if it is enabled
329
+     *
330
+     * The StallGuard threshold is used to optimize the StallGuard reading to sensible values. It should be at 0 at
331
+     * the maximum allowable load on the otor (but not before). = is a good starting point (and the default)
332
+     * If you get Stall Gaurd readings of 0 without any load or with too little laod increase the value.
333
+     * If you get readings of 1023 even with load decrease the setting.
334
+     *
335
+     * If you switch on the filter the StallGuard reading is only updated each 4th full step to reduce the noise in the
336
+     * reading.
337
+     * 
338
+     * \sa getCurrentStallGuardReading() to read out the current value.
339
+     */ 
340
+	void setStallGuardThreshold(char stall_guard_threshold, char stall_guard_filter_enabled);
341
+    
342
+    /*!
343
+     * \brief reads out the StallGuard threshold
344
+     * \return a number between -64 and 63.
345
+     */
346
+    char getStallGuardThreshold(void);
347
+    
348
+    /*!
349
+     * \brief returns the current setting of the StallGuard filter
350
+     * \return 0 if not set, -1 if set
351
+     */
352
+    char getStallGuardFilter(void);
353
+    
354
+    /*!
355
+     * \brief This method configures the CoolStep smart energy operation. You must have a proper StallGuard configuration for the motor situation (current, voltage, speed) in rder to use this feature.
356
+     * \param lower_SG_threshold Sets the lower threshold for stallGuard2TM reading. Below this value, the motor current becomes increased. Allowed values are 0...480
357
+     * \param SG_hysteresis Sets the distance between the lower and the upper threshold for stallGuard2TM reading. Above the upper threshold (which is lower_SG_threshold+SG_hysteresis+1) the motor current becomes decreased. Allowed values are 0...480
358
+     * \param current_decrement_step_size Sets the current decrement steps. If the StallGuard value is above the threshold the current gets decremented by this step size. 0...32
359
+     * \param current_increment_step_size Sets the current increment step. The current becomes incremented for each measured stallGuard2TM value below the lower threshold. 0...8
360
+     * \param lower_current_limit Sets the lower motor current limit for coolStepTM operation by scaling the CS value. Values can be COOL_STEP_HALF_CS_LIMIT, COOL_STEP_QUARTER_CS_LIMIT
361
+     * The CoolStep smart energy operation automatically adjust the current sent into the motor according to the current load,
362
+     * read out by the StallGuard in order to provide the optimum torque with the minimal current consumption.
363
+     * You configure the CoolStep current regulator by defining upper and lower bounds of StallGuard readouts. If the readout is above the 
364
+     * limit the current gets increased, below the limit the current gets decreased.
365
+     * You can specify the upper an lower threshold of the StallGuard readout in order to adjust the current. You can also set the number of
366
+     * StallGuard readings neccessary above or below the limit to get a more stable current adjustement.
367
+     * The current adjustement itself is configured by the number of steps the current gests in- or decreased and the absolut minimum current
368
+     * (1/2 or 1/4th otf the configured current).
369
+     * \sa COOL_STEP_HALF_CS_LIMIT, COOL_STEP_QUARTER_CS_LIMIT
370
+     */
371
+    void setCoolStepConfiguration(unsigned int lower_SG_threshold, unsigned int SG_hysteresis, unsigned char current_decrement_step_size,
372
+                                  unsigned char current_increment_step_size, unsigned char lower_current_limit);
373
+    
374
+    /*!
375
+     * \brief enables or disables the CoolStep smart energy operation feature. It must be configured before enabling it.
376
+     * \param enabled true if CoolStep should be enabled, false if not.
377
+     * \sa setCoolStepConfiguration()
378
+     */
379
+    void setCoolStepEnabled(boolean enabled);
380
+    
381
+    
382
+    /*!
383
+     * \brief check if the CoolStep feature is enabled
384
+     * \sa setCoolStepEnabled()
385
+     */
386
+    boolean isCoolStepEnabled();
387
+
388
+    /*!
389
+     * \brief returns the lower StallGuard threshold for the CoolStep operation
390
+     * \sa setCoolStepConfiguration()
391
+     */
392
+    unsigned int getCoolStepLowerSgThreshold();
393
+    
394
+    /*!
395
+     * \brief returns the upper StallGuard threshold for the CoolStep operation
396
+     * \sa setCoolStepConfiguration()
397
+     */
398
+    unsigned int getCoolStepUpperSgThreshold();
399
+    
400
+    /*!
401
+     * \brief returns the number of StallGuard readings befor CoolStep adjusts the motor current.
402
+     * \sa setCoolStepConfiguration()
403
+     */
404
+    unsigned char getCoolStepNumberOfSGReadings();
405
+    
406
+    /*!
407
+     * \brief returns the increment steps for the current for the CoolStep operation
408
+     * \sa setCoolStepConfiguration()
409
+     */
410
+    unsigned char getCoolStepCurrentIncrementSize();
411
+    
412
+    /*!
413
+     * \brief returns the absolut minium current for the CoolStep operation
414
+     * \sa setCoolStepConfiguration()
415
+     * \sa COOL_STEP_HALF_CS_LIMIT, COOL_STEP_QUARTER_CS_LIMIT
416
+     */
417
+    unsigned char getCoolStepLowerCurrentLimit();
418
+    
419
+	/*!
420
+     * \brief Get the current microstep position for phase A
421
+     * \return The current microstep position for phase A 0…255
422
+     * 
423
+     * Keep in mind that this routine reads and writes a value via SPI - so this may take a bit time.
424
+     */
425
+	int getMotorPosition(void);
426
+    
427
+    /*!
428
+     * \brief Reads the current StallGuard value.
429
+     * \return The current StallGuard value, lesser values indicate higher load, 0 means stall detected.
430
+     * Keep in mind that this routine reads and writes a value via SPI - so this may take a bit time.
431
+     * \sa setStallGuardThreshold() for tuning the readout to sensible ranges.
432
+     */
433
+	int getCurrentStallGuardReading(void);
434
+    
435
+    /*!
436
+     * \brief Reads the current current setting value as fraction of the maximum current
437
+     * Returns values between 0 and 31, representing 1/32 to 32/32 (=1)
438
+     * \sa setCoolStepConfiguration()
439
+     */
440
+    unsigned char getCurrentCSReading(void);
441
+    
442
+    
443
+    /*!
444
+     *\brief a convenience method to determine if the current scaling uses 0.31V or 0.165V as reference.
445
+     *\return false if 0.13V is the reference voltage, true if 0.165V is used.
446
+     */
447
+    boolean isCurrentScalingHalfed();
448
+
449
+    /*!
450
+     * \brief Reads the current current setting value and recalculates the absolute current in mA (1A would be 1000).
451
+     * This method calculates the currently used current setting (either by setting or by CoolStep) and reconstructs
452
+     * the current in mA by usinge the VSENSE and resistor value. This method uses floating point math - so it 
453
+     * may not be the fastest.
454
+     * \sa getCurrentCSReading(), getResistor(), isCurrentScalingHalfed(), getCurrent()
455
+     */
456
+    unsigned int getCurrentCurrent(void);
457
+    
458
+    /*!
459
+     * \brief checks if there is a StallGuard warning in the last status
460
+     * \return 0 if there was no warning, -1 if there was some warning.
461
+     * Keep in mind that this method does not enforce a readout but uses the value of the last status readout.
462
+     * You may want to use getMotorPosition() or getCurrentStallGuardReading() to enforce an updated status readout.
463
+     *
464
+     * \sa setStallGuardThreshold() for tuning the readout to sensible ranges.
465
+     */
466
+	boolean isStallGuardOverThreshold(void);
467
+    
468
+    /*!
469
+     * \brief Return over temperature status of the last status readout
470
+     * return 0 is everything is OK, TMC26X_OVERTEMPERATURE_PREWARING if status is reached, TMC26X_OVERTEMPERATURE_SHUTDOWN is the chip is shutdown, -1 if the status is unknown.
471
+     * Keep in mind that this method does not enforce a readout but uses the value of the last status readout.
472
+     * You may want to use getMotorPosition() or getCurrentStallGuardReading() to enforce an updated status readout.
473
+     */
474
+	char getOverTemperature(void);
475
+    
476
+    /*!
477
+     * \brief Is motor channel A shorted to ground detected in the last status readout.
478
+     * \return true is yes, false if not.
479
+     * Keep in mind that this method does not enforce a readout but uses the value of the last status readout.
480
+     * You may want to use getMotorPosition() or getCurrentStallGuardReading() to enforce an updated status readout.
481
+     */
482
+     
483
+	boolean isShortToGroundA(void);
484
+
485
+    /*!
486
+     * \brief Is motor channel B shorted to ground detected in the last status readout.
487
+     * \return true is yes, false if not.
488
+     * Keep in mind that this method does not enforce a readout but uses the value of the last status readout.
489
+     * You may want to use getMotorPosition() or getCurrentStallGuardReading() to enforce an updated status readout.
490
+     */
491
+	boolean isShortToGroundB(void);
492
+	/*!
493
+     * \brief iIs motor channel A connected according to the last statu readout.
494
+     * \return true is yes, false if not.
495
+     * Keep in mind that this method does not enforce a readout but uses the value of the last status readout.
496
+     * You may want to use getMotorPosition() or getCurrentStallGuardReading() to enforce an updated status readout.
497
+     */
498
+	boolean isOpenLoadA(void);
499
+
500
+	/*!
501
+     * \brief iIs motor channel A connected according to the last statu readout.
502
+     * \return true is yes, false if not.
503
+     * Keep in mind that this method does not enforce a readout but uses the value of the last status readout.
504
+     * You may want to use getMotorPosition() or getCurrentStallGuardReading() to enforce an updated status readout.
505
+     */
506
+	boolean isOpenLoadB(void);
507
+    
508
+    /*!
509
+     * \brief Is chopper inactive since 2^20 clock cycles - defaults to ~0,08s
510
+     * \return true is yes, false if not.
511
+     * Keep in mind that this method does not enforce a readout but uses the value of the last status readout.
512
+     * You may want to use getMotorPosition() or getCurrentStallGuardReading() to enforce an updated status readout.
513
+     */
514
+	boolean isStandStill(void);
515
+
516
+    /*!
517
+     * \brief checks if there is a StallGuard warning in the last status
518
+     * \return 0 if there was no warning, -1 if there was some warning.
519
+     * Keep in mind that this method does not enforce a readout but uses the value of the last status readout.
520
+     * You may want to use getMotorPosition() or getCurrentStallGuardReading() to enforce an updated status readout.
521
+     *
522
+     * \sa isStallGuardOverThreshold()
523
+     * TODO why?
524
+     *
525
+     * \sa setStallGuardThreshold() for tuning the readout to sensible ranges.
526
+     */
527
+	boolean isStallGuardReached(void);
528
+    
529
+    /*!
530
+     *\brief enables or disables the motor driver bridges. If disabled the motor can run freely. If enabled not.
531
+     *\param enabled a boolean value true if the motor should be enabled, false otherwise.
532
+     */
533
+    void setEnabled(boolean enabled);
534
+    
535
+    /*!
536
+     *\brief checks if the output bridges are enabled. If the bridges are not enabled the motor can run freely
537
+     *\return true if the bridges and by that the motor driver are enabled, false if not.
538
+     *\sa setEnabled()
539
+     */
540
+    boolean isEnabled();
541
+
542
+	/*!
543
+     * \brief Manually read out the status register
544
+     * This function sends a byte to the motor driver in order to get the current readout. The parameter read_value
545
+     * seletcs which value will get returned. If the read_vlaue changes in respect to the previous readout this method
546
+     * automatically send two bytes to the motor: one to set the redout and one to get the actual readout. So this method 
547
+     * may take time to send and read one or two bits - depending on the previous readout.
548
+     * \param read_value selects which value to read out (0..3). You can use the defines TMC26X_READOUT_POSITION, TMC_262_READOUT_STALLGUARD, or TMC_262_READOUT_CURRENT
549
+     * \sa TMC26X_READOUT_POSITION, TMC_262_READOUT_STALLGUARD, TMC_262_READOUT_CURRENT
550
+     */
551
+	void readStatus(char read_value);
552
+    
553
+    /*!
554
+     * \brief Returns the current sense resistor value in milliohm.
555
+     * The default value of ,15 Ohm will return 150.
556
+     */
557
+    int getResistor();
558
+
559
+    /*!
560
+     * \brief Prints out all the information that can be found in the last status read out - it does not force a status readout. 
561
+     * The result is printed via Serial
562
+     */
563
+	void debugLastStatus(void);
564
+	/*!
565
+     * \brief library version
566
+     * \return the version number as int.
567
+     */
568
+    int version(void);
569
+
570
+  private:    
571
+  	unsigned int steps_left;		//the steps the motor has to do to complete the movement
572
+    int direction;        // Direction of rotation
573
+    unsigned long step_delay;    // delay between steps, in ms, based on speed
574
+    int number_of_steps;      // total number of steps this motor can take
575
+    unsigned int speed; // we need to store the current speed in order to change the speed after changing microstepping
576
+    unsigned int resistor; //current sense resitor value in milliohm
577
+        
578
+    unsigned long last_step_time;      // time stamp in ms of when the last step was taken
579
+    unsigned long next_step_time;      // time stamp in ms of when the last step was taken
580
+	
581
+	//driver control register copies to easily set & modify the registers
582
+	unsigned long driver_control_register_value;
583
+	unsigned long chopper_config_register;
584
+	unsigned long cool_step_register_value;
585
+	unsigned long stall_guard2_current_register_value;
586
+	unsigned long driver_configuration_register_value;
587
+	//the driver status result
588
+	unsigned long driver_status_result;
589
+	
590
+	//helper routione to get the top 10 bit of the readout
591
+	inline int getReadoutValue();
592
+	
593
+	//the pins for the stepper driver
594
+	unsigned char cs_pin;
595
+	unsigned char step_pin;
596
+	unsigned char dir_pin;
597
+	
598
+	//status values 
599
+	boolean started; //if the stepper has been started yet
600
+	int microsteps; //the current number of micro steps
601
+    char constant_off_time; //we need to remember this value in order to enable and disable the motor
602
+    unsigned char cool_step_lower_threshold; // we need to remember the threshold to enable and disable the CoolStep feature
603
+    boolean cool_step_enabled; //we need to remember this to configure the coolstep if it si enabled
604
+	
605
+	//SPI sender
606
+	inline void send262(unsigned long datagram);
607
+};
608
+
609
+#endif
610
+

+ 68
- 0
Marlin/src/HAL/HAL_STM32F7/endstop_interrupts.h 查看文件

@@ -0,0 +1,68 @@
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
+ * Copyright (C) 2017 Victor Perez
8
+ *
9
+ * This program is free software: you can redistribute it and/or modify
10
+ * it under the terms of the GNU General Public License as published by
11
+ * the Free Software Foundation, either version 3 of the License, or
12
+ * (at your option) any later version.
13
+ *
14
+ * This program is distributed in the hope that it will be useful,
15
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
16
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
17
+ * GNU General Public License for more details.
18
+ *
19
+ * You should have received a copy of the GNU General Public License
20
+ * along with this program.  If not, see <http://www.gnu.org/licenses/>.
21
+ *
22
+ */
23
+
24
+
25
+
26
+#ifndef _ENDSTOP_INTERRUPTS_H_
27
+#define _ENDSTOP_INTERRUPTS_H_
28
+
29
+void setup_endstop_interrupts(void) {
30
+  #if HAS_X_MAX
31
+    pinMode(X_MAX_PIN, INPUT);
32
+    attachInterrupt(X_MAX_PIN, endstop_ISR, CHANGE); // assign it
33
+  #endif
34
+  #if HAS_X_MIN
35
+    pinMode(X_MIN_PIN, INPUT);
36
+    attachInterrupt(X_MIN_PIN, endstop_ISR, CHANGE);
37
+  #endif
38
+  #if HAS_Y_MAX
39
+    pinMode(Y_MAX_PIN, INPUT);
40
+    attachInterrupt(Y_MAX_PIN, endstop_ISR, CHANGE);
41
+  #endif
42
+  #if HAS_Y_MIN
43
+    pinMode(Y_MIN_PIN, INPUT);
44
+    attachInterrupt(Y_MIN_PIN, endstop_ISR, CHANGE);
45
+  #endif
46
+  #if HAS_Z_MAX
47
+    pinMode(Z_MAX_PIN, INPUT);
48
+    attachInterrupt(Z_MAX_PIN, endstop_ISR, CHANGE);
49
+  #endif
50
+  #if HAS_Z_MIN
51
+    pinMode(Z_MIN_PIN, INPUT);
52
+    attachInterrupt(Z_MIN_PIN, endstop_ISR, CHANGE);
53
+  #endif
54
+  #if HAS_Z2_MAX
55
+    pinMode(Z2_MAX_PIN, INPUT);
56
+    attachInterrupt(Z2_MAX_PIN, endstop_ISR, CHANGE);
57
+  #endif
58
+  #if HAS_Z2_MIN
59
+    pinMode(Z2_MIN_PIN, INPUT);
60
+    attachInterrupt(Z2_MIN_PIN, endstop_ISR, CHANGE);
61
+  #endif
62
+  #if HAS_Z_MIN_PROBE_PIN
63
+    pinMode(Z_MIN_PROBE_PIN, INPUT);
64
+    attachInterrupt(Z_MIN_PROBE_PIN, endstop_ISR, CHANGE);
65
+  #endif
66
+}
67
+
68
+#endif //_ENDSTOP_INTERRUPTS_H_

+ 54
- 0
Marlin/src/HAL/HAL_STM32F7/fastio_STM32F7.h 查看文件

@@ -0,0 +1,54 @@
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
+ * Copyright (C) 2017 Victor Perez
8
+ *
9
+ * This program is free software: you can redistribute it and/or modify
10
+ * it under the terms of the GNU General Public License as published by
11
+ * the Free Software Foundation, either version 3 of the License, or
12
+ * (at your option) any later version.
13
+ *
14
+ * This program is distributed in the hope that it will be useful,
15
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
16
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
17
+ * GNU General Public License for more details.
18
+ *
19
+ * You should have received a copy of the GNU General Public License
20
+ * along with this program.  If not, see <http://www.gnu.org/licenses/>.
21
+ *
22
+ */
23
+
24
+/**
25
+ * Fast I/O interfaces for STM32F7
26
+ * These use GPIO functions instead of Direct Port Manipulation, as on AVR.
27
+ */
28
+
29
+#ifndef	_FASTIO_STM32F7_H
30
+#define	_FASTIO_STM32F7_H
31
+
32
+#define _BV(bit) 	(1 << (bit))
33
+
34
+#define READ(IO)              digitalRead(IO)
35
+#define WRITE(IO, v)          digitalWrite(IO,v)
36
+#define TOGGLE(IO)            do{ _SET_OUTPUT(IO); digitalWrite(IO,!digitalRead(IO)); }while(0)
37
+#define WRITE_VAR(IO, v)      digitalWrite(IO,v)
38
+
39
+#define _GET_MODE(IO)
40
+#define _SET_MODE(IO,M)       pinMode(IO, M)
41
+#define _SET_OUTPUT(IO)       pinMode(IO, OUTPUT)								/*!< Output Push Pull Mode & GPIO_NOPULL   */
42
+
43
+#define SET_INPUT(IO)         _SET_MODE(IO, INPUT)								/*!< Input Floating Mode                   */
44
+#define SET_INPUT_PULLUP(IO)  _SET_MODE(IO, INPUT_PULLUP)						/*!< Input with Pull-up activation         */
45
+#define SET_INPUT_PULLDOW(IO) _SET_MODE(IO, INPUT_PULLDOWN)						/*!< Input with Pull-down activation       */
46
+#define SET_OUTPUT(IO)        do{ _SET_OUTPUT(IO); WRITE(IO, LOW); }while(0)	
47
+
48
+#define GET_INPUT(IO)         
49
+#define GET_OUTPUT(IO)        
50
+#define GET_TIMER(IO)         
51
+
52
+#define OUT_WRITE(IO, v) { _SET_OUTPUT(IO); WRITE(IO, v); }
53
+
54
+#endif	/* _FASTIO_STM32F7_H */

+ 82
- 0
Marlin/src/HAL/HAL_STM32F7/persistent_store_impl.cpp 查看文件

@@ -0,0 +1,82 @@
1
+/**
2
+ * Marlin 3D Printer Firmware
3
+ *
4
+ * Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
5
+ * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
6
+ * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com
7
+ * Copyright (c) 2016 Victor Perez victor_pv@hotmail.com
8
+ *
9
+ * This program is free software: you can redistribute it and/or modify
10
+ * it under the terms of the GNU General Public License as published by
11
+ * the Free Software Foundation, either version 3 of the License, or
12
+ * (at your option) any later version.
13
+ *
14
+ * This program is distributed in the hope that it will be useful,
15
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
16
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
17
+ * GNU General Public License for more details.
18
+ *
19
+ * You should have received a copy of the GNU General Public License
20
+ * along with this program.  If not, see <http://www.gnu.org/licenses/>.
21
+ *
22
+ */
23
+
24
+
25
+#ifdef STM32F7
26
+
27
+#include "../persistent_store_api.h"
28
+
29
+#include "../../inc/MarlinConfig.h"
30
+
31
+#if ENABLED(EEPROM_SETTINGS)
32
+
33
+namespace HAL {
34
+namespace PersistentStore {
35
+
36
+bool access_start() {
37
+  return true;
38
+}
39
+
40
+bool access_finish(){
41
+  return true;
42
+}
43
+
44
+bool write_data(int &pos, const uint8_t *value, uint16_t size, uint16_t *crc) {
45
+  while (size--) {
46
+    uint8_t * const p = (uint8_t * const)pos;
47
+    uint8_t v = *value;
48
+    // EEPROM has only ~100,000 write cycles,
49
+    // so only write bytes that have changed!
50
+    if (v != eeprom_read_byte(p)) {
51
+      eeprom_write_byte(p, v);
52
+      if (eeprom_read_byte(p) != v) {
53
+        SERIAL_ECHO_START();
54
+        SERIAL_ECHOLNPGM(MSG_ERR_EEPROM_WRITE);
55
+        return true;
56
+      }
57
+    }
58
+    crc16(crc, &v, 1);
59
+    pos++;
60
+    value++;
61
+  };
62
+  return false;
63
+}
64
+
65
+bool read_data(int &pos, uint8_t* value, uint16_t size, uint16_t *crc) {
66
+  do {
67
+    uint8_t c = eeprom_read_byte((unsigned char*)pos);
68
+    *value = c;
69
+    crc16(crc, &c, 1);
70
+    pos++;
71
+    value++;
72
+  } while (--size);
73
+  return false;
74
+}
75
+
76
+}
77
+}
78
+
79
+#endif // EEPROM_SETTINGS
80
+#endif // STM32F7
81
+
82
+

+ 33
- 0
Marlin/src/HAL/HAL_STM32F7/spi_pins.h 查看文件

@@ -0,0 +1,33 @@
1
+/**
2
+* Marlin 3D Printer Firmware
3
+* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
+*
5
+* This program is free software: you can redistribute it and/or modify
6
+* it under the terms of the GNU General Public License as published by
7
+* the Free Software Foundation, either version 3 of the License, or
8
+* (at your option) any later version.
9
+*
10
+* This program 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
13
+* GNU General Public License for more details.
14
+*
15
+* You should have received a copy of the GNU General Public License
16
+* along with this program.  If not, see <http://www.gnu.org/licenses/>.
17
+*
18
+*/
19
+
20
+#ifndef SPI_PINS_H_
21
+#define SPI_PINS_H_
22
+
23
+
24
+/**
25
+ * Define SPI Pins: SCK, MISO, MOSI, SS
26
+ *
27
+ */
28
+#define SCK_PIN   _STM32_PIN(PORTA, 5)
29
+#define MISO_PIN  _STM32_PIN(PORTA, 6)
30
+#define MOSI_PIN  _STM32_PIN(PORTA, 7)
31
+#define SS_PIN    _STM32_PIN(PORTA, 8)
32
+
33
+#endif // SPI_PINS_H_

+ 55
- 0
Marlin/src/HAL/HAL_STM32F7/watchdog_STM32F7.cpp 查看文件

@@ -0,0 +1,55 @@
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
+#ifdef STM32F7
24
+
25
+#include "../../inc/MarlinConfig.h"
26
+
27
+#if ENABLED(USE_WATCHDOG)
28
+
29
+    #include "watchdog_STM32F7.h"
30
+
31
+	IWDG_HandleTypeDef hiwdg;
32
+
33
+    void watchdog_init() {
34
+		hiwdg.Instance = IWDG;
35
+		hiwdg.Init.Prescaler = IWDG_PRESCALER_32;	//32kHz LSI clock and 32x prescalar = 1024Hz IWDG clock
36
+		hiwdg.Init.Reload = 4095; 					//4095 counts = 4 seconds at 1024Hz
37
+		if (HAL_IWDG_Init(&hiwdg) != HAL_OK)
38
+		{
39
+			//Error_Handler();
40
+		}
41
+    }
42
+
43
+    void watchdog_reset() {
44
+		/* Refresh IWDG: reload counter */
45
+		if (HAL_IWDG_Refresh(&hiwdg) != HAL_OK)
46
+		{
47
+			/* Refresh Error */
48
+			//Error_Handler();
49
+		}
50
+    }
51
+
52
+
53
+#endif // USE_WATCHDOG
54
+
55
+#endif // STM32F7

+ 33
- 0
Marlin/src/HAL/HAL_STM32F7/watchdog_STM32F7.h 查看文件

@@ -0,0 +1,33 @@
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
+#ifndef WATCHDOG_STM32F7_H
24
+#define WATCHDOG_STM32F7_H
25
+
26
+#include "../../../src/inc/MarlinConfig.h"
27
+
28
+extern IWDG_HandleTypeDef hiwdg;
29
+
30
+void watchdog_init();
31
+void watchdog_reset();
32
+
33
+#endif // WATCHDOG_STM32F1_H

+ 13
- 5
Marlin/src/HAL/HAL_SanityCheck.h 查看文件

@@ -24,15 +24,23 @@
24 24
 
25 25
 #ifdef __AVR__
26 26
   #include "HAL_AVR/SanityCheck_AVR_8_bit.h"
27
-#elif defined(ARDUINO_ARCH_SAM)
27
+
28
+  #elif defined(ARDUINO_ARCH_SAM)
28 29
   #include "HAL_DUE/SanityCheck_Due.h"
29
-#elif IS_32BIT_TEENSY
30
+
31
+  #elif IS_32BIT_TEENSY
30 32
   #include "HAL_TEENSY35_36/SanityCheck_Teensy_35_36.h"
31
-#elif defined(TARGET_LPC1768)
33
+
34
+  #elif defined(TARGET_LPC1768)
32 35
   #include "HAL_LPC1768/SanityCheck_Re_ARM.h"
33
-#elif defined(__STM32F1__)
36
+
37
+  #elif defined(__STM32F1__)
34 38
     #include "HAL_STM32F1/SanityCheck_Stm32f1.h"
35
-#else
39
+
40
+	#elif defined(STM32F7)
41
+    #include "HAL_STM32F7/SanityCheck_STM32F7.h"
42
+
43
+	#else
36 44
   #error Unsupported Platform!
37 45
 #endif
38 46
 

+ 4
- 0
Marlin/src/HAL/HAL_endstop_interrupts.h 查看文件

@@ -45,6 +45,10 @@ void endstop_ISR(void) { endstop_ISR_worker(); }
45 45
 #elif IS_32BIT_TEENSY
46 46
 
47 47
   #include "HAL_TEENSY35_36/endstop_interrupts.h"
48
+  
49
+#elif defined(STM32F7)
50
+
51
+  #include "HAL_STM32F7/endstop_interrupts.h"
48 52
 
49 53
 #else
50 54
 

+ 7
- 2
Marlin/src/HAL/HAL_spi_pins.h 查看文件

@@ -34,9 +34,14 @@
34 34
 
35 35
 #elif defined(TARGET_LPC1768)
36 36
   #include "HAL_LPC1768/spi_pins.h"
37
+
37 38
 #elif defined(__STM32F1__)
38
-    #include "HAL_STM32F1/spi_pins.h"
39
-#else
39
+  #include "HAL_STM32F1/spi_pins.h"
40
+
41
+#elif defined(STM32F7)
42
+  #include "HAL_STM32F7/spi_pins.h"
43
+
44
+	#else
40 45
   #error "Unsupported Platform!"
41 46
 #endif
42 47
 

+ 1793
- 0
Marlin/src/config/examples/TheBorg/Configuration.h
文件差異過大導致無法顯示
查看文件


+ 1594
- 0
Marlin/src/config/examples/TheBorg/Configuration_adv.h
文件差異過大導致無法顯示
查看文件


+ 6
- 0
Marlin/src/core/boards.h 查看文件

@@ -199,6 +199,12 @@
199 199
 #define BOARD_BEAST            1802  // STM32FxxxVxT6 Libmaple based stm32f4 controller
200 200
 #define BOARD_STM3R_MINI       1803  // STM32 Libmaple based stm32f1 controller
201 201
 
202
+//
203
+// ARM Cortex M7
204
+//
205
+#define BOARD_THE_BORG         1860   // THE-BORG (Power outputs: Hotend0, Hotend1, Bed, Fan)
206
+
207
+
202 208
 #define MB(board) (MOTHERBOARD==BOARD_##board)
203 209
 
204 210
 #endif // __BOARDS_H

+ 6
- 1
Marlin/src/module/stepper_indirection.cpp 查看文件

@@ -41,7 +41,12 @@
41 41
 #if ENABLED(HAVE_TMCDRIVER)
42 42
 
43 43
   #include <SPI.h>
44
-  #include <TMC26XStepper.h>
44
+  
45
+  #if defined(STM32F7)
46
+    #include "../HAL/HAL_STM32F7/TMC2660.h"
47
+  #else
48
+    #include <TMC26XStepper.h>
49
+  #endif
45 50
 
46 51
   #define _TMC_DEFINE(ST) TMC26XStepper stepper##ST(200, ST##_ENABLE_PIN, ST##_STEP_PIN, ST##_DIR_PIN, ST##_MAX_CURRENT, ST##_SENSE_RESISTOR)
47 52
 

+ 5
- 1
Marlin/src/module/stepper_indirection.h 查看文件

@@ -49,7 +49,11 @@
49 49
 // TMC26X drivers have STEP/DIR on normal pins, but ENABLE via SPI
50 50
 #if ENABLED(HAVE_TMCDRIVER)
51 51
   #include <SPI.h>
52
-  #include <TMC26XStepper.h>
52
+  #if defined(STM32F7)
53
+    #include "../HAL/HAL_STM32F7/TMC2660.h"
54
+  #else
55
+    #include <TMC26XStepper.h>
56
+  #endif
53 57
   void tmc_init();
54 58
 #endif
55 59
 

+ 2
- 0
Marlin/src/pins/pins.h 查看文件

@@ -337,6 +337,8 @@
337 337
   #include "pins_AZTEEG_X5_GT.h"
338 338
 #elif MB(BIQU_BQ111_A4)
339 339
   #include "pins_BIQU_BQ111_A4.h"
340
+#elif MB(THE_BORG)
341
+  #include "pins_THE_BORG.h"
340 342
 #else
341 343
   #error "Unknown MOTHERBOARD value set in Configuration.h"
342 344
 #endif

+ 208
- 0
Marlin/src/pins/pins_THE_BORG.h 查看文件

@@ -0,0 +1,208 @@
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
+#if !defined(STM32F7)
24
+    #error "Oops!  Make sure you have an STM32F7 board selected from the 'Tools -> Boards' menu."
25
+#endif
26
+
27
+#define DEFAULT_MACHINE_NAME "The-Borge"
28
+#define BOARD_NAME "The-Borge"
29
+
30
+#define LARGE_FLASH true
31
+
32
+#define E2END 0xFFF // EEPROM end address
33
+
34
+// Ignore temp readings during develpment.
35
+#define BOGUS_TEMPERATURE_FAILSAFE_OVERRIDE
36
+
37
+#if E_STEPPERS > 3 || HOTENDS > 3
38
+  #error "The-Borg supports up to 3 hotends / E-steppers."
39
+#endif
40
+
41
+#define PORTA 0
42
+#define PORTB 1
43
+#define PORTC 2
44
+#define PORTD 3
45
+#define PORTE 4
46
+#define PORTF 5
47
+#define PORTG 6
48
+
49
+#define _STM32_PIN(_PORT,_PIN) ((_PORT * 16) + _PIN)
50
+
51
+
52
+//
53
+// Limit Switches
54
+//
55
+#define X_MIN_PIN          _STM32_PIN(PORTE, 9)
56
+#define X_MAX_PIN          _STM32_PIN(PORTE, 10)
57
+#define Y_MIN_PIN          _STM32_PIN(PORTE, 7)
58
+#define Y_MAX_PIN          _STM32_PIN(PORTE, 8)
59
+#define Z_MIN_PIN          _STM32_PIN(PORTF, 15) 
60
+#define Z_MAX_PIN          _STM32_PIN(PORTG, 0)
61
+#define E_MIN_PIN          _STM32_PIN(PORTE, 2)  
62
+#define E_MAX_PIN          _STM32_PIN(PORTE, 3)
63
+//
64
+// Z Probe (when not Z_MIN_PIN)
65
+//
66
+#ifndef Z_MIN_PROBE_PIN
67
+  #define Z_MIN_PROBE_PIN  _STM32_PIN(PORTA, 4)
68
+#endif
69
+
70
+//
71
+// Steppers
72
+//
73
+
74
+#define STEPPER_ENABLE_PIN _STM32_PIN(PORTE, 0)
75
+
76
+#define X_STEP_PIN         _STM32_PIN(PORTC, 6)	//96, 39 in arduino
77
+#define X_DIR_PIN          _STM32_PIN(PORTC, 7)
78
+#define X_ENABLE_PIN       _STM32_PIN(PORTC, 8)
79
+
80
+
81
+#define Y_STEP_PIN         _STM32_PIN(PORTD, 9)
82
+#define Y_DIR_PIN          _STM32_PIN(PORTD, 10)
83
+#define Y_ENABLE_PIN       _STM32_PIN(PORTD, 11)
84
+
85
+#define Z_STEP_PIN         _STM32_PIN(PORTE, 15)
86
+#define Z_DIR_PIN          _STM32_PIN(PORTG, 1)
87
+#define Z_ENABLE_PIN       _STM32_PIN(PORTD, 8)
88
+
89
+
90
+#define E0_STEP_PIN        _STM32_PIN(PORTB, 1)
91
+#define E0_DIR_PIN         _STM32_PIN(PORTB, 2)
92
+#define E0_ENABLE_PIN      _STM32_PIN(PORTE, 11)
93
+
94
+
95
+#define E1_STEP_PIN        _STM32_PIN(PORTC, 4)
96
+#define E1_DIR_PIN         _STM32_PIN(PORTC, 5)
97
+#define E1_ENABLE_PIN      _STM32_PIN(PORTB, 0)
98
+
99
+
100
+#define E2_STEP_PIN        _STM32_PIN(PORTC, 13)
101
+#define E2_DIR_PIN         _STM32_PIN(PORTC, 14)
102
+#define E2_ENABLE_PIN      _STM32_PIN(PORTC, 15)
103
+
104
+#define Z2_STEP_PIN        _STM32_PIN(PORTC, 13)
105
+#define Z2_DIR_PIN         _STM32_PIN(PORTC, 14)
106
+#define Z2_ENABLE_PIN      _STM32_PIN(PORTC, 15)
107
+
108
+
109
+
110
+
111
+
112
+
113
+
114
+#define SCK_PIN				_STM32_PIN(PORTA, 5)
115
+#define MISO_PIN			_STM32_PIN(PORTA, 6)
116
+#define MOSI_PIN			_STM32_PIN(PORTA, 7)
117
+
118
+#define SPI1_SCK_PIN		_STM32_PIN(PORTA, 5)
119
+#define SPI1_MISO_PIN      	_STM32_PIN(PORTA, 6)
120
+#define SPI1_MOSI_PIN      	_STM32_PIN(PORTA, 7)
121
+
122
+#define SPI6_SCK_PIN       	_STM32_PIN(PORTG, 13)
123
+#define SPI6_MISO_PIN      	_STM32_PIN(PORTG, 12)
124
+#define SPI6_MOSI_PIN      	_STM32_PIN(PORTG, 14)
125
+
126
+
127
+
128
+
129
+//
130
+// Temperature Sensors
131
+//
132
+
133
+#define TEMP_0_PIN       	_STM32_PIN(PORTC, 3)   // Analog Input
134
+#define TEMP_1_PIN       	_STM32_PIN(PORTC, 2)   // Analog Input
135
+#define TEMP_2_PIN       	_STM32_PIN(PORTC, 1)   // Analog Input
136
+#define TEMP_3_PIN       	_STM32_PIN(PORTC, 0)   // Analog Input
137
+
138
+#define TEMP_BED_PIN     	_STM32_PIN(PORTF, 10)  // Analog Input
139
+
140
+#define TEMP_5_PIN       	_STM32_PIN(PORTE, 12)  // Analog Input, Probe temp
141
+
142
+
143
+//
144
+// Heaters / Fans
145
+//
146
+#define HEATER_0_PIN        _STM32_PIN(PORTD, 15)
147
+#define HEATER_1_PIN        _STM32_PIN(PORTD, 14)
148
+#define HEATER_BED_PIN      _STM32_PIN(PORTF,  6)
149
+
150
+#define FAN_PIN             _STM32_PIN(PORTD, 13)
151
+#define FAN1_PIN            _STM32_PIN(PORTA, 0)
152
+#define FAN2_PIN            _STM32_PIN(PORTA, 1)
153
+
154
+//#define E0_AUTO_FAN_PIN 	_STM32_PIN(PORTA, 1)
155
+
156
+//
157
+// Misc. Functions
158
+//
159
+
160
+//#define CASE_LIGHT_PIN_CI   _STM32_PIN(PORTF, 13)  //
161
+//#define CASE_LIGHT_PIN_DO   _STM32_PIN(PORTF, 14)  //
162
+//#define NEOPIXEL_PIN		_STM32_PIN(PORTF, 13)
163
+
164
+//
165
+// Prusa i3 MK2 Multi Material Multiplexer Support
166
+//
167
+
168
+#define E_MUX0_PIN         _STM32_PIN(PORTG, 3)  
169
+#define E_MUX1_PIN         _STM32_PIN(PORTG, 4)
170
+
171
+//
172
+// Servos
173
+//
174
+
175
+#define SERVO0_PIN 		   _STM32_PIN(PORTE, 13)  
176
+#define SERVO1_PIN 		   _STM32_PIN(PORTE, 14)  
177
+
178
+
179
+#define SDSS               _STM32_PIN(PORTA, 8)
180
+#define SS_PIN			   _STM32_PIN(PORTA, 8)
181
+#define LED_PIN            _STM32_PIN(PORTA, 2)			//Alive
182
+#define PS_ON_PIN          _STM32_PIN(PORTA, 3)
183
+#define KILL_PIN           -1//_STM32_PIN(PORTD, 5)		//EXP2-10
184
+#define PWR_LOSS		   _STM32_PIN(PORTG, 5)			//Power loss / nAC_FAULT
185
+
186
+//
187
+//MAX7219_DEBUG
188
+//
189
+#define MAX7219_CLK_PIN   _STM32_PIN(PORTG, 10)		//EXP1-1
190
+#define MAX7219_DIN_PIN   _STM32_PIN(PORTD, 7)		//EXP1-3
191
+#define MAX7219_LOAD_PIN   _STM32_PIN(PORTD, 1)		//EXP1-5
192
+
193
+//#define NEOPIXEL_PIN    4
194
+  
195
+//
196
+// LCD / Controller
197
+//
198
+//#define SD_DETECT_PIN      -1 //_STM32_PIN(PORTB, 6))		//EXP2-4
199
+#define BEEPER_PIN         _STM32_PIN(PORTG, 10)		//EXP1-1
200
+#define LCD_PINS_RS        _STM32_PIN(PORTG, 9)			//EXP1-4
201
+#define LCD_PINS_ENABLE    _STM32_PIN(PORTD, 7)			//EXP1-3
202
+#define LCD_PINS_D4        _STM32_PIN(PORTD, 1)			//EXP1-5
203
+#define LCD_PINS_D5        _STM32_PIN(PORTF, 0)			//EXP1-6
204
+#define LCD_PINS_D6        _STM32_PIN(PORTD, 3)			//EXP1-7
205
+#define LCD_PINS_D7        _STM32_PIN(PORTD, 4)			//EXP1-8
206
+#define BTN_EN1            _STM32_PIN(PORTD, 6)			//EXP2-5
207
+#define BTN_EN2            _STM32_PIN(PORTD, 0)			//EXP2-3
208
+#define BTN_ENC            _STM32_PIN(PORTG, 11)		//EXP1-2

Loading…
取消
儲存