From 42933c804a08740b47a341623783be52182f477b Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 15 Jan 2018 02:28:39 -0600 Subject: [PATCH] Cleanups for STM32F7 --- Marlin/src/HAL/HAL_STM32F1/HAL_Stm32f1.h | 2 +- Marlin/src/HAL/HAL_STM32F1/fastio_Stm32f1.h | 8 +- .../HAL_STM32F7/EEPROM_Emul/eeprom_emul.cpp | 465 ++---- Marlin/src/HAL/HAL_STM32F7/EmulatedEeprom.cpp | 2 +- Marlin/src/HAL/HAL_STM32F7/HAL_STM32F7.cpp | 19 +- Marlin/src/HAL/HAL_STM32F7/HAL_STM32F7.h | 8 +- .../src/HAL/HAL_STM32F7/HAL_spi_STM32F7.cpp | 15 +- .../HAL/HAL_STM32F7/HAL_timers_STM32F7.cpp | 44 +- .../src/HAL/HAL_STM32F7/HAL_timers_STM32F7.h | 37 +- Marlin/src/HAL/HAL_STM32F7/TMC2660.cpp | 1418 ++++++++--------- Marlin/src/HAL/HAL_STM32F7/TMC2660.h | 195 ++- Marlin/src/HAL/HAL_STM32F7/fastio_STM32F7.h | 24 +- .../src/HAL/HAL_STM32F7/watchdog_STM32F7.cpp | 73 +- Marlin/src/HAL/HAL_SanityCheck.h | 4 +- Marlin/src/HAL/HAL_spi_pins.h | 2 +- Marlin/src/core/macros.h | 1 + Marlin/src/module/stepper_indirection.cpp | 2 +- Marlin/src/module/stepper_indirection.h | 2 +- 18 files changed, 1008 insertions(+), 1313 deletions(-) diff --git a/Marlin/src/HAL/HAL_STM32F1/HAL_Stm32f1.h b/Marlin/src/HAL/HAL_STM32F1/HAL_Stm32f1.h index c5186c9fd8..23b8be33a7 100644 --- a/Marlin/src/HAL/HAL_STM32F1/HAL_Stm32f1.h +++ b/Marlin/src/HAL/HAL_STM32F1/HAL_Stm32f1.h @@ -109,7 +109,7 @@ #define analogInputToDigitalPin(p) (p) #endif -#define CRITICAL_SECTION_START noInterrupts(); +#define CRITICAL_SECTION_START noInterrupts(); #define CRITICAL_SECTION_END interrupts(); // On AVR this is in math.h? diff --git a/Marlin/src/HAL/HAL_STM32F1/fastio_Stm32f1.h b/Marlin/src/HAL/HAL_STM32F1/fastio_Stm32f1.h index 4519a4fe49..1ebf9e8557 100644 --- a/Marlin/src/HAL/HAL_STM32F1/fastio_Stm32f1.h +++ b/Marlin/src/HAL/HAL_STM32F1/fastio_Stm32f1.h @@ -26,8 +26,8 @@ * These use GPIO functions instead of Direct Port Manipulation, as on AVR. */ -#ifndef _FASTIO_STM32F1_H -#define _FASTIO_STM32F1_H +#ifndef _FASTIO_STM32F1_H +#define _FASTIO_STM32F1_H #include @@ -49,9 +49,9 @@ #define GET_TIMER(IO) (PIN_MAP[IO].timer_device != NULL) #define OUT_WRITE(IO, v) { _SET_OUTPUT(IO); WRITE(IO, v); } -/* +/** * TODO: Write a macro to test if PIN is PWM or not. */ #define PWM_PIN(p) true -#endif /* _FASTIO_STM32F1_H */ +#endif // _FASTIO_STM32F1_H diff --git a/Marlin/src/HAL/HAL_STM32F7/EEPROM_Emul/eeprom_emul.cpp b/Marlin/src/HAL/HAL_STM32F7/EEPROM_Emul/eeprom_emul.cpp index 266573f7b3..507a4e7377 100644 --- a/Marlin/src/HAL/HAL_STM32F7/EEPROM_Emul/eeprom_emul.cpp +++ b/Marlin/src/HAL/HAL_STM32F7/EEPROM_Emul/eeprom_emul.cpp @@ -78,8 +78,7 @@ static uint16_t EE_VerifyPageFullyErased(uint32_t Address); * @retval - Flash error code: on write Flash error * - FLASH_COMPLETE: on success */ -uint16_t EE_Initialise(void) -{ +uint16_t EE_Initialise(void) { uint16_t PageStatus0 = 6, PageStatus1 = 6; uint16_t VarIdx = 0; uint16_t EepromStatus = 0, ReadStatus = 0; @@ -100,209 +99,141 @@ uint16_t EE_Initialise(void) pEraseInit.VoltageRange = VOLTAGE_RANGE; /* Check for invalid header states and repair if necessary */ - switch (PageStatus0) - { + switch (PageStatus0) { case ERASED: - if (PageStatus1 == VALID_PAGE) /* Page0 erased, Page1 valid */ - { + if (PageStatus1 == VALID_PAGE) { /* Page0 erased, Page1 valid */ /* Erase Page0 */ - if(!EE_VerifyPageFullyErased(PAGE0_BASE_ADDRESS)) - { + if(!EE_VerifyPageFullyErased(PAGE0_BASE_ADDRESS)) { FlashStatus = HAL_FLASHEx_Erase(&pEraseInit, &SectorError); /* If erase operation was failed, a Flash error code is returned */ - if (FlashStatus != HAL_OK) - { + if (FlashStatus != HAL_OK) { return FlashStatus; } } } - else if (PageStatus1 == RECEIVE_DATA) /* Page0 erased, Page1 receive */ - { + else if (PageStatus1 == RECEIVE_DATA) { /* Page0 erased, Page1 receive */ /* Erase Page0 */ - if(!EE_VerifyPageFullyErased(PAGE0_BASE_ADDRESS)) - { + if (!EE_VerifyPageFullyErased(PAGE0_BASE_ADDRESS)) { FlashStatus = HAL_FLASHEx_Erase(&pEraseInit, &SectorError); /* If erase operation was failed, a Flash error code is returned */ - if (FlashStatus != HAL_OK) - { - return FlashStatus; - } + if (FlashStatus != HAL_OK) return FlashStatus; } /* Mark Page1 as valid */ FlashStatus = HAL_FLASH_Program(TYPEPROGRAM_HALFWORD, PAGE1_BASE_ADDRESS, VALID_PAGE); /* If program operation was failed, a Flash error code is returned */ - if (FlashStatus != HAL_OK) - { - return FlashStatus; - } + if (FlashStatus != HAL_OK) return FlashStatus; } - else /* First EEPROM access (Page0&1 are erased) or invalid state -> format EEPROM */ - { + else { /* First EEPROM access (Page0&1 are erased) or invalid state -> format EEPROM */ /* Erase both Page0 and Page1 and set Page0 as valid page */ FlashStatus = EE_Format(); /* If erase/program operation was failed, a Flash error code is returned */ - if (FlashStatus != HAL_OK) - { - return FlashStatus; - } + if (FlashStatus != HAL_OK) return FlashStatus; } break; case RECEIVE_DATA: - if (PageStatus1 == VALID_PAGE) /* Page0 receive, Page1 valid */ - { + if (PageStatus1 == VALID_PAGE) { /* Page0 receive, Page1 valid */ /* Transfer data from Page1 to Page0 */ - for (VarIdx = 0; VarIdx < NB_OF_VAR; VarIdx++) - { + for (VarIdx = 0; VarIdx < NB_OF_VAR; VarIdx++) { if (( *(__IO uint16_t*)(PAGE0_BASE_ADDRESS + 6)) == VirtAddVarTab[VarIdx]) - { x = VarIdx; - } - if (VarIdx != x) - { + if (VarIdx != x) { /* Read the last variables' updates */ ReadStatus = EE_ReadVariable(VirtAddVarTab[VarIdx], &DataVar); /* In case variable corresponding to the virtual address was found */ - if (ReadStatus != 0x1) - { + if (ReadStatus != 0x1) { /* Transfer the variable to the Page0 */ EepromStatus = EE_VerifyPageFullWriteVariable(VirtAddVarTab[VarIdx], DataVar); /* If program operation was failed, a Flash error code is returned */ - if (EepromStatus != HAL_OK) - { - return EepromStatus; - } + if (EepromStatus != HAL_OK) return EepromStatus; } } } /* Mark Page0 as valid */ FlashStatus = HAL_FLASH_Program(TYPEPROGRAM_HALFWORD, PAGE0_BASE_ADDRESS, VALID_PAGE); /* If program operation was failed, a Flash error code is returned */ - if (FlashStatus != HAL_OK) - { - return FlashStatus; - } + if (FlashStatus != HAL_OK) return FlashStatus; pEraseInit.Sector = PAGE1_ID; pEraseInit.NbSectors = 1; pEraseInit.VoltageRange = VOLTAGE_RANGE; /* Erase Page1 */ - if(!EE_VerifyPageFullyErased(PAGE1_BASE_ADDRESS)) - { + if (!EE_VerifyPageFullyErased(PAGE1_BASE_ADDRESS)) { FlashStatus = HAL_FLASHEx_Erase(&pEraseInit, &SectorError); /* If erase operation was failed, a Flash error code is returned */ - if (FlashStatus != HAL_OK) - { - return FlashStatus; - } + if (FlashStatus != HAL_OK) return FlashStatus; } } - else if (PageStatus1 == ERASED) /* Page0 receive, Page1 erased */ - { + else if (PageStatus1 == ERASED) { /* Page0 receive, Page1 erased */ pEraseInit.Sector = PAGE1_ID; pEraseInit.NbSectors = 1; pEraseInit.VoltageRange = VOLTAGE_RANGE; /* Erase Page1 */ - if(!EE_VerifyPageFullyErased(PAGE1_BASE_ADDRESS)) - { + if (!EE_VerifyPageFullyErased(PAGE1_BASE_ADDRESS)) { FlashStatus = HAL_FLASHEx_Erase(&pEraseInit, &SectorError); /* If erase operation was failed, a Flash error code is returned */ - if (FlashStatus != HAL_OK) - { - return FlashStatus; - } + if (FlashStatus != HAL_OK) return FlashStatus; } /* Mark Page0 as valid */ FlashStatus = HAL_FLASH_Program(TYPEPROGRAM_HALFWORD, PAGE0_BASE_ADDRESS, VALID_PAGE); /* If program operation was failed, a Flash error code is returned */ - if (FlashStatus != HAL_OK) - { - return FlashStatus; - } + if (FlashStatus != HAL_OK) return FlashStatus; } - else /* Invalid state -> format eeprom */ - { + else { /* Invalid state -> format eeprom */ /* Erase both Page0 and Page1 and set Page0 as valid page */ FlashStatus = EE_Format(); /* If erase/program operation was failed, a Flash error code is returned */ - if (FlashStatus != HAL_OK) - { - return FlashStatus; - } + if (FlashStatus != HAL_OK) return FlashStatus; } break; case VALID_PAGE: - if (PageStatus1 == VALID_PAGE) /* Invalid state -> format eeprom */ - { + if (PageStatus1 == VALID_PAGE) { /* Invalid state -> format eeprom */ /* Erase both Page0 and Page1 and set Page0 as valid page */ FlashStatus = EE_Format(); /* If erase/program operation was failed, a Flash error code is returned */ - if (FlashStatus != HAL_OK) - { - return FlashStatus; - } + if (FlashStatus != HAL_OK) return FlashStatus; } - else if (PageStatus1 == ERASED) /* Page0 valid, Page1 erased */ - { + else if (PageStatus1 == ERASED) { /* Page0 valid, Page1 erased */ pEraseInit.Sector = PAGE1_ID; pEraseInit.NbSectors = 1; pEraseInit.VoltageRange = VOLTAGE_RANGE; /* Erase Page1 */ - if(!EE_VerifyPageFullyErased(PAGE1_BASE_ADDRESS)) - { + if (!EE_VerifyPageFullyErased(PAGE1_BASE_ADDRESS)) { FlashStatus = HAL_FLASHEx_Erase(&pEraseInit, &SectorError); /* If erase operation was failed, a Flash error code is returned */ - if (FlashStatus != HAL_OK) - { - return FlashStatus; - } + if (FlashStatus != HAL_OK) return FlashStatus; } } - else /* Page0 valid, Page1 receive */ - { + else { /* Page0 valid, Page1 receive */ /* Transfer data from Page0 to Page1 */ - for (VarIdx = 0; VarIdx < NB_OF_VAR; VarIdx++) - { + for (VarIdx = 0; VarIdx < NB_OF_VAR; VarIdx++) { if ((*(__IO uint16_t*)(PAGE1_BASE_ADDRESS + 6)) == VirtAddVarTab[VarIdx]) - { x = VarIdx; - } - if (VarIdx != x) - { + + if (VarIdx != x) { /* Read the last variables' updates */ ReadStatus = EE_ReadVariable(VirtAddVarTab[VarIdx], &DataVar); /* In case variable corresponding to the virtual address was found */ - if (ReadStatus != 0x1) - { + if (ReadStatus != 0x1) { /* Transfer the variable to the Page1 */ EepromStatus = EE_VerifyPageFullWriteVariable(VirtAddVarTab[VarIdx], DataVar); /* If program operation was failed, a Flash error code is returned */ - if (EepromStatus != HAL_OK) - { - return EepromStatus; - } + if (EepromStatus != HAL_OK) return EepromStatus; } } } /* Mark Page1 as valid */ FlashStatus = HAL_FLASH_Program(TYPEPROGRAM_HALFWORD, PAGE1_BASE_ADDRESS, VALID_PAGE); /* If program operation was failed, a Flash error code is returned */ - if (FlashStatus != HAL_OK) - { - return FlashStatus; - } + if (FlashStatus != HAL_OK) return FlashStatus; pEraseInit.Sector = PAGE0_ID; pEraseInit.NbSectors = 1; pEraseInit.VoltageRange = VOLTAGE_RANGE; /* Erase Page0 */ - if(!EE_VerifyPageFullyErased(PAGE0_BASE_ADDRESS)) - { + if (!EE_VerifyPageFullyErased(PAGE0_BASE_ADDRESS)) { FlashStatus = HAL_FLASHEx_Erase(&pEraseInit, &SectorError); /* If erase operation was failed, a Flash error code is returned */ - if (FlashStatus != HAL_OK) - { - return FlashStatus; - } + if (FlashStatus != HAL_OK) return FlashStatus; } } break; @@ -311,10 +242,7 @@ uint16_t EE_Initialise(void) /* Erase both Page0 and Page1 and set Page0 as valid page */ FlashStatus = EE_Format(); /* If erase/program operation was failed, a Flash error code is returned */ - if (FlashStatus != HAL_OK) - { - return FlashStatus; - } + if (FlashStatus != HAL_OK) return FlashStatus; break; } @@ -322,55 +250,46 @@ uint16_t EE_Initialise(void) } /** - * @brief Verify if specified page is fully erased. - * @param Address: page address - * This parameter can be one of the following values: - * @arg PAGE0_BASE_ADDRESS: Page0 base address - * @arg PAGE1_BASE_ADDRESS: Page1 base address - * @retval page fully erased status: - * - 0: if Page not erased - * - 1: if Page erased - */ -uint16_t EE_VerifyPageFullyErased(uint32_t Address) -{ + * @brief Verify if specified page is fully erased. + * @param Address: page address + * This parameter can be one of the following values: + * @arg PAGE0_BASE_ADDRESS: Page0 base address + * @arg PAGE1_BASE_ADDRESS: Page1 base address + * @retval page fully erased status: + * - 0: if Page not erased + * - 1: if Page erased + */ +uint16_t EE_VerifyPageFullyErased(uint32_t Address) { uint32_t ReadStatus = 1; uint16_t AddressValue = 0x5555; - /* Check each active page address starting from end */ - while (Address <= PAGE0_END_ADDRESS) - { + while (Address <= PAGE0_END_ADDRESS) { /* Get the current location content to be compared with virtual address */ AddressValue = (*(__IO uint16_t*)Address); - /* Compare the read address with the virtual address */ - if (AddressValue != ERASED) - { - + if (AddressValue != ERASED) { /* In case variable value is read, reset ReadStatus flag */ ReadStatus = 0; - break; } /* Next address location */ - Address = Address + 4; + Address += 4; } - /* Return ReadStatus value: (0: Page not erased, 1: Sector erased) */ return ReadStatus; } /** - * @brief Returns the last stored variable data, if found, which correspond to - * the passed virtual address - * @param VirtAddress: Variable virtual address - * @param Data: Global variable contains the read variable value - * @retval Success or error status: - * - 0: if variable was found - * - 1: if the variable was not found - * - NO_VALID_PAGE: if no valid page was found. - */ -uint16_t EE_ReadVariable(uint16_t VirtAddress, uint16_t* Data) -{ + * @brief Returns the last stored variable data, if found, which correspond to + * the passed virtual address + * @param VirtAddress: Variable virtual address + * @param Data: Global variable contains the read variable value + * @retval Success or error status: + * - 0: if variable was found + * - 1: if the variable was not found + * - NO_VALID_PAGE: if no valid page was found. + */ +uint16_t EE_ReadVariable(uint16_t VirtAddress, uint16_t* Data) { uint16_t ValidPage = PAGE0; uint16_t AddressValue = 0x5555, ReadStatus = 1; uint32_t Address = EEPROM_START_ADDRESS, PageStartAddress = EEPROM_START_ADDRESS; @@ -379,10 +298,7 @@ uint16_t EE_ReadVariable(uint16_t VirtAddress, uint16_t* Data) ValidPage = EE_FindValidPage(READ_FROM_VALID_PAGE); /* Check if there is no valid page */ - if (ValidPage == NO_VALID_PAGE) - { - return NO_VALID_PAGE; - } + if (ValidPage == NO_VALID_PAGE) return NO_VALID_PAGE; /* Get the valid Page start Address */ PageStartAddress = (uint32_t)(EEPROM_START_ADDRESS + (uint32_t)(ValidPage * PAGE_SIZE)); @@ -391,69 +307,54 @@ uint16_t EE_ReadVariable(uint16_t VirtAddress, uint16_t* Data) Address = (uint32_t)((EEPROM_START_ADDRESS - 2) + (uint32_t)((1 + ValidPage) * PAGE_SIZE)); /* Check each active page address starting from end */ - while (Address > (PageStartAddress + 2)) - { + while (Address > (PageStartAddress + 2)) { /* Get the current location content to be compared with virtual address */ AddressValue = (*(__IO uint16_t*)Address); /* Compare the read address with the virtual address */ - if (AddressValue == VirtAddress) - { + if (AddressValue == VirtAddress) { /* Get content of Address-2 which is variable value */ *Data = (*(__IO uint16_t*)(Address - 2)); - /* In case variable value is read, reset ReadStatus flag */ ReadStatus = 0; - break; } - else - { - /* Next address location */ - Address = Address - 4; - } + else /* Next address location */ + Address -= 4; } - /* Return ReadStatus value: (0: variable exist, 1: variable doesn't exist) */ return ReadStatus; } /** - * @brief Writes/upadtes variable data in EEPROM. - * @param VirtAddress: Variable virtual address - * @param Data: 16 bit data to be written - * @retval Success or error status: - * - FLASH_COMPLETE: on success - * - PAGE_FULL: if valid page is full - * - NO_VALID_PAGE: if no valid page was found - * - Flash error code: on write Flash error - */ -uint16_t EE_WriteVariable(uint16_t VirtAddress, uint16_t Data) -{ - uint16_t Status = 0; - + * @brief Writes/upadtes variable data in EEPROM. + * @param VirtAddress: Variable virtual address + * @param Data: 16 bit data to be written + * @retval Success or error status: + * - FLASH_COMPLETE: on success + * - PAGE_FULL: if valid page is full + * - NO_VALID_PAGE: if no valid page was found + * - Flash error code: on write Flash error + */ +uint16_t EE_WriteVariable(uint16_t VirtAddress, uint16_t Data) { /* Write the variable virtual address and value in the EEPROM */ - Status = EE_VerifyPageFullWriteVariable(VirtAddress, Data); + uint16_t Status = EE_VerifyPageFullWriteVariable(VirtAddress, Data); /* In case the EEPROM active page is full */ - if (Status == PAGE_FULL) - { - /* Perform Page transfer */ + if (Status == PAGE_FULL) /* Perform Page transfer */ Status = EE_PageTransfer(VirtAddress, Data); - } /* Return last operation status */ return Status; } /** - * @brief Erases PAGE and PAGE1 and writes VALID_PAGE header to PAGE - * @param None - * @retval Status of the last operation (Flash write or erase) done during - * EEPROM formating - */ -static HAL_StatusTypeDef EE_Format(void) -{ + * @brief Erases PAGE and PAGE1 and writes VALID_PAGE header to PAGE + * @param None + * @retval Status of the last operation (Flash write or erase) done during + * EEPROM formating + */ +static HAL_StatusTypeDef EE_Format(void) { HAL_StatusTypeDef FlashStatus = HAL_OK; uint32_t SectorError = 0; FLASH_EraseInitTypeDef pEraseInit; @@ -463,49 +364,37 @@ static HAL_StatusTypeDef EE_Format(void) pEraseInit.NbSectors = 1; pEraseInit.VoltageRange = VOLTAGE_RANGE; /* Erase Page0 */ - if(!EE_VerifyPageFullyErased(PAGE0_BASE_ADDRESS)) - { + if (!EE_VerifyPageFullyErased(PAGE0_BASE_ADDRESS)) { FlashStatus = HAL_FLASHEx_Erase(&pEraseInit, &SectorError); /* If erase operation was failed, a Flash error code is returned */ - if (FlashStatus != HAL_OK) - { - return FlashStatus; - } + if (FlashStatus != HAL_OK) return FlashStatus; } /* Set Page0 as valid page: Write VALID_PAGE at Page0 base address */ FlashStatus = HAL_FLASH_Program(TYPEPROGRAM_HALFWORD, PAGE0_BASE_ADDRESS, VALID_PAGE); /* If program operation was failed, a Flash error code is returned */ - if (FlashStatus != HAL_OK) - { - return FlashStatus; - } + if (FlashStatus != HAL_OK) return FlashStatus; pEraseInit.Sector = PAGE1_ID; /* Erase Page1 */ - if(!EE_VerifyPageFullyErased(PAGE1_BASE_ADDRESS)) - { + if (!EE_VerifyPageFullyErased(PAGE1_BASE_ADDRESS)) { FlashStatus = HAL_FLASHEx_Erase(&pEraseInit, &SectorError); /* If erase operation was failed, a Flash error code is returned */ - if (FlashStatus != HAL_OK) - { - return FlashStatus; - } + if (FlashStatus != HAL_OK) return FlashStatus; } return HAL_OK; } /** - * @brief Find valid Page for write or read operation - * @param Operation: operation to achieve on the valid page. - * This parameter can be one of the following values: - * @arg READ_FROM_VALID_PAGE: read operation from valid page - * @arg WRITE_IN_VALID_PAGE: write operation from valid page - * @retval Valid page number (PAGE or PAGE1) or NO_VALID_PAGE in case - * of no valid page was found - */ -static uint16_t EE_FindValidPage(uint8_t Operation) -{ + * @brief Find valid Page for write or read operation + * @param Operation: operation to achieve on the valid page. + * This parameter can be one of the following values: + * @arg READ_FROM_VALID_PAGE: read operation from valid page + * @arg WRITE_IN_VALID_PAGE: write operation from valid page + * @retval Valid page number (PAGE or PAGE1) or NO_VALID_PAGE in case + * of no valid page was found + */ +static uint16_t EE_FindValidPage(uint8_t Operation) { uint16_t PageStatus0 = 6, PageStatus1 = 6; /* Get Page0 actual status */ @@ -515,51 +404,28 @@ static uint16_t EE_FindValidPage(uint8_t Operation) PageStatus1 = (*(__IO uint16_t*)PAGE1_BASE_ADDRESS); /* Write or read operation */ - switch (Operation) - { + switch (Operation) { case WRITE_IN_VALID_PAGE: /* ---- Write operation ---- */ - if (PageStatus1 == VALID_PAGE) - { + if (PageStatus1 == VALID_PAGE) { /* Page0 receiving data */ - if (PageStatus0 == RECEIVE_DATA) - { - return PAGE0; /* Page0 valid */ - } - else - { - return PAGE1; /* Page1 valid */ - } + if (PageStatus0 == RECEIVE_DATA) return PAGE0; /* Page0 valid */ + else return PAGE1; /* Page1 valid */ } - else if (PageStatus0 == VALID_PAGE) - { + else if (PageStatus0 == VALID_PAGE) { /* Page1 receiving data */ - if (PageStatus1 == RECEIVE_DATA) - { - return PAGE1; /* Page1 valid */ - } - else - { - return PAGE0; /* Page0 valid */ - } + if (PageStatus1 == RECEIVE_DATA) return PAGE1; /* Page1 valid */ + else return PAGE0; /* Page0 valid */ } else - { return NO_VALID_PAGE; /* No valid Page */ - } case READ_FROM_VALID_PAGE: /* ---- Read operation ---- */ if (PageStatus0 == VALID_PAGE) - { return PAGE0; /* Page0 valid */ - } else if (PageStatus1 == VALID_PAGE) - { return PAGE1; /* Page1 valid */ - } else - { - return NO_VALID_PAGE ; /* No valid Page */ - } + return NO_VALID_PAGE; /* No valid Page */ default: return PAGE0; /* Page0 valid */ @@ -567,17 +433,16 @@ static uint16_t EE_FindValidPage(uint8_t Operation) } /** - * @brief Verify if active page is full and Writes variable in EEPROM. - * @param VirtAddress: 16 bit virtual address of the variable - * @param Data: 16 bit data to be written as variable value - * @retval Success or error status: - * - FLASH_COMPLETE: on success - * - PAGE_FULL: if valid page is full - * - NO_VALID_PAGE: if no valid page was found - * - Flash error code: on write Flash error - */ -static uint16_t EE_VerifyPageFullWriteVariable(uint16_t VirtAddress, uint16_t Data) -{ + * @brief Verify if active page is full and Writes variable in EEPROM. + * @param VirtAddress: 16 bit virtual address of the variable + * @param Data: 16 bit data to be written as variable value + * @retval Success or error status: + * - FLASH_COMPLETE: on success + * - PAGE_FULL: if valid page is full + * - NO_VALID_PAGE: if no valid page was found + * - Flash error code: on write Flash error + */ +static uint16_t EE_VerifyPageFullWriteVariable(uint16_t VirtAddress, uint16_t Data) { HAL_StatusTypeDef FlashStatus = HAL_OK; uint16_t ValidPage = PAGE0; uint32_t Address = EEPROM_START_ADDRESS, PageEndAddress = EEPROM_START_ADDRESS+PAGE_SIZE; @@ -586,10 +451,7 @@ static uint16_t EE_VerifyPageFullWriteVariable(uint16_t VirtAddress, uint16_t Da ValidPage = EE_FindValidPage(WRITE_IN_VALID_PAGE); /* Check if there is no valid page */ - if (ValidPage == NO_VALID_PAGE) - { - return NO_VALID_PAGE; - } + if (ValidPage == NO_VALID_PAGE) return NO_VALID_PAGE; /* Get the valid Page start Address */ Address = (uint32_t)(EEPROM_START_ADDRESS + (uint32_t)(ValidPage * PAGE_SIZE)); @@ -598,28 +460,20 @@ static uint16_t EE_VerifyPageFullWriteVariable(uint16_t VirtAddress, uint16_t Da PageEndAddress = (uint32_t)((EEPROM_START_ADDRESS - 1) + (uint32_t)((ValidPage + 1) * PAGE_SIZE)); /* Check each active page address starting from begining */ - while (Address < PageEndAddress) - { + while (Address < PageEndAddress) { /* Verify if Address and Address+2 contents are 0xFFFFFFFF */ - if ((*(__IO uint32_t*)Address) == 0xFFFFFFFF) - { + if ((*(__IO uint32_t*)Address) == 0xFFFFFFFF) { /* Set variable data */ FlashStatus = HAL_FLASH_Program(TYPEPROGRAM_HALFWORD, Address, Data); /* If program operation was failed, a Flash error code is returned */ - if (FlashStatus != HAL_OK) - { - return FlashStatus; - } + if (FlashStatus != HAL_OK) return FlashStatus; /* Set variable virtual address */ FlashStatus = HAL_FLASH_Program(TYPEPROGRAM_HALFWORD, Address + 2, VirtAddress); /* Return program operation status */ return FlashStatus; } - else - { - /* Next address location */ - Address = Address + 4; - } + else /* Next address location */ + Address += 4; } /* Return PAGE_FULL in case the valid page is full */ @@ -627,18 +481,17 @@ static uint16_t EE_VerifyPageFullWriteVariable(uint16_t VirtAddress, uint16_t Da } /** - * @brief Transfers last updated variables data from the full Page to - * an empty one. - * @param VirtAddress: 16 bit virtual address of the variable - * @param Data: 16 bit data to be written as variable value - * @retval Success or error status: - * - FLASH_COMPLETE: on success - * - PAGE_FULL: if valid page is full - * - NO_VALID_PAGE: if no valid page was found - * - Flash error code: on write Flash error - */ -static uint16_t EE_PageTransfer(uint16_t VirtAddress, uint16_t Data) -{ + * @brief Transfers last updated variables data from the full Page to + * an empty one. + * @param VirtAddress: 16 bit virtual address of the variable + * @param Data: 16 bit data to be written as variable value + * @retval Success or error status: + * - FLASH_COMPLETE: on success + * - PAGE_FULL: if valid page is full + * - NO_VALID_PAGE: if no valid page was found + * - Flash error code: on write Flash error + */ +static uint16_t EE_PageTransfer(uint16_t VirtAddress, uint16_t Data) { HAL_StatusTypeDef FlashStatus = HAL_OK; uint32_t NewPageAddress = EEPROM_START_ADDRESS; uint16_t OldPageId=0; @@ -650,60 +503,42 @@ static uint16_t EE_PageTransfer(uint16_t VirtAddress, uint16_t Data) /* Get active Page for read operation */ ValidPage = EE_FindValidPage(READ_FROM_VALID_PAGE); - if (ValidPage == PAGE1) /* Page1 valid */ - { + if (ValidPage == PAGE1) { /* Page1 valid */ /* New page address where variable will be moved to */ NewPageAddress = PAGE0_BASE_ADDRESS; - /* Old page ID where variable will be taken from */ OldPageId = PAGE1_ID; } - else if (ValidPage == PAGE0) /* Page0 valid */ - { + else if (ValidPage == PAGE0) { /* Page0 valid */ /* New page address where variable will be moved to */ NewPageAddress = PAGE1_BASE_ADDRESS; - /* Old page ID where variable will be taken from */ OldPageId = PAGE0_ID; } else - { return NO_VALID_PAGE; /* No valid Page */ - } /* Set the new Page status to RECEIVE_DATA status */ FlashStatus = HAL_FLASH_Program(TYPEPROGRAM_HALFWORD, NewPageAddress, RECEIVE_DATA); /* If program operation was failed, a Flash error code is returned */ - if (FlashStatus != HAL_OK) - { - return FlashStatus; - } + if (FlashStatus != HAL_OK) return FlashStatus; /* Write the variable passed as parameter in the new active page */ EepromStatus = EE_VerifyPageFullWriteVariable(VirtAddress, Data); /* If program operation was failed, a Flash error code is returned */ - if (EepromStatus != HAL_OK) - { - return EepromStatus; - } + if (EepromStatus != HAL_OK) return EepromStatus; /* Transfer process: transfer variables from old to the new active page */ - for (VarIdx = 0; VarIdx < NB_OF_VAR; VarIdx++) - { - if (VirtAddVarTab[VarIdx] != VirtAddress) /* Check each variable except the one passed as parameter */ - { + for (VarIdx = 0; VarIdx < NB_OF_VAR; VarIdx++) { + if (VirtAddVarTab[VarIdx] != VirtAddress) { /* Check each variable except the one passed as parameter */ /* Read the other last variable updates */ ReadStatus = EE_ReadVariable(VirtAddVarTab[VarIdx], &DataVar); /* In case variable corresponding to the virtual address was found */ - if (ReadStatus != 0x1) - { + if (ReadStatus != 0x1) { /* Transfer the variable to the new active page */ EepromStatus = EE_VerifyPageFullWriteVariable(VirtAddVarTab[VarIdx], DataVar); /* If program operation was failed, a Flash error code is returned */ - if (EepromStatus != HAL_OK) - { - return EepromStatus; - } + if (EepromStatus != HAL_OK) return EepromStatus; } } } @@ -716,18 +551,12 @@ static uint16_t EE_PageTransfer(uint16_t VirtAddress, uint16_t Data) /* Erase the old Page: Set old Page status to ERASED status */ FlashStatus = HAL_FLASHEx_Erase(&pEraseInit, &SectorError); /* If erase operation was failed, a Flash error code is returned */ - if (FlashStatus != HAL_OK) - { - return FlashStatus; - } + if (FlashStatus != HAL_OK) return FlashStatus; /* Set new Page status to VALID_PAGE status */ FlashStatus = HAL_FLASH_Program(TYPEPROGRAM_HALFWORD, NewPageAddress, VALID_PAGE); /* If program operation was failed, a Flash error code is returned */ - if (FlashStatus != HAL_OK) - { - return FlashStatus; - } + if (FlashStatus != HAL_OK) return FlashStatus; /* Return last operation flash status */ return FlashStatus; @@ -736,7 +565,7 @@ static uint16_t EE_PageTransfer(uint16_t VirtAddress, uint16_t Data) #endif // STM32F7 /** - * @} - */ + * @} + */ /******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/Marlin/src/HAL/HAL_STM32F7/EmulatedEeprom.cpp b/Marlin/src/HAL/HAL_STM32F7/EmulatedEeprom.cpp index 519dfbddec..71140d18e6 100644 --- a/Marlin/src/HAL/HAL_STM32F7/EmulatedEeprom.cpp +++ b/Marlin/src/HAL/HAL_STM32F7/EmulatedEeprom.cpp @@ -18,7 +18,7 @@ */ #ifdef STM32F7 - + /** * Description: functions for I2C connected external EEPROM. * Not platform dependent. diff --git a/Marlin/src/HAL/HAL_STM32F7/HAL_STM32F7.cpp b/Marlin/src/HAL/HAL_STM32F7/HAL_STM32F7.cpp index 17e567ba33..04d0192dfd 100644 --- a/Marlin/src/HAL/HAL_STM32F7/HAL_STM32F7.cpp +++ b/Marlin/src/HAL/HAL_STM32F7/HAL_STM32F7.cpp @@ -81,18 +81,17 @@ void sei(void) { interrupts(); } void HAL_clear_reset_source(void) { __HAL_RCC_CLEAR_RESET_FLAGS(); } uint8_t HAL_get_reset_source (void) { - if(__HAL_RCC_GET_FLAG(RCC_FLAG_IWDGRST) != RESET) - return RST_WATCHDOG; + if (__HAL_RCC_GET_FLAG(RCC_FLAG_IWDGRST) != RESET) + return RST_WATCHDOG; - if(__HAL_RCC_GET_FLAG(RCC_FLAG_SFTRST) != RESET) - return RST_SOFTWARE; + if (__HAL_RCC_GET_FLAG(RCC_FLAG_SFTRST) != RESET) + return RST_SOFTWARE; - if(__HAL_RCC_GET_FLAG(RCC_FLAG_PINRST) != RESET) - return RST_EXTERNAL; + if (__HAL_RCC_GET_FLAG(RCC_FLAG_PINRST) != RESET) + return RST_EXTERNAL; - if(__HAL_RCC_GET_FLAG(RCC_FLAG_PORRST) != RESET) - return RST_POWER_ON; - + if (__HAL_RCC_GET_FLAG(RCC_FLAG_PORRST) != RESET) + return RST_POWER_ON; return 0; } @@ -102,8 +101,6 @@ extern "C" { extern unsigned int _ebss; // end of bss section } - - // return free memory between end of heap (or end bss) and whatever is current /* diff --git a/Marlin/src/HAL/HAL_STM32F7/HAL_STM32F7.h b/Marlin/src/HAL/HAL_STM32F7/HAL_STM32F7.h index 7a0b72a10c..f2196a6740 100644 --- a/Marlin/src/HAL/HAL_STM32F7/HAL_STM32F7.h +++ b/Marlin/src/HAL/HAL_STM32F7/HAL_STM32F7.h @@ -57,7 +57,7 @@ #error "SERIAL_PORT must be from -1 to 6" #endif #if SERIAL_PORT == -1 - #define MYSERIAL0 SerialUSB + #define MYSERIAL0 SerialUSB #elif SERIAL_PORT == 1 #define MYSERIAL0 SerialUART1 #elif SERIAL_PORT == 2 @@ -79,7 +79,7 @@ #error "SERIAL_PORT_2 must be different than SERIAL_PORT" #endif #define NUM_SERIAL 2 - #if SERIAL_PORT_2 == -1 + #if SERIAL_PORT_2 == -1 #define MYSERIAL1 SerialUSB #elif SERIAL_PORT_2 == 1 #define MYSERIAL1 SerialUART1 @@ -98,7 +98,7 @@ #define NUM_SERIAL 1 #endif -#define _BV(bit) (1 << (bit)) +#define _BV(bit) (1 << (bit)) /** * TODO: review this to return 1 for pins that are not analog input @@ -107,7 +107,7 @@ #define analogInputToDigitalPin(p) (p) #endif -#define CRITICAL_SECTION_START noInterrupts(); +#define CRITICAL_SECTION_START noInterrupts(); #define CRITICAL_SECTION_END interrupts(); // On AVR this is in math.h? diff --git a/Marlin/src/HAL/HAL_STM32F7/HAL_spi_STM32F7.cpp b/Marlin/src/HAL/HAL_STM32F7/HAL_spi_STM32F7.cpp index 47e06efe2b..47fe8743ec 100644 --- a/Marlin/src/HAL/HAL_STM32F7/HAL_spi_STM32F7.cpp +++ b/Marlin/src/HAL/HAL_STM32F7/HAL_spi_STM32F7.cpp @@ -82,20 +82,17 @@ void spiBegin(void) { #if !PIN_EXISTS(SS) #error SS_PIN not defined! #endif - + SET_OUTPUT(SS_PIN); WRITE(SS_PIN, HIGH); - } - - /** Configure SPI for specified SPI speed */ void spiInit(uint8_t spiRate) { // Use datarates Marlin uses uint32_t clock; switch (spiRate) { - case SPI_FULL_SPEED: clock = 20000000; break; //13.9mhz=20000000 6.75mhz=10000000 3.38mhz=5000000 .833mhz=1000000 + case SPI_FULL_SPEED: clock = 20000000; break; // 13.9mhz=20000000 6.75mhz=10000000 3.38mhz=5000000 .833mhz=1000000 case SPI_HALF_SPEED: clock = 5000000; break; case SPI_QUARTER_SPEED: clock = 2500000; break; case SPI_EIGHTH_SPEED: clock = 1250000; break; @@ -108,8 +105,6 @@ void spiInit(uint8_t spiRate) { SPI.begin(); } - - /** * @brief Receives a single byte from the SPI port. * @@ -133,8 +128,6 @@ uint8_t spiRec(void) { * * @details Uses DMA */ - - void spiRead(uint8_t* buf, uint16_t nbyte) { SPI.beginTransaction(spiConfig); SPI.dmaTransfer(0, const_cast(buf), nbyte); @@ -162,8 +155,6 @@ void spiSend(uint8_t b) { * * @details Use DMA */ - - void spiSendBlock(uint8_t token, const uint8_t* buf) { SPI.beginTransaction(spiConfig); SPI.transfer(token); @@ -171,8 +162,6 @@ void spiSendBlock(uint8_t token, const uint8_t* buf) { SPI.endTransaction(); } - - #endif // SOFTWARE_SPI #endif // STM32F7 diff --git a/Marlin/src/HAL/HAL_STM32F7/HAL_timers_STM32F7.cpp b/Marlin/src/HAL/HAL_STM32F7/HAL_timers_STM32F7.cpp index 7bb331970a..96e839265e 100644 --- a/Marlin/src/HAL/HAL_STM32F7/HAL_timers_STM32F7.cpp +++ b/Marlin/src/HAL/HAL_STM32F7/HAL_timers_STM32F7.cpp @@ -20,8 +20,8 @@ * */ - #ifdef STM32F7 + // -------------------------------------------------------------------------- // Includes // -------------------------------------------------------------------------- @@ -71,12 +71,12 @@ tTimerConfig timerConfig[NUM_HARDWARE_TIMERS]; bool timers_initialised[NUM_HARDWARE_TIMERS] = {false}; -void HAL_timer_start(uint8_t timer_num, uint32_t frequency) { +void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) { - if(!timers_initialised[timer_num]) { + if (!timers_initialised[timer_num]) { switch (timer_num) { case STEP_TIMER_NUM: - //STEPPER TIMER TIM5 //use a 32bit timer + //STEPPER TIMER TIM5 //use a 32bit timer __HAL_RCC_TIM5_CLK_ENABLE(); timerConfig[0].timerdef.Instance = TIM5; timerConfig[0].timerdef.Init.Prescaler = (STEPPER_TIMER_PRESCALE); @@ -92,8 +92,8 @@ void HAL_timer_start(uint8_t timer_num, uint32_t frequency) { //TEMP TIMER TIM7 // any available 16bit Timer (1 already used for PWM) __HAL_RCC_TIM7_CLK_ENABLE(); timerConfig[1].timerdef.Instance = TIM7; - timerConfig[1].timerdef.Init.Prescaler = (TEMP_TIMER_PRESCALE); - timerConfig[1].timerdef.Init.CounterMode = TIM_COUNTERMODE_UP; + timerConfig[1].timerdef.Init.Prescaler = (TEMP_TIMER_PRESCALE); + timerConfig[1].timerdef.Init.CounterMode = TIM_COUNTERMODE_UP; timerConfig[1].timerdef.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1; timerConfig[1].IRQ_Id = TIM7_IRQn; timerConfig[1].callback = (uint32_t)TC7_Handler; @@ -103,52 +103,48 @@ void HAL_timer_start(uint8_t timer_num, uint32_t frequency) { timers_initialised[timer_num] = true; } - timerConfig[timer_num].timerdef.Init.Period = ((HAL_TIMER_RATE / timerConfig[timer_num].timerdef.Init.Prescaler) / (frequency)) - 1; + timerConfig[timer_num].timerdef.Init.Period = (((HAL_TIMER_RATE) / timerConfig[timer_num].timerdef.Init.Prescaler) / frequency) - 1; - if(HAL_TIM_Base_Init(&timerConfig[timer_num].timerdef) == HAL_OK ){ + if (HAL_TIM_Base_Init(&timerConfig[timer_num].timerdef) == HAL_OK) HAL_TIM_Base_Start_IT(&timerConfig[timer_num].timerdef); - } - } //forward the interrupt -extern "C" void TIM5_IRQHandler() -{ - ((void(*)(void))timerConfig[0].callback)(); +extern "C" void TIM5_IRQHandler() { + ((void(*)(void))timerConfig[0].callback)(); } -extern "C" void TIM7_IRQHandler() -{ - ((void(*)(void))timerConfig[1].callback)(); +extern "C" void TIM7_IRQHandler() { + ((void(*)(void))timerConfig[1].callback)(); } -void HAL_timer_set_count (uint8_t timer_num, uint32_t count) { +void HAL_timer_set_count(const uint8_t timer_num, const uint32_t count) { __HAL_TIM_SetAutoreload(&timerConfig[timer_num].timerdef, count); } -void HAL_timer_set_current_count (uint8_t timer_num, uint32_t count) { +void HAL_timer_set_current_count(const uint8_t timer_num, const uint32_t count) { __HAL_TIM_SetAutoreload(&timerConfig[timer_num].timerdef, count); } -void HAL_timer_enable_interrupt (uint8_t timer_num) { +void HAL_timer_enable_interrupt(const uint8_t timer_num) { HAL_NVIC_EnableIRQ(timerConfig[timer_num].IRQ_Id); } -void HAL_timer_disable_interrupt (uint8_t timer_num) { +void HAL_timer_disable_interrupt(const uint8_t timer_num) { HAL_NVIC_DisableIRQ(timerConfig[timer_num].IRQ_Id); } -hal_timer_t HAL_timer_get_count (uint8_t timer_num) { +hal_timer_t HAL_timer_get_count(const uint8_t timer_num) { return __HAL_TIM_GetAutoreload(&timerConfig[timer_num].timerdef); } -uint32_t HAL_timer_get_current_count(uint8_t timer_num) { +uint32_t HAL_timer_get_current_count(const uint8_t timer_num) { return __HAL_TIM_GetCounter(&timerConfig[timer_num].timerdef); } -void HAL_timer_isr_prologue (uint8_t timer_num) { +void HAL_timer_isr_prologue(const uint8_t timer_num) { if (__HAL_TIM_GET_FLAG(&timerConfig[timer_num].timerdef, TIM_FLAG_UPDATE) == SET) { __HAL_TIM_CLEAR_FLAG(&timerConfig[timer_num].timerdef, TIM_FLAG_UPDATE); } } -#endif \ No newline at end of file +#endif // STM32F7 diff --git a/Marlin/src/HAL/HAL_STM32F7/HAL_timers_STM32F7.h b/Marlin/src/HAL/HAL_STM32F7/HAL_timers_STM32F7.h index c77866c5af..909df99abe 100644 --- a/Marlin/src/HAL/HAL_STM32F7/HAL_timers_STM32F7.h +++ b/Marlin/src/HAL/HAL_STM32F7/HAL_timers_STM32F7.h @@ -20,8 +20,6 @@ * */ - - #ifndef _HAL_TIMERS_STM32F7_H #define _HAL_TIMERS_STM32F7_H @@ -35,16 +33,15 @@ // Defines // -------------------------------------------------------------------------- - #define FORCE_INLINE __attribute__((always_inline)) inline -#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? -#define HAL_TIMER_TYPE_MAX 0xFFFF +#define hal_timer_t uint32_t // TODO: One is 16-bit, one 32-bit - does this need to be checked? +#define HAL_TIMER_TYPE_MAX 0xFFFF #define STEP_TIMER_NUM 0 // index of timer to use for stepper #define TEMP_TIMER_NUM 1 // index of timer to use for temperature -#define HAL_TIMER_RATE (HAL_RCC_GetSysClockFreq()/2) // frequency of timer peripherals +#define HAL_TIMER_RATE (HAL_RCC_GetSysClockFreq() / 2) // frequency of timer peripherals #define STEPPER_TIMER_PRESCALE 54 // was 40,prescaler for setting stepper timer, 2Mhz #define HAL_STEPPER_TIMER_RATE (HAL_TIMER_RATE / STEPPER_TIMER_PRESCALE) // frequency of stepper timer (HAL_TIMER_RATE / STEPPER_TIMER_PRESCALE) #define HAL_TICKS_PER_US ((HAL_STEPPER_TIMER_RATE) / 1000000) // stepper timer ticks per us @@ -55,11 +52,11 @@ #define TEMP_TIMER_PRESCALE 1000 // prescaler for setting Temp timer, 72Khz #define TEMP_TIMER_FREQUENCY 1000 // temperature interrupt frequency -#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt (STEP_TIMER_NUM) -#define DISABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_disable_interrupt (STEP_TIMER_NUM) +#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(STEP_TIMER_NUM) +#define DISABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_disable_interrupt(STEP_TIMER_NUM) -#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt (TEMP_TIMER_NUM) -#define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt (TEMP_TIMER_NUM) +#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(TEMP_TIMER_NUM) +#define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(TEMP_TIMER_NUM) #define HAL_ENABLE_ISRs() do { if (thermalManager.in_temp_isr)DISABLE_TEMPERATURE_INTERRUPT(); else ENABLE_TEMPERATURE_INTERRUPT(); ENABLE_STEPPER_DRIVER_INTERRUPT(); } while(0) // TODO change this @@ -86,27 +83,23 @@ typedef struct { //extern const tTimerConfig timerConfig[]; - - // -------------------------------------------------------------------------- // Public functions // -------------------------------------------------------------------------- -void HAL_timer_start (uint8_t timer_num, uint32_t frequency); -void HAL_timer_enable_interrupt(uint8_t timer_num); -void HAL_timer_disable_interrupt(uint8_t timer_num); - - +void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency); +void HAL_timer_enable_interrupt(const uint8_t timer_num); +void HAL_timer_disable_interrupt(const uint8_t timer_num); -void HAL_timer_set_count (uint8_t timer_num, uint32_t count); -hal_timer_t HAL_timer_get_count (uint8_t timer_num); -uint32_t HAL_timer_get_current_count(uint8_t timer_num); +void HAL_timer_set_count(const uint8_t timer_num, const uint32_t count); +hal_timer_t HAL_timer_get_count(const uint8_t timer_num); +uint32_t HAL_timer_get_current_count(const uint8_t timer_num); -void HAL_timer_set_current_count (uint8_t timer_num, uint32_t count); //New +void HAL_timer_set_current_count(const uint8_t timer_num, const uint32_t count); // New /*FORCE_INLINE static void HAL_timer_set_current_count(const uint8_t timer_num, const hal_timer_t count) { // To do ?? }*/ -void HAL_timer_isr_prologue (uint8_t timer_num); +void HAL_timer_isr_prologue(const uint8_t timer_num); #endif // _HAL_TIMERS_STM32F7_H diff --git a/Marlin/src/HAL/HAL_STM32F7/TMC2660.cpp b/Marlin/src/HAL/HAL_STM32F7/TMC2660.cpp index 20976d6096..856a475491 100644 --- a/Marlin/src/HAL/HAL_STM32F7/TMC2660.cpp +++ b/Marlin/src/HAL/HAL_STM32F7/TMC2660.cpp @@ -1,28 +1,28 @@ -/* - TMC26XStepper.cpp - - TMC26X Stepper library for Wiring/Arduino - - based on the stepper library by Tom Igoe, et. al. - - Copyright (c) 2011, Interactive Matter, Marcus Nowotny - - Permission is hereby granted, free of charge, to any person obtaining a copy - of this software and associated documentation files (the "Software"), to deal - in the Software without restriction, including without limitation the rights - to use, copy, modify, merge, publish, distribute, sublicense, and/or sell - copies of the Software, and to permit persons to whom the Software is - furnished to do so, subject to the following conditions: - - The above copyright notice and this permission notice shall be included in - all copies or substantial portions of the Software. - - THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR - IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, - FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE - AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER - LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, - OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN - THE SOFTWARE. - +/** + * TMC26XStepper.cpp - - TMC26X Stepper library for Wiring/Arduino + * + * based on the stepper library by Tom Igoe, et. al. + * + * Copyright (c) 2011, Interactive Matter, Marcus Nowotny + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN + * THE SOFTWARE. + * */ //#include "Arduino.h" @@ -120,916 +120,812 @@ SPIClass SPI_6(SPI6, SPI6_MOSI_PIN, SPI6_MISO_PIN, SPI6_SCK_PIN); unsigned char current_scaling = 0; -/* +/** * Constructor * number_of_steps - the steps per rotation * cs_pin - the SPI client select pin * dir_pin - the pin where the direction pin is connected * step_pin - the pin where the step pin is connected */ -TMC26XStepper::TMC26XStepper(int number_of_steps, int cs_pin, int dir_pin, int step_pin, unsigned int current, unsigned int resistor) -{ - //we are not started yet - started=false; - //by default cool step is not enabled - cool_step_enabled=false; - - //save the pins for later use - this->cs_pin=cs_pin; - this->dir_pin=dir_pin; - this->step_pin = step_pin; - - //store the current sense resistor value for later use - this->resistor = resistor; - - //initizalize our status values - this->steps_left = 0; - this->direction = 0; - - //initialize register values - driver_control_register_value=DRIVER_CONTROL_REGISTER | INITIAL_MICROSTEPPING; - chopper_config_register=CHOPPER_CONFIG_REGISTER; - - //setting the default register values - driver_control_register_value=DRIVER_CONTROL_REGISTER|INITIAL_MICROSTEPPING; - microsteps = (1 << INITIAL_MICROSTEPPING); - chopper_config_register=CHOPPER_CONFIG_REGISTER; - cool_step_register_value=COOL_STEP_REGISTER; - stall_guard2_current_register_value=STALL_GUARD2_LOAD_MEASURE_REGISTER; - driver_configuration_register_value = DRIVER_CONFIG_REGISTER | READ_STALL_GUARD_READING; - - //set the current - setCurrent(current); - //set to a conservative start value - setConstantOffTimeChopper(7, 54, 13,12,1); - //set a nice microstepping value - setMicrosteps(DEFAULT_MICROSTEPPING_VALUE); - //save the number of steps - this->number_of_steps = number_of_steps; +TMC26XStepper::TMC26XStepper(int number_of_steps, int cs_pin, int dir_pin, int step_pin, unsigned int current, unsigned int resistor) { + // We are not started yet + started = false; + + // By default cool step is not enabled + cool_step_enabled = false; + + // Save the pins for later use + this->cs_pin = cs_pin; + this->dir_pin = dir_pin; + this->step_pin = step_pin; + + // Store the current sense resistor value for later use + this->resistor = resistor; + + // Initizalize our status values + this->steps_left = 0; + this->direction = 0; + + // Initialize register values + driver_control_register_value = DRIVER_CONTROL_REGISTER | INITIAL_MICROSTEPPING; + chopper_config_register = CHOPPER_CONFIG_REGISTER; + + // Setting the default register values + driver_control_register_value = DRIVER_CONTROL_REGISTER|INITIAL_MICROSTEPPING; + microsteps = _BV(INITIAL_MICROSTEPPING); + chopper_config_register = CHOPPER_CONFIG_REGISTER; + cool_step_register_value = COOL_STEP_REGISTER; + stall_guard2_current_register_value = STALL_GUARD2_LOAD_MEASURE_REGISTER; + driver_configuration_register_value = DRIVER_CONFIG_REGISTER | READ_STALL_GUARD_READING; + + // Set the current + setCurrent(current); + // Set to a conservative start value + setConstantOffTimeChopper(7, 54, 13,12,1); + // Set a nice microstepping value + setMicrosteps(DEFAULT_MICROSTEPPING_VALUE); + // Save the number of steps + this->number_of_steps = number_of_steps; } -/* +/** * start & configure the stepper driver * just must be called. */ void TMC26XStepper::start() { -#ifdef TMC_DEBUG1 - SERIAL_ECHOPGM("\n TMC26X stepper library \n"); - SERIAL_ECHOPAIR("\n CS pin: ",cs_pin); - SERIAL_ECHOPAIR("\n DIR pin: ",dir_pin); - SERIAL_ECHOPAIR("\n STEP pin: ", step_pin); - SERIAL_PRINTF("\n current scaling: %d", current_scaling); - SERIAL_PRINTF("\n Resistor: %d", resistor); - //SERIAL_PRINTF("\n current: %d", current); - SERIAL_ECHOPAIR("\n Microstepping: ", microsteps); - -#endif - - //set the pins as output & its initial value - pinMode(step_pin, OUTPUT); - pinMode(dir_pin, OUTPUT); - pinMode(cs_pin, OUTPUT); - //pinMode(STEPPER_ENABLE_PIN, OUTPUT); - digitalWrite(step_pin, LOW); - digitalWrite(dir_pin, LOW); - digitalWrite(cs_pin, HIGH); - - STEPPER_SPI.begin(); - STEPPER_SPI.beginTransaction(SPISettings(4000000, MSBFIRST, SPI_MODE3)); - - //set the initial values - send262(driver_control_register_value); - send262(chopper_config_register); - send262(cool_step_register_value); - send262(stall_guard2_current_register_value); - send262(driver_configuration_register_value); - - //save that we are in running mode - started=true; -} - -/* - Mark the driver as unstarted to be able to start it again + #ifdef TMC_DEBUG1 + SERIAL_ECHOPGM("\n TMC26X stepper library \n"); + SERIAL_ECHOPAIR("\n CS pin: ", cs_pin); + SERIAL_ECHOPAIR("\n DIR pin: ", dir_pin); + SERIAL_ECHOPAIR("\n STEP pin: ", step_pin); + SERIAL_PRINTF("\n current scaling: %d", current_scaling); + SERIAL_PRINTF("\n Resistor: %d", resistor); + //SERIAL_PRINTF("\n current: %d", current); + SERIAL_ECHOPAIR("\n Microstepping: ", microsteps); + #endif + + //set the pins as output & its initial value + pinMode(step_pin, OUTPUT); + pinMode(dir_pin, OUTPUT); + pinMode(cs_pin, OUTPUT); + //pinMode(STEPPER_ENABLE_PIN, OUTPUT); + digitalWrite(step_pin, LOW); + digitalWrite(dir_pin, LOW); + digitalWrite(cs_pin, HIGH); + + STEPPER_SPI.begin(); + STEPPER_SPI.beginTransaction(SPISettings(4000000, MSBFIRST, SPI_MODE3)); + + //set the initial values + send262(driver_control_register_value); + send262(chopper_config_register); + send262(cool_step_register_value); + send262(stall_guard2_current_register_value); + send262(driver_configuration_register_value); + + //save that we are in running mode + started = true; +} + +/** + * Mark the driver as unstarted to be able to start it again */ -void TMC26XStepper::un_start() { - started=false; -} +void TMC26XStepper::un_start() { started = false; } -/* - Sets the speed in revs per minute - -*/ -void TMC26XStepper::setSpeed(unsigned int whatSpeed) -{ +/** + * Sets the speed in revs per minute + */ +void TMC26XStepper::setSpeed(unsigned int whatSpeed) { this->speed = whatSpeed; - this->step_delay = (60UL * 1000UL * 1000UL) / ((unsigned long)this->number_of_steps * (unsigned long)whatSpeed * (unsigned long)this->microsteps); -#ifdef TMC_DEBUG0 //crashes + this->step_delay = 60UL * sq(1000UL) / ((unsigned long)this->number_of_steps * (unsigned long)whatSpeed * (unsigned long)this->microsteps); + #ifdef TMC_DEBUG0 // crashes //SERIAL_PRINTF("Step delay in micros: "); - SERIAL_ECHOPAIR("\nStep delay in micros: ",this->step_delay); -#endif - //update the next step time - this->next_step_time = this->last_step_time+this->step_delay; - + SERIAL_ECHOPAIR("\nStep delay in micros: ", this->step_delay); + #endif + // Update the next step time + this->next_step_time = this->last_step_time + this->step_delay; } -unsigned int TMC26XStepper::getSpeed(void) { - return this->speed; -} +unsigned int TMC26XStepper::getSpeed(void) { return this->speed; } -/* - Moves the motor steps_to_move steps. If the number is negative, - the motor moves in the reverse direction. +/** + * Moves the motor steps_to_move steps. + * Negative indicates the reverse direction. */ -char TMC26XStepper::step(int steps_to_move) -{ - if (this->steps_left==0) { - this->steps_left = abs(steps_to_move); // how many steps to take - - // determine direction based on whether steps_to_mode is + or -: - if (steps_to_move > 0) { - this->direction = 1; - } else if (steps_to_move < 0) { - this->direction = 0; - } - return 0; - } else { - return -1; - } +char TMC26XStepper::step(int steps_to_move) { + if (this->steps_left == 0) { + this->steps_left = abs(steps_to_move); // how many steps to take + + // determine direction based on whether steps_to_move is + or -: + if (steps_to_move > 0) + this->direction = 1; + else if (steps_to_move < 0) + this->direction = 0; + return 0; + } + return -1; } char TMC26XStepper::move(void) { // decrement the number of steps, moving one step each time: - if(this->steps_left>0) { - unsigned long time = micros(); - // move only if the appropriate delay has passed: - - // rem if (time >= this->next_step_time) { - - if(abs(time - this->last_step_time) > this->step_delay) { - - // increment or decrement the step number, - // depending on direction: - if (this->direction == 1) { - digitalWrite(step_pin, HIGH); - } else { - digitalWrite(dir_pin, HIGH); - digitalWrite(step_pin, HIGH); - } - // get the timeStamp of when you stepped: - this->last_step_time = time; - this->next_step_time = time+this->step_delay; - // decrement the steps left: - steps_left--; - //disable the step & dir pins - digitalWrite(step_pin, LOW); - digitalWrite(dir_pin, LOW); - } - return -1; - } - return 0; + if (this->steps_left > 0) { + unsigned long time = micros(); + // move only if the appropriate delay has passed: + + // rem if (time >= this->next_step_time) { + + if (abs(time - this->last_step_time) > this->step_delay) { + // increment or decrement the step number, + // depending on direction: + if (this->direction == 1) + digitalWrite(step_pin, HIGH); + else { + digitalWrite(dir_pin, HIGH); + digitalWrite(step_pin, HIGH); + } + // get the timeStamp of when you stepped: + this->last_step_time = time; + this->next_step_time = time + this->step_delay; + // decrement the steps left: + steps_left--; + //disable the step & dir pins + digitalWrite(step_pin, LOW); + digitalWrite(dir_pin, LOW); + } + return -1; + } + return 0; } -char TMC26XStepper::isMoving(void) { - return (this->steps_left>0); -} +char TMC26XStepper::isMoving(void) { return this->steps_left > 0; } -unsigned int TMC26XStepper::getStepsLeft(void) { - return this->steps_left; -} +unsigned int TMC26XStepper::getStepsLeft(void) { return this->steps_left; } char TMC26XStepper::stop(void) { - //note to self if the motor is currently moving - char state = isMoving(); - //stop the motor - this->steps_left = 0; - this->direction = 0; - //return if it was moving - return state; + //note to self if the motor is currently moving + char state = isMoving(); + //stop the motor + this->steps_left = 0; + this->direction = 0; + //return if it was moving + return state; } void TMC26XStepper::setCurrent(unsigned int current) { - unsigned char current_scaling = 0; - //calculate the current scaling from the max current setting (in mA) - double mASetting = (double)current; - double resistor_value = (double) this->resistor; - // remove vesense flag - this->driver_configuration_register_value &= ~(VSENSE); - //this is derrived from I=(cs+1)/32*(Vsense/Rsense) - //leading to cs = CS = 32*R*I/V (with V = 0,31V oder 0,165V and I = 1000*current) - //with Rsense=0,15 - //for vsense = 0,310V (VSENSE not set) - //or vsense = 0,165V (VSENSE set) - current_scaling = (byte)((resistor_value*mASetting*32.0/(0.31*1000.0*1000.0))-0.5); //theoretically - 1.0 for better rounding it is 0.5 - - //check if the current scalingis too low - if (current_scaling<16) { - //set the csense bit to get a use half the sense voltage (to support lower motor currents) - this->driver_configuration_register_value |= VSENSE; - //and recalculate the current setting - current_scaling = (byte)((resistor_value*mASetting*32.0/(0.165*1000.0*1000.0))-0.5); //theoretically - 1.0 for better rounding it is 0.5 -#ifdef TMC_DEBUG0 //crashes - //SERIAL_PRINTF("CS (Vsense=1): "); - SERIAL_ECHOPAIR("\nCS (Vsense=1): ",current_scaling); - } else { + unsigned char current_scaling = 0; + //calculate the current scaling from the max current setting (in mA) + double mASetting = (double)current, + resistor_value = (double)this->resistor; + // remove vsense flag + this->driver_configuration_register_value &= ~(VSENSE); + // Derived from I = (cs + 1) / 32 * (Vsense / Rsense) + // leading to cs = 32 * R * I / V (with V = 0,31V oder 0,165V and I = 1000 * current) + // with Rsense = 0,15 + // for vsense = 0,310V (VSENSE not set) + // or vsense = 0,165V (VSENSE set) + current_scaling = (byte)((resistor_value * mASetting * 32.0 / (0.31 * sq(1000.0))) - 0.5); //theoretically - 1.0 for better rounding it is 0.5 + + // Check if the current scalingis too low + if (current_scaling < 16) { + // Set the csense bit to get a use half the sense voltage (to support lower motor currents) + this->driver_configuration_register_value |= VSENSE; + // and recalculate the current setting + current_scaling = (byte)((resistor_value * mASetting * 32.0 / (0.165 * sq(1000.0))) - 0.5); //theoretically - 1.0 for better rounding it is 0.5 + #ifdef TMC_DEBUG0 // crashes + //SERIAL_PRINTF("CS (Vsense=1): "); + SERIAL_ECHOPAIR("\nCS (Vsense=1): ",current_scaling); + } else { //SERIAL_PRINTF("CS: "); SERIAL_ECHOPAIR("\nCS: ", current_scaling); -#endif - } + #endif + } + + // do some sanity checks + NOMORE(current_scaling, 31); - //do some sanity checks - if (current_scaling>31) { - current_scaling=31; - } - //delete the old value - stall_guard2_current_register_value &= ~(CURRENT_SCALING_PATTERN); - //set the new current scaling - stall_guard2_current_register_value |= current_scaling; - //if started we directly send it to the motor - if (started) { - send262(driver_configuration_register_value); - send262(stall_guard2_current_register_value); - } + // delete the old value + stall_guard2_current_register_value &= ~(CURRENT_SCALING_PATTERN); + // set the new current scaling + stall_guard2_current_register_value |= current_scaling; + // if started we directly send it to the motor + if (started) { + send262(driver_configuration_register_value); + send262(stall_guard2_current_register_value); + } } unsigned int TMC26XStepper::getCurrent(void) { - //we calculate the current according to the datasheet to be on the safe side - //this is not the fastest but the most accurate and illustrative way - double result = (double)(stall_guard2_current_register_value & CURRENT_SCALING_PATTERN); - double resistor_value = (double)this->resistor; - double voltage = (driver_configuration_register_value & VSENSE)? 0.165:0.31; - result = (result+1.0)/32.0*voltage/resistor_value*1000.0*1000.0; - return (unsigned int)result; + // Calculate the current according to the datasheet to be on the safe side. + // This is not the fastest but the most accurate and illustrative way. + double result = (double)(stall_guard2_current_register_value & CURRENT_SCALING_PATTERN), + resistor_value = (double)this->resistor, + voltage = (driver_configuration_register_value & VSENSE) ? 0.165 : 0.31; + result = (result + 1.0) / 32.0 * voltage / resistor_value * sq(1000.0); + return (unsigned int)result; } void TMC26XStepper::setStallGuardThreshold(char stall_guard_threshold, char stall_guard_filter_enabled) { - if (stall_guard_threshold<-64) { - stall_guard_threshold = -64; - //We just have 5 bits - } else if (stall_guard_threshold > 63) { - stall_guard_threshold = 63; - } - //add trim down to 7 bits - stall_guard_threshold &=0x7f; - //delete old stall guard settings - stall_guard2_current_register_value &= ~(STALL_GUARD_CONFIG_PATTERN); - if (stall_guard_filter_enabled) { - stall_guard2_current_register_value |= STALL_GUARD_FILTER_ENABLED; - } - //Set the new stall guard threshold - stall_guard2_current_register_value |= (((unsigned long)stall_guard_threshold << 8) & STALL_GUARD_CONFIG_PATTERN); - //if started we directly send it to the motor - if (started) { - send262(stall_guard2_current_register_value); - } + // We just have 5 bits + LIMIT(stall_guard_threshold, -64, 63); + + // Add trim down to 7 bits + stall_guard_threshold &= 0x7F; + // Delete old stall guard settings + stall_guard2_current_register_value &= ~(STALL_GUARD_CONFIG_PATTERN); + if (stall_guard_filter_enabled) + stall_guard2_current_register_value |= STALL_GUARD_FILTER_ENABLED; + + // Set the new stall guard threshold + stall_guard2_current_register_value |= (((unsigned long)stall_guard_threshold << 8) & STALL_GUARD_CONFIG_PATTERN); + // If started we directly send it to the motor + if (started) send262(stall_guard2_current_register_value); } char TMC26XStepper::getStallGuardThreshold(void) { - unsigned long stall_guard_threshold = stall_guard2_current_register_value & STALL_GUARD_VALUE_PATTERN; - //shift it down to bit 0 - stall_guard_threshold >>=8; - //convert the value to an int to correctly handle the negative numbers - char result = stall_guard_threshold; - //check if it is negative and fill it up with leading 1 for proper negative number representation - //rem if (result & _BV(6)) { - - if (result & (1 << (6))) { - - result |= 0xC0; - } - return result; + unsigned long stall_guard_threshold = stall_guard2_current_register_value & STALL_GUARD_VALUE_PATTERN; + //shift it down to bit 0 + stall_guard_threshold >>= 8; + //convert the value to an int to correctly handle the negative numbers + char result = stall_guard_threshold; + //check if it is negative and fill it up with leading 1 for proper negative number representation + //rem if (result & _BV(6)) { + + if (TEST(result, 6)) result |= 0xC0; + return result; } char TMC26XStepper::getStallGuardFilter(void) { - if (stall_guard2_current_register_value & STALL_GUARD_FILTER_ENABLED) { - return -1; - } else { - return 0; - } + if (stall_guard2_current_register_value & STALL_GUARD_FILTER_ENABLED) + return -1; + return 0; } -/* + +/** * Set the number of microsteps per step. * 0,2,4,8,16,32,64,128,256 is supported * any value in between will be mapped to the next smaller value * 0 and 1 set the motor in full step mode */ void TMC26XStepper::setMicrosteps(int number_of_steps) { - long setting_pattern; - //poor mans log - if (number_of_steps>=256) { - setting_pattern=0; - microsteps=256; - } else if (number_of_steps>=128) { - setting_pattern=1; - microsteps=128; - } else if (number_of_steps>=64) { - setting_pattern=2; - microsteps=64; - } else if (number_of_steps>=32) { - setting_pattern=3; - microsteps=32; - } else if (number_of_steps>=16) { - setting_pattern=4; - microsteps=16; - } else if (number_of_steps>=8) { - setting_pattern=5; - microsteps=8; - } else if (number_of_steps>=4) { - setting_pattern=6; - microsteps=4; - } else if (number_of_steps>=2) { - setting_pattern=7; - microsteps=2; + long setting_pattern; + //poor mans log + if (number_of_steps >= 256) { + setting_pattern = 0; + microsteps = 256; + } + else if (number_of_steps >= 128) { + setting_pattern = 1; + microsteps = 128; + } + else if (number_of_steps >= 64) { + setting_pattern = 2; + microsteps = 64; + } + else if (number_of_steps >= 32) { + setting_pattern = 3; + microsteps = 32; + } + else if (number_of_steps >= 16) { + setting_pattern = 4; + microsteps = 16; + } + else if (number_of_steps >= 8) { + setting_pattern = 5; + microsteps = 8; + } + else if (number_of_steps >= 4) { + setting_pattern = 6; + microsteps = 4; + } + else if (number_of_steps >= 2) { + setting_pattern = 7; + microsteps = 2; //1 and 0 lead to full step - } else if (number_of_steps<=1) { - setting_pattern=8; - microsteps=1; - } -#ifdef TMC_DEBUG0 //crashes - //SERIAL_PRINTF("Microstepping: "); - SERIAL_ECHOPAIR("\n Microstepping: ", microsteps); -#endif - //delete the old value - this->driver_control_register_value &=0xFFFF0ul; - //set the new value - this->driver_control_register_value |=setting_pattern; - - //if started we directly send it to the motor - if (started) { - send262(driver_control_register_value); - } - //recalculate the stepping delay by simply setting the speed again - this->setSpeed(this->speed); -} - -/* + } + else if (number_of_steps <= 1) { + setting_pattern = 8; + microsteps = 1; + } + #ifdef TMC_DEBUG0 // crashes + //SERIAL_PRINTF("Microstepping: "); + SERIAL_ECHOPAIR("\n Microstepping: ", microsteps); + #endif + // Delete the old value + this->driver_control_register_value &= 0xFFFF0UL; + // Set the new value + this->driver_control_register_value |= setting_pattern; + + // If started we directly send it to the motor + if (started) send262(driver_control_register_value); + + // Recalculate the stepping delay by simply setting the speed again + this->setSpeed(this->speed); +} + +/** * returns the effective number of microsteps at the moment */ -int TMC26XStepper::getMicrosteps(void) { - return microsteps; -} +int TMC26XStepper::getMicrosteps(void) { return microsteps } -/* - * 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. - * 2...15: off time setting +/** + * 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. + * 2...15: off time setting * * 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 - * 0: min. setting 3: max. setting + * 0: min. setting 3: max. setting * * fast_decay_time_setting: Fast decay time setting. With CHM=1, these bits control the portion of fast decay for each chopper cycle. - * 0: slow decay only - * 1...15: duration of fast decay phase + * 0: slow decay only + * 1...15: duration of fast decay phase * - * sine_wave_offset: Sine wave offset. With CHM=1, these bits control the sine wave offset. + * sine_wave_offset: Sine wave offset. With CHM=1, these bits control the sine wave offset. * A positive offset corrects for zero crossing error. - * -3..-1: negative offset 0: no offset 1...12: positive offset + * -3..-1: negative offset 0: no offset 1...12: positive offset * - * use_current_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 + * use_current_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. - * 1: enable comparator termination of fast decay cycle - * 0: end by time only + * 1: enable comparator termination of fast decay cycle + * 0: end by time only */ void TMC26XStepper::setConstantOffTimeChopper(char constant_off_time, char blank_time, char fast_decay_time_setting, char sine_wave_offset, unsigned char use_current_comparator) { - //perform some sanity checks - if (constant_off_time<2) { - constant_off_time=2; - } else if (constant_off_time>15) { - constant_off_time=15; - } - //save the constant off time - this->constant_off_time = constant_off_time; - char blank_value; - //calculate the value acc to the clock cycles - if (blank_time>=54) { - blank_value=3; - } else if (blank_time>=36) { - blank_value=2; - } else if (blank_time>=24) { - blank_value=1; - } else { - blank_value=0; - } - if (fast_decay_time_setting<0) { - fast_decay_time_setting=0; - } else if (fast_decay_time_setting>15) { - fast_decay_time_setting=15; - } - if (sine_wave_offset < -3) { - sine_wave_offset = -3; - } else if (sine_wave_offset>12) { - sine_wave_offset = 12; - } - //shift the sine_wave_offset - sine_wave_offset +=3; - - //calculate the register setting - //first of all delete all the values for this - chopper_config_register &= ~((1<<12) | BLANK_TIMING_PATTERN | HYSTERESIS_DECREMENT_PATTERN | HYSTERESIS_LOW_VALUE_PATTERN | HYSTERESIS_START_VALUE_PATTERN | T_OFF_TIMING_PATERN); - //set the constant off pattern - chopper_config_register |= CHOPPER_MODE_T_OFF_FAST_DECAY; - //set the blank timing value - chopper_config_register |= ((unsigned long)blank_value) << BLANK_TIMING_SHIFT; - //setting the constant off time - chopper_config_register |= constant_off_time; - //set the fast decay time - //set msb - chopper_config_register |= (((unsigned long)(fast_decay_time_setting & 0x8))<constant_off_time = constant_off_time; + + // Calculate the value acc to the clock cycles + const char blank_value = blank_time >= 54 ? 3 : + blank_time >= 36 ? 2 : + blank_time >= 24 ? 1 : 0; + + LIMIT(fast_decay_time_setting, 0, 15); + LIMIT(sine_wave_offset, -3, 12); + + // Shift the sine_wave_offset + sine_wave_offset += 3; + + // Calculate the register setting + // First of all delete all the values for this + chopper_config_register &= ~(_BV(12) | BLANK_TIMING_PATTERN | HYSTERESIS_DECREMENT_PATTERN | HYSTERESIS_LOW_VALUE_PATTERN | HYSTERESIS_START_VALUE_PATTERN | T_OFF_TIMING_PATERN); + // Set the constant off pattern + chopper_config_register |= CHOPPER_MODE_T_OFF_FAST_DECAY; + // Set the blank timing value + chopper_config_register |= ((unsigned long)blank_value) << BLANK_TIMING_SHIFT; + // Setting the constant off time + chopper_config_register |= constant_off_time; + // Set the fast decay time + // Set msb + chopper_config_register |= (((unsigned long)(fast_decay_time_setting & 0x8)) << HYSTERESIS_DECREMENT_SHIFT); + // Other bits + chopper_config_register |= (((unsigned long)(fast_decay_time_setting & 0x7)) << HYSTERESIS_START_VALUE_SHIFT); + // Set the sine wave offset + chopper_config_register |= (unsigned long)sine_wave_offset << HYSTERESIS_LOW_SHIFT; + // Using the current comparator? + if (!use_current_comparator) + chopper_config_register |= _BV(12); + + // If started we directly send it to the motor + if (started) { + // rem send262(driver_control_register_value); + send262(chopper_config_register); + } +} + +/** + * 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. + * 2...15: off time setting * * 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 - * 0: min. setting 3: max. setting + * 0: min. setting 3: max. setting * * hysteresis_start: Hysteresis start setting. Please remark, that this value is an offset to the hysteresis end value HEND. - * 1...8 + * 1...8 * - * hysteresis_end: Hysteresis end setting. Sets the hysteresis end value after a number of decrements. Decrement interval time is controlled by HDEC. + * hysteresis_end: Hysteresis end setting. Sets the hysteresis end value after a number of decrements. Decrement interval time is controlled by HDEC. * The sum HSTRT+HEND must be <16. At a current setting CS of max. 30 (amplitude reduced to 240), the sum is not limited. - * -3..-1: negative HEND 0: zero HEND 1...12: positive HEND + * -3..-1: negative HEND 0: zero HEND 1...12: positive HEND * * 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: very slow decrement + * 0: fast decrement 3: very slow decrement */ void TMC26XStepper::setSpreadCycleChopper(char constant_off_time, char blank_time, char hysteresis_start, char hysteresis_end, char hysteresis_decrement) { - //perform some sanity checks - if (constant_off_time<2) { - constant_off_time=2; - } else if (constant_off_time>15) { - constant_off_time=15; - } - //save the constant off time - this->constant_off_time = constant_off_time; - char blank_value; - //calculate the value acc to the clock cycles - if (blank_time>=54) { - blank_value=3; - } else if (blank_time>=36) { - blank_value=2; - } else if (blank_time>=24) { - blank_value=1; - } else { - blank_value=0; - } - if (hysteresis_start<1) { - hysteresis_start=1; - } else if (hysteresis_start>8) { - hysteresis_start=8; - } - hysteresis_start--; - - if (hysteresis_end < -3) { - hysteresis_end = -3; - } else if (hysteresis_end>12) { - hysteresis_end = 12; - } - //shift the hysteresis_end - hysteresis_end +=3; - - if (hysteresis_decrement<0) { - hysteresis_decrement=0; - } else if (hysteresis_decrement>3) { - hysteresis_decrement=3; - } - - //first of all delete all the values for this - chopper_config_register &= ~(CHOPPER_MODE_T_OFF_FAST_DECAY | BLANK_TIMING_PATTERN | HYSTERESIS_DECREMENT_PATTERN | HYSTERESIS_LOW_VALUE_PATTERN | HYSTERESIS_START_VALUE_PATTERN | T_OFF_TIMING_PATERN); - - //set the blank timing value - chopper_config_register |= ((unsigned long)blank_value) << BLANK_TIMING_SHIFT; - //setting the constant off time - chopper_config_register |= constant_off_time; - //set the hysteresis_start - chopper_config_register |= ((unsigned long)hysteresis_start) << HYSTERESIS_START_VALUE_SHIFT; - //set the hysteresis end - chopper_config_register |= ((unsigned long)hysteresis_end) << HYSTERESIS_LOW_SHIFT; - //set the hystereis decrement - chopper_config_register |= ((unsigned long)blank_value) << BLANK_TIMING_SHIFT; - //if started we directly send it to the motor - if (started) { - //rem send262(driver_control_register_value); - - send262(chopper_config_register); - } -} - -/* - * In a constant off time chopper scheme both coil choppers run freely, i.e. are not synchronized. - * The frequency of each chopper mainly depends on the coil current and the position dependant motor coil inductivity, thus it depends on the microstep position. - * With some motors a slightly audible beat can occur between the chopper frequencies, especially when they are near to each other. This typically occurs at a - * few microstep positions within each quarter wave. This effect normally is not audible when compared to mechanical noise generated by ball bearings, etc. + // Perform some sanity checks + LIMIT(constant_off_time, 2, 15); + + // Save the constant off time + this->constant_off_time = constant_off_time; + + // Calculate the value acc to the clock cycles + const char blank_value = blank_time >= 54 ? 3 : + blank_time >= 36 ? 2 : + blank_time >= 24 ? 1 : 0; + + LIMIT(hysteresis_start, 1, 8); + hysteresis_start--; + + LIMIT(hysteresis_start, -3, 12); + + // Shift the hysteresis_end + hysteresis_end += 3; + + LIMIT(hysteresis_decrement, 0, 3); + + //first of all delete all the values for this + chopper_config_register &= ~(CHOPPER_MODE_T_OFF_FAST_DECAY | BLANK_TIMING_PATTERN | HYSTERESIS_DECREMENT_PATTERN | HYSTERESIS_LOW_VALUE_PATTERN | HYSTERESIS_START_VALUE_PATTERN | T_OFF_TIMING_PATERN); + + //set the blank timing value + chopper_config_register |= ((unsigned long)blank_value) << BLANK_TIMING_SHIFT; + //setting the constant off time + chopper_config_register |= constant_off_time; + //set the hysteresis_start + chopper_config_register |= ((unsigned long)hysteresis_start) << HYSTERESIS_START_VALUE_SHIFT; + //set the hysteresis end + chopper_config_register |= ((unsigned long)hysteresis_end) << HYSTERESIS_LOW_SHIFT; + //set the hystereis decrement + chopper_config_register |= ((unsigned long)blank_value) << BLANK_TIMING_SHIFT; + //if started we directly send it to the motor + if (started) { + //rem send262(driver_control_register_value); + send262(chopper_config_register); + } +} + +/** + * In a constant off time chopper scheme both coil choppers run freely, i.e. are not synchronized. + * The frequency of each chopper mainly depends on the coil current and the position dependant motor coil inductivity, thus it depends on the microstep position. + * With some motors a slightly audible beat can occur between the chopper frequencies, especially when they are near to each other. This typically occurs at a + * few microstep positions within each quarter wave. This effect normally is not audible when compared to mechanical noise generated by ball bearings, etc. * Further factors which can cause a similar effect are a poor layout of sense resistor GND connection. - * Hint: A common factor, which can cause motor noise, is a bad PCB layout causing coupling of both sense resistor voltages + * Hint: A common factor, which can cause motor noise, is a bad PCB layout causing coupling of both sense resistor voltages * (please refer to sense resistor layout hint in chapter 8.1). - * In order to minimize the effect of a beat between both chopper frequencies, an internal random generator is provided. - * It modulates the slow decay time setting when switched on by the RNDTF bit. The RNDTF feature further spreads the chopper spectrum, + * In order to minimize the effect of a beat between both chopper frequencies, an internal random generator is provided. + * It modulates the slow decay time setting when switched on by the RNDTF bit. The RNDTF feature further spreads the chopper spectrum, * reducing electromagnetic emission on single frequencies. */ void TMC26XStepper::setRandomOffTime(char value) { - if (value) { - chopper_config_register |= RANDOM_TOFF_TIME; - } else { - chopper_config_register &= ~(RANDOM_TOFF_TIME); - } - //if started we directly send it to the motor - if (started) { - //rem send262(driver_control_register_value); - - send262(chopper_config_register); - } -} - -void TMC26XStepper::setCoolStepConfiguration(unsigned int lower_SG_threshold, unsigned int SG_hysteresis, unsigned char current_decrement_step_size, - unsigned char current_increment_step_size, unsigned char lower_current_limit) { - //sanitize the input values - if (lower_SG_threshold>480) { - lower_SG_threshold = 480; - } - //divide by 32 - lower_SG_threshold >>=5; - if (SG_hysteresis>480) { - SG_hysteresis=480; - } - //divide by 32 - SG_hysteresis >>=5; - if (current_decrement_step_size>3) { - current_decrement_step_size=3; - } - if (current_increment_step_size>3) { - current_increment_step_size=3; - } - if (lower_current_limit>1) { - lower_current_limit=1; - } - //store the lower level in order to enable/disable the cool step - this->cool_step_lower_threshold=lower_SG_threshold; - //if cool step is not enabled we delete the lower value to keep it disabled - if (!this->cool_step_enabled) { - lower_SG_threshold=0; - } - //the good news is that we can start with a complete new cool step register value - //and simply set the values in the register - cool_step_register_value = ((unsigned long)lower_SG_threshold) | (((unsigned long)SG_hysteresis)<<8) | (((unsigned long)current_decrement_step_size)<<5) - | (((unsigned long)current_increment_step_size)<<13) | (((unsigned long)lower_current_limit)<<15) - //and of course we have to include the signature of the register - | COOL_STEP_REGISTER; - //SERIAL_PRINTFln(cool_step_register_value,HEX); - if (started) { - send262(cool_step_register_value); - } + if (value) + chopper_config_register |= RANDOM_TOFF_TIME; + else + chopper_config_register &= ~(RANDOM_TOFF_TIME); + //if started we directly send it to the motor + if (started) { + //rem send262(driver_control_register_value); + send262(chopper_config_register); + } +} + +void TMC26XStepper::setCoolStepConfiguration( + unsigned int lower_SG_threshold, + unsigned int SG_hysteresis, + unsigned char current_decrement_step_size, + unsigned char current_increment_step_size, + unsigned char lower_current_limit) +{ + // Sanitize the input values + NOMORE(lower_SG_threshold, 480); + // Divide by 32 + lower_SG_threshold >>= 5; + NOMORE(SG_hysteresis, 480); + // Divide by 32 + SG_hysteresis >>= 5; + NOMORE(current_decrement_step_size, 3); + NOMORE(current_increment_step_size, 3); + NOMORE(lower_current_limit, 1); + + // Store the lower level in order to enable/disable the cool step + this->cool_step_lower_threshold=lower_SG_threshold; + // If cool step is not enabled we delete the lower value to keep it disabled + if (!this->cool_step_enabled) lower_SG_threshold = 0; + // The good news is that we can start with a complete new cool step register value + // And simply set the values in the register + cool_step_register_value = ((unsigned long)lower_SG_threshold) + | (((unsigned long)SG_hysteresis) << 8) + | (((unsigned long)current_decrement_step_size) << 5) + | (((unsigned long)current_increment_step_size) << 13) + | (((unsigned long)lower_current_limit) << 15) + | COOL_STEP_REGISTER; // Register signature + + //SERIAL_PRINTFln(cool_step_register_value,HEX); + if (started) send262(cool_step_register_value); } void TMC26XStepper::setCoolStepEnabled(boolean enabled) { - //simply delete the lower limit to disable the cool step - cool_step_register_value &= ~SE_MIN_PATTERN; - //and set it to the proper value if cool step is to be enabled - if (enabled) { - cool_step_register_value |=this->cool_step_lower_threshold; - } - //and save the enabled status - this->cool_step_enabled = enabled; - //save the register value - if (started) { - send262(cool_step_register_value); - } + // Simply delete the lower limit to disable the cool step + cool_step_register_value &= ~SE_MIN_PATTERN; + // And set it to the proper value if cool step is to be enabled + if (enabled) + cool_step_register_value |= this->cool_step_lower_threshold; + // And save the enabled status + this->cool_step_enabled = enabled; + // Save the register value + if (started) send262(cool_step_register_value); } -boolean TMC26XStepper::isCoolStepEnabled(void) { - return this->cool_step_enabled; -} +boolean TMC26XStepper::isCoolStepEnabled(void) { return this->cool_step_enabled; } unsigned int TMC26XStepper::getCoolStepLowerSgThreshold() { - //we return our internally stored value - in order to provide the correct setting even if cool step is not enabled - return this->cool_step_lower_threshold<<5; + // We return our internally stored value - in order to provide the correct setting even if cool step is not enabled + return this->cool_step_lower_threshold<<5; } unsigned int TMC26XStepper::getCoolStepUpperSgThreshold() { - return (unsigned char)((cool_step_register_value & SE_MAX_PATTERN)>>8)<<5; + return (unsigned char)((cool_step_register_value & SE_MAX_PATTERN) >> 8) << 5; } unsigned char TMC26XStepper::getCoolStepCurrentIncrementSize() { - return (unsigned char)((cool_step_register_value & CURRENT_DOWN_STEP_SPEED_PATTERN)>>13); + return (unsigned char)((cool_step_register_value & CURRENT_DOWN_STEP_SPEED_PATTERN) >> 13); } unsigned char TMC26XStepper::getCoolStepNumberOfSGReadings() { - return (unsigned char)((cool_step_register_value & SE_CURRENT_STEP_WIDTH_PATTERN)>>5); + return (unsigned char)((cool_step_register_value & SE_CURRENT_STEP_WIDTH_PATTERN) >> 5); } unsigned char TMC26XStepper::getCoolStepLowerCurrentLimit() { - return (unsigned char)((cool_step_register_value & MINIMUM_CURRENT_FOURTH)>>15); + return (unsigned char)((cool_step_register_value & MINIMUM_CURRENT_FOURTH) >> 15); } void TMC26XStepper::setEnabled(boolean enabled) { - //delete the t_off in the chopper config to get sure - chopper_config_register &= ~(T_OFF_PATTERN); - if (enabled) { - //and set the t_off time - chopper_config_register |= this->constant_off_time; - } - //if not enabled we don't have to do anything since we already delete t_off from the register - if (started) { - send262(chopper_config_register); - } + //delete the t_off in the chopper config to get sure + chopper_config_register &= ~(T_OFF_PATTERN); + if (enabled) { + //and set the t_off time + chopper_config_register |= this->constant_off_time; + } + //if not enabled we don't have to do anything since we already delete t_off from the register + if (started) send262(chopper_config_register); } -boolean TMC26XStepper::isEnabled() { - if (chopper_config_register & T_OFF_PATTERN) { - return true; - } else { - return false; - } -} +boolean TMC26XStepper::isEnabled() { return !!(chopper_config_register & T_OFF_PATTERN); } -/* - * reads a value from the TMC26X status register. The value is not obtained directly but can then +/** + * reads a value from the TMC26X status register. The value is not obtained directly but can then * be read by the various status routines. * */ void TMC26XStepper::readStatus(char read_value) { - unsigned long old_driver_configuration_register_value = driver_configuration_register_value; - //reset the readout configuration - driver_configuration_register_value &= ~(READ_SELECTION_PATTERN); - //this now equals TMC26X_READOUT_POSITION - so we just have to check the other two options - if (read_value == TMC26X_READOUT_STALLGUARD) { - driver_configuration_register_value |= READ_STALL_GUARD_READING; - } else if (read_value == TMC26X_READOUT_CURRENT) { - driver_configuration_register_value |= READ_STALL_GUARD_AND_COOL_STEP; - } - //all other cases are ignored to prevent funny values - //check if the readout is configured for the value we are interested in - if (driver_configuration_register_value!=old_driver_configuration_register_value) { - //because then we need to write the value twice - one time for configuring, second time to get the value, see below - send262(driver_configuration_register_value); - } - //write the configuration to get the last status - send262(driver_configuration_register_value); + unsigned long old_driver_configuration_register_value = driver_configuration_register_value; + //reset the readout configuration + driver_configuration_register_value &= ~(READ_SELECTION_PATTERN); + //this now equals TMC26X_READOUT_POSITION - so we just have to check the other two options + if (read_value == TMC26X_READOUT_STALLGUARD) + driver_configuration_register_value |= READ_STALL_GUARD_READING; + else if (read_value == TMC26X_READOUT_CURRENT) + driver_configuration_register_value |= READ_STALL_GUARD_AND_COOL_STEP; + + //all other cases are ignored to prevent funny values + //check if the readout is configured for the value we are interested in + if (driver_configuration_register_value != old_driver_configuration_register_value) { + //because then we need to write the value twice - one time for configuring, second time to get the value, see below + send262(driver_configuration_register_value); + } + //write the configuration to get the last status + send262(driver_configuration_register_value); } int TMC26XStepper::getMotorPosition(void) { - //we read it out even if we are not started yet - perhaps it is useful information for somebody - readStatus(TMC26X_READOUT_POSITION); - return getReadoutValue(); + //we read it out even if we are not started yet - perhaps it is useful information for somebody + readStatus(TMC26X_READOUT_POSITION); + return getReadoutValue(); } //reads the stall guard setting from last status //returns -1 if stallguard information is not present int TMC26XStepper::getCurrentStallGuardReading(void) { - //if we don't yet started there cannot be a stall guard value - if (!started) { - return -1; - } - //not time optimal, but solution optiomal: - //first read out the stall guard value - readStatus(TMC26X_READOUT_STALLGUARD); - return getReadoutValue(); + //if we don't yet started there cannot be a stall guard value + if (!started) return -1; + //not time optimal, but solution optiomal: + //first read out the stall guard value + readStatus(TMC26X_READOUT_STALLGUARD); + return getReadoutValue(); } unsigned char TMC26XStepper::getCurrentCSReading(void) { - //if we don't yet started there cannot be a stall guard value - if (!started) { - return 0; - } - //not time optimal, but solution optiomal: - //first read out the stall guard value - readStatus(TMC26X_READOUT_CURRENT); - return (getReadoutValue() & 0x1f); + //if we don't yet started there cannot be a stall guard value + if (!started) return 0; + //not time optimal, but solution optiomal: + //first read out the stall guard value + readStatus(TMC26X_READOUT_CURRENT); + return (getReadoutValue() & 0x1F); } unsigned int TMC26XStepper::getCurrentCurrent(void) { - double result = (double)getCurrentCSReading(); - double resistor_value = (double)this->resistor; - double voltage = (driver_configuration_register_value & VSENSE)? 0.165:0.31; - result = (result+1.0)/32.0*voltage/resistor_value*1000.0*1000.0; + double result = (double)getCurrentCSReading(), + resistor_value = (double)this->resistor, + voltage = (driver_configuration_register_value & VSENSE)? 0.165 : 0.31; + result = (result + 1.0) / 32.0 * voltage / resistor_value * sq(1000.0); return (unsigned int)result; } -/* - return true if the stallguard threshold has been reached -*/ +/** + * Return true if the stallguard threshold has been reached + */ boolean TMC26XStepper::isStallGuardOverThreshold(void) { - if (!this->started) { - return false; - } - return (driver_status_result & STATUS_STALL_GUARD_STATUS); + if (!this->started) return false; + return (driver_status_result & STATUS_STALL_GUARD_STATUS); } -/* - returns if there is any over temperature condition: - OVER_TEMPERATURE_PREWARING if pre warning level has been reached - OVER_TEMPERATURE_SHUTDOWN if the temperature is so hot that the driver is shut down - Any of those levels are not too good. -*/ +/** + * returns if there is any over temperature condition: + * OVER_TEMPERATURE_PREWARING if pre warning level has been reached + * OVER_TEMPERATURE_SHUTDOWN if the temperature is so hot that the driver is shut down + * Any of those levels are not too good. + */ char TMC26XStepper::getOverTemperature(void) { - if (!this->started) { - return 0; - } - if (driver_status_result & STATUS_OVER_TEMPERATURE_SHUTDOWN) { - return TMC26X_OVERTEMPERATURE_SHUTDOWN; - } - if (driver_status_result & STATUS_OVER_TEMPERATURE_WARNING) { - return TMC26X_OVERTEMPERATURE_PREWARING; - } - return 0; + if (!this->started) return 0; + + if (driver_status_result & STATUS_OVER_TEMPERATURE_SHUTDOWN) + return TMC26X_OVERTEMPERATURE_SHUTDOWN; + + if (driver_status_result & STATUS_OVER_TEMPERATURE_WARNING) + return TMC26X_OVERTEMPERATURE_PREWARING; + + return 0; } -//is motor channel A shorted to ground +// Is motor channel A shorted to ground boolean TMC26XStepper::isShortToGroundA(void) { - if (!this->started) { - return false; - } - return (driver_status_result & STATUS_SHORT_TO_GROUND_A); + if (!this->started) return false; + return (driver_status_result & STATUS_SHORT_TO_GROUND_A); } -//is motor channel B shorted to ground +// Is motor channel B shorted to ground boolean TMC26XStepper::isShortToGroundB(void) { - if (!this->started) { - return false; - } - return (driver_status_result & STATUS_SHORT_TO_GROUND_B); + if (!this->started) return false; + return (driver_status_result & STATUS_SHORT_TO_GROUND_B); } -//is motor channel A connected +// Is motor channel A connected boolean TMC26XStepper::isOpenLoadA(void) { - if (!this->started) { - return false; - } - return (driver_status_result & STATUS_OPEN_LOAD_A); + if (!this->started) return false; + return (driver_status_result & STATUS_OPEN_LOAD_A); } -//is motor channel B connected +// Is motor channel B connected boolean TMC26XStepper::isOpenLoadB(void) { - if (!this->started) { - return false; - } - return (driver_status_result & STATUS_OPEN_LOAD_B); + if (!this->started) return false; + return (driver_status_result & STATUS_OPEN_LOAD_B); } -//is chopper inactive since 2^20 clock cycles - defaults to ~0,08s +// Is chopper inactive since 2^20 clock cycles - defaults to ~0,08s boolean TMC26XStepper::isStandStill(void) { - if (!this->started) { - return false; - } - return (driver_status_result & STATUS_STAND_STILL); + if (!this->started) return false; + return (driver_status_result & STATUS_STAND_STILL); } //is chopper inactive since 2^20 clock cycles - defaults to ~0,08s boolean TMC26XStepper::isStallGuardReached(void) { - if (!this->started) { - return false; - } - return (driver_status_result & STATUS_STALL_GUARD_STATUS); + if (!this->started) return false; + return (driver_status_result & STATUS_STALL_GUARD_STATUS); } //reads the stall guard setting from last status //returns -1 if stallguard inforamtion is not present int TMC26XStepper::getReadoutValue(void) { - return (int)(driver_status_result >> 10); + return (int)(driver_status_result >> 10); } -int TMC26XStepper::getResistor() { - return this->resistor; -} +int TMC26XStepper::getResistor() { return this->resistor; } boolean TMC26XStepper::isCurrentScalingHalfed() { - if (this->driver_configuration_register_value & VSENSE) { - return true; - } else { - return false; - } + return !!(this->driver_configuration_register_value & VSENSE); } -/* - version() returns the version of the library: +/** + * version() returns the version of the library: */ -int TMC26XStepper::version(void) -{ - return 1; -} +int TMC26XStepper::version(void) { return 1; } void TMC26XStepper::debugLastStatus() { -#ifdef TMC_DEBUG1 -if (this->started) { - if (this->getOverTemperature()&TMC26X_OVERTEMPERATURE_PREWARING) { - SERIAL_ECHOLNPGM("\n WARNING: Overtemperature Prewarning!"); - } else if (this->getOverTemperature()&TMC26X_OVERTEMPERATURE_SHUTDOWN) { - SERIAL_ECHOLNPGM("\n ERROR: Overtemperature Shutdown!"); - } - if (this->isShortToGroundA()) { - SERIAL_ECHOLNPGM("\n ERROR: SHORT to ground on channel A!"); - } - if (this->isShortToGroundB()) { - SERIAL_ECHOLNPGM("\n ERROR: SHORT to ground on channel B!"); - } - if (this->isOpenLoadA()) { - SERIAL_ECHOLNPGM("\n ERROR: Channel A seems to be unconnected!"); - } - if (this->isOpenLoadB()) { - SERIAL_ECHOLNPGM("\n ERROR: Channel B seems to be unconnected!"); - } - if (this->isStallGuardReached()) { - SERIAL_ECHOLNPGM("\n INFO: Stall Guard level reached!"); - } - if (this->isStandStill()) { - SERIAL_ECHOLNPGM("\n INFO: Motor is standing still."); - } - unsigned long readout_config = driver_configuration_register_value & READ_SELECTION_PATTERN; - int value = getReadoutValue(); - if (readout_config == READ_MICROSTEP_POSTION) { - //SERIAL_PRINTF("Microstep postion phase A: "); - SERIAL_ECHOPAIR("\n Microstep postion phase A: ", value); - } else if (readout_config == READ_STALL_GUARD_READING) { - //SERIAL_PRINTF("Stall Guard value:"); - SERIAL_ECHOPAIR("\n Stall Guard value:", value); - } else if (readout_config == READ_STALL_GUARD_AND_COOL_STEP) { - int stallGuard = value & 0xf; - int current = value & 0x1F0; - //SERIAL_PRINTF("Approx Stall Guard: "); - SERIAL_ECHOPAIR("\n Approx Stall Guard: ", stallGuard); - //SERIAL_PRINTF("Current level"); - SERIAL_ECHOPAIR("\n Current level", current); - } - } -#endif + #ifdef TMC_DEBUG1 + if (this->started) { + if (this->getOverTemperature()&TMC26X_OVERTEMPERATURE_PREWARING) + SERIAL_ECHOLNPGM("\n WARNING: Overtemperature Prewarning!"); + else if (this->getOverTemperature()&TMC26X_OVERTEMPERATURE_SHUTDOWN) + SERIAL_ECHOLNPGM("\n ERROR: Overtemperature Shutdown!"); + + if (this->isShortToGroundA()) + SERIAL_ECHOLNPGM("\n ERROR: SHORT to ground on channel A!"); + + if (this->isShortToGroundB()) + SERIAL_ECHOLNPGM("\n ERROR: SHORT to ground on channel B!"); + + if (this->isOpenLoadA()) + SERIAL_ECHOLNPGM("\n ERROR: Channel A seems to be unconnected!"); + + if (this->isOpenLoadB()) + SERIAL_ECHOLNPGM("\n ERROR: Channel B seems to be unconnected!"); + + if (this->isStallGuardReached()) + SERIAL_ECHOLNPGM("\n INFO: Stall Guard level reached!"); + + if (this->isStandStill()) + SERIAL_ECHOLNPGM("\n INFO: Motor is standing still."); + + unsigned long readout_config = driver_configuration_register_value & READ_SELECTION_PATTERN; + const int value = getReadoutValue(); + if (readout_config == READ_MICROSTEP_POSTION) { + //SERIAL_PRINTF("Microstep postion phase A: "); + SERIAL_ECHOPAIR("\n Microstep postion phase A: ", value); + } + else if (readout_config == READ_STALL_GUARD_READING) { + //SERIAL_PRINTF("Stall Guard value:"); + SERIAL_ECHOPAIR("\n Stall Guard value:", value); + } + else if (readout_config == READ_STALL_GUARD_AND_COOL_STEP) { + int stallGuard = value & 0xF, current = value & 0x1F0; + //SERIAL_PRINTF("Approx Stall Guard: "); + SERIAL_ECHOPAIR("\n Approx Stall Guard: ", stallGuard); + //SERIAL_PRINTF("Current level"); + SERIAL_ECHOPAIR("\n Current level", current); + } + } + #endif } -/* +/** * send register settings to the stepper driver via SPI * returns the current status */ inline void TMC26XStepper::send262(unsigned long datagram) { - unsigned long i_datagram; - - //preserver the previous spi mode - //unsigned char oldMode = SPCR & SPI_MODE_MASK; - - //if the mode is not correct set it to mode 3 - //if (oldMode != SPI_MODE3) { - // SPI.setDataMode(SPI_MODE3); - //} - - //select the TMC driver - digitalWrite(cs_pin,LOW); - - //ensure that only valid bist are set (0-19) - //datagram &=REGISTER_BIT_PATTERN; - -#ifdef TMC_DEBUG1 - //SERIAL_PRINTF("Sending "); - //SERIAL_PRINTF("Sending ", datagram,HEX); - //SERIAL_ECHOPAIR("\n\nSending \n", print_hex_long(datagram)); - SERIAL_PRINTF("\n\nSending %x", datagram); -#endif - - //write/read the values - i_datagram = STEPPER_SPI.transfer((datagram >> 16) & 0xff); - i_datagram <<= 8; - i_datagram |= STEPPER_SPI.transfer((datagram >> 8) & 0xff); - i_datagram <<= 8; - i_datagram |= STEPPER_SPI.transfer((datagram) & 0xff); - i_datagram >>= 4; - -#ifdef TMC_DEBUG1 - //SERIAL_PRINTF("Received "); - //SERIAL_PRINTF("Received ", i_datagram,HEX); - //SERIAL_ECHOPAIR("\n\nReceived \n", i_datagram); - SERIAL_PRINTF("\n\nReceived %x", i_datagram); - debugLastStatus(); -#endif - //deselect the TMC chip - digitalWrite(cs_pin,HIGH); - - //restore the previous SPI mode if neccessary - //if the mode is not correct set it to mode 3 - //if (oldMode != SPI_MODE3) { - // SPI.setDataMode(oldMode); - //} - - - //store the datagram as status result - driver_status_result = i_datagram; -} - -#endif // STM32F7 \ No newline at end of file + unsigned long i_datagram; + + //preserver the previous spi mode + //unsigned char oldMode = SPCR & SPI_MODE_MASK; + + //if the mode is not correct set it to mode 3 + //if (oldMode != SPI_MODE3) { + // SPI.setDataMode(SPI_MODE3); + //} + + //select the TMC driver + digitalWrite(cs_pin,LOW); + + //ensure that only valid bist are set (0-19) + //datagram &=REGISTER_BIT_PATTERN; + + #ifdef TMC_DEBUG1 + //SERIAL_PRINTF("Sending "); + //SERIAL_PRINTF("Sending ", datagram,HEX); + //SERIAL_ECHOPAIR("\n\nSending \n", print_hex_long(datagram)); + SERIAL_PRINTF("\n\nSending %x", datagram); + #endif + + //write/read the values + i_datagram = STEPPER_SPI.transfer((datagram >> 16) & 0xFF); + i_datagram <<= 8; + i_datagram |= STEPPER_SPI.transfer((datagram >> 8) & 0xFF); + i_datagram <<= 8; + i_datagram |= STEPPER_SPI.transfer((datagram) & 0xFF); + i_datagram >>= 4; + + #ifdef TMC_DEBUG1 + //SERIAL_PRINTF("Received "); + //SERIAL_PRINTF("Received ", i_datagram,HEX); + //SERIAL_ECHOPAIR("\n\nReceived \n", i_datagram); + SERIAL_PRINTF("\n\nReceived %x", i_datagram); + debugLastStatus(); + #endif + + //deselect the TMC chip + digitalWrite(cs_pin,HIGH); + + //restore the previous SPI mode if neccessary + //if the mode is not correct set it to mode 3 + //if (oldMode != SPI_MODE3) { + // SPI.setDataMode(oldMode); + //} + + //store the datagram as status result + driver_status_result = i_datagram; +} + +#endif // STM32F7 diff --git a/Marlin/src/HAL/HAL_STM32F7/TMC2660.h b/Marlin/src/HAL/HAL_STM32F7/TMC2660.h index 9c10b53f4e..75fbe097d9 100644 --- a/Marlin/src/HAL/HAL_STM32F7/TMC2660.h +++ b/Marlin/src/HAL/HAL_STM32F7/TMC2660.h @@ -1,37 +1,35 @@ -/* - TMC26XStepper.cpp - - TMC26X Stepper library for Wiring/Arduino - - based on the stepper library by Tom Igoe, et. al. - - Copyright (c) 2011, Interactive Matter, Marcus Nowotny - - Permission is hereby granted, free of charge, to any person obtaining a copy - of this software and associated documentation files (the "Software"), to deal - in the Software without restriction, including without limitation the rights - to use, copy, modify, merge, publish, distribute, sublicense, and/or sell - copies of the Software, and to permit persons to whom the Software is - furnished to do so, subject to the following conditions: - - The above copyright notice and this permission notice shall be included in - all copies or substantial portions of the Software. - - THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR - IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, - FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE - AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER - LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, - OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN - THE SOFTWARE. - +/** + * TMC26XStepper.h - - TMC26X Stepper library for Wiring/Arduino + * + * based on the stepper library by Tom Igoe, et. al. + * + * Copyright (c) 2011, Interactive Matter, Marcus Nowotny + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN + * THE SOFTWARE. + * */ - - #include "../../inc/MarlinConfig.h" // ensure this library description is only included once -#ifndef TMC26XStepper_h -#define TMC26XStepper_h +#ifndef _TMC26XSTEPPER_H_ +#define _TMC26XSTEPPER_H_ //! return value for TMC26XStepper.getOverTemperature() if there is a overtemperature situation in the TMC chip /*! @@ -124,8 +122,8 @@ class TMC26XStepper { * You can select a different stepping with setMicrosteps() to aa different value. * \sa start(), setMicrosteps() */ - TMC26XStepper(int number_of_steps, int cs_pin, int dir_pin, int step_pin, unsigned int current, unsigned int resistor=100); //resistor=150 - + TMC26XStepper(int number_of_steps, int cs_pin, int dir_pin, int step_pin, unsigned int current, unsigned int resistor=100); //resistor=150 + /*! * \brief configures and starts the TMC26X stepper driver. Before you called this function the stepper driver is in nonfunctional mode. * @@ -133,7 +131,7 @@ class TMC26XStepper { * Most member functions are non functional if the driver has not been started. * Therefore it is best to call this in your Arduino setup() function. */ - void start(); + void start(); /*! * \brief resets the stepper in unconfigured mode. @@ -145,7 +143,7 @@ class TMC26XStepper { * this has to be configured back by yourself. * (Hint: Normally you do not need this function) */ - void un_start(); + void un_start(); /*! @@ -168,9 +166,9 @@ class TMC26XStepper { * If you give any other value it will be rounded to the next smaller number (3 would give a microstepping of 2). * You can always check the current microstepping with getMicrosteps(). */ - void setMicrosteps(int number_of_steps); + void setMicrosteps(int number_of_steps); - /*! + /*! * \brief returns the effective current number of microsteps selected. * * This function always returns the effective number of microsteps. @@ -178,7 +176,7 @@ class TMC26XStepper { * * \sa setMicrosteps() */ - int getMicrosteps(void); + int getMicrosteps(void); /*! * \brief Initiate a movement for the given number of steps. Positive numbers move in one, negative numbers in the other direction. @@ -187,7 +185,7 @@ class TMC26XStepper { * \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. * * If the previous movement is not finished yet the function will return -1 and not change the steps to move the motor. - * If the motor does not move it return 0 + * If the motor does not move it return 0 * * The direction of the movement is indicated by the sign of the steps parameter. It is not determinable if positive values are right * or left This depends on the internal construction of the motor and how you connected it to the stepper driver. @@ -264,7 +262,7 @@ class TMC26XStepper { * \sa setSpreadCycleChoper() for other alternatives. * \sa setRandomOffTime() for spreading the noise over a wider spectrum */ - void setConstantOffTimeChopper(char constant_off_time, char blank_time, char fast_decay_time_setting, char sine_wave_offset, unsigned char use_current_comparator); + void setConstantOffTimeChopper(char constant_off_time, char blank_time, char fast_decay_time_setting, char sine_wave_offset, unsigned char use_current_comparator); /*! * \brief Sets and configures with spread cycle chopper. @@ -286,9 +284,9 @@ class TMC26XStepper { * * \sa setRandomOffTime() for spreading the noise over a wider spectrum */ - void setSpreadCycleChopper(char constant_off_time, char blank_time, char hysteresis_start, char hysteresis_end, char hysteresis_decrement); + void setSpreadCycleChopper(char constant_off_time, char blank_time, char hysteresis_start, char hysteresis_end, char hysteresis_decrement); - /*! + /*! * \brief Use random off time for noise reduction (0 for off, -1 for on). * \param value 0 for off, -1 for on * @@ -303,16 +301,16 @@ class TMC26XStepper { * It modulates the slow decay time setting when switched on. The random off time feature further spreads the chopper spectrum, * reducing electromagnetic emission on single frequencies. */ - void setRandomOffTime(char value); + void setRandomOffTime(char value); - /*! + /*! * \brief set the maximum motor current in mA (1000 is 1 Amp) * 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 * by employing CoolStep. * \param current the maximum motor current in mA * \sa getCurrent(), getCurrentCurrent() */ - void setCurrent(unsigned int current); + void setCurrent(unsigned int current); /*! * \brief readout the motor maximum current in mA (1000 is an Amp) @@ -322,7 +320,7 @@ class TMC26XStepper { */ unsigned int getCurrent(void); - /*! + /*! * \brief set the StallGuard threshold in order to get sensible StallGuard readings. * \param stall_guard_threshold -64 … 63 the StallGuard threshold * \param stall_guard_filter_enabled 0 if the filter is disabled, -1 if it is enabled @@ -337,7 +335,7 @@ class TMC26XStepper { * * \sa getCurrentStallGuardReading() to read out the current value. */ - void setStallGuardThreshold(char stall_guard_threshold, char stall_guard_filter_enabled); + void setStallGuardThreshold(char stall_guard_threshold, char stall_guard_filter_enabled); /*! * \brief reads out the StallGuard threshold @@ -416,13 +414,13 @@ class TMC26XStepper { */ unsigned char getCoolStepLowerCurrentLimit(); - /*! + /*! * \brief Get the current microstep position for phase A * \return The current microstep position for phase A 0…255 * * Keep in mind that this routine reads and writes a value via SPI - so this may take a bit time. */ - int getMotorPosition(void); + int getMotorPosition(void); /*! * \brief Reads the current StallGuard value. @@ -430,7 +428,7 @@ class TMC26XStepper { * Keep in mind that this routine reads and writes a value via SPI - so this may take a bit time. * \sa setStallGuardThreshold() for tuning the readout to sensible ranges. */ - int getCurrentStallGuardReading(void); + int getCurrentStallGuardReading(void); /*! * \brief Reads the current current setting value as fraction of the maximum current @@ -463,7 +461,7 @@ class TMC26XStepper { * * \sa setStallGuardThreshold() for tuning the readout to sensible ranges. */ - boolean isStallGuardOverThreshold(void); + boolean isStallGuardOverThreshold(void); /*! * \brief Return over temperature status of the last status readout @@ -471,7 +469,7 @@ class TMC26XStepper { * Keep in mind that this method does not enforce a readout but uses the value of the last status readout. * You may want to use getMotorPosition() or getCurrentStallGuardReading() to enforce an updated status readout. */ - char getOverTemperature(void); + char getOverTemperature(void); /*! * \brief Is motor channel A shorted to ground detected in the last status readout. @@ -480,7 +478,7 @@ class TMC26XStepper { * You may want to use getMotorPosition() or getCurrentStallGuardReading() to enforce an updated status readout. */ - boolean isShortToGroundA(void); + boolean isShortToGroundA(void); /*! * \brief Is motor channel B shorted to ground detected in the last status readout. @@ -488,22 +486,22 @@ class TMC26XStepper { * Keep in mind that this method does not enforce a readout but uses the value of the last status readout. * You may want to use getMotorPosition() or getCurrentStallGuardReading() to enforce an updated status readout. */ - boolean isShortToGroundB(void); - /*! + boolean isShortToGroundB(void); + /*! * \brief iIs motor channel A connected according to the last statu readout. * \return true is yes, false if not. * Keep in mind that this method does not enforce a readout but uses the value of the last status readout. * You may want to use getMotorPosition() or getCurrentStallGuardReading() to enforce an updated status readout. */ - boolean isOpenLoadA(void); + boolean isOpenLoadA(void); - /*! + /*! * \brief iIs motor channel A connected according to the last statu readout. * \return true is yes, false if not. * Keep in mind that this method does not enforce a readout but uses the value of the last status readout. * You may want to use getMotorPosition() or getCurrentStallGuardReading() to enforce an updated status readout. */ - boolean isOpenLoadB(void); + boolean isOpenLoadB(void); /*! * \brief Is chopper inactive since 2^20 clock cycles - defaults to ~0,08s @@ -511,7 +509,7 @@ class TMC26XStepper { * Keep in mind that this method does not enforce a readout but uses the value of the last status readout. * You may want to use getMotorPosition() or getCurrentStallGuardReading() to enforce an updated status readout. */ - boolean isStandStill(void); + boolean isStandStill(void); /*! * \brief checks if there is a StallGuard warning in the last status @@ -524,7 +522,7 @@ class TMC26XStepper { * * \sa setStallGuardThreshold() for tuning the readout to sensible ranges. */ - boolean isStallGuardReached(void); + boolean isStallGuardReached(void); /*! *\brief enables or disables the motor driver bridges. If disabled the motor can run freely. If enabled not. @@ -539,7 +537,7 @@ class TMC26XStepper { */ boolean isEnabled(); - /*! + /*! * \brief Manually read out the status register * This function sends a byte to the motor driver in order to get the current readout. The parameter read_value * seletcs which value will get returned. If the read_vlaue changes in respect to the previous readout this method @@ -548,7 +546,7 @@ class TMC26XStepper { * \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 * \sa TMC26X_READOUT_POSITION, TMC_262_READOUT_STALLGUARD, TMC_262_READOUT_CURRENT */ - void readStatus(char read_value); + void readStatus(char read_value); /*! * \brief Returns the current sense resistor value in milliohm. @@ -560,51 +558,50 @@ class TMC26XStepper { * \brief Prints out all the information that can be found in the last status read out - it does not force a status readout. * The result is printed via Serial */ - void debugLastStatus(void); - /*! + void debugLastStatus(void); + /*! * \brief library version * \return the version number as int. */ int version(void); private: - unsigned int steps_left; //the steps the motor has to do to complete the movement - int direction; // Direction of rotation - unsigned long step_delay; // delay between steps, in ms, based on speed - int number_of_steps; // total number of steps this motor can take - unsigned int speed; // we need to store the current speed in order to change the speed after changing microstepping - unsigned int resistor; //current sense resitor value in milliohm + unsigned int steps_left; // The steps the motor has to do to complete the movement + int direction; // Direction of rotation + unsigned long step_delay; // Delay between steps, in ms, based on speed + int number_of_steps; // Total number of steps this motor can take + unsigned int speed; // Store the current speed in order to change the speed after changing microstepping + unsigned int resistor; // Current sense resitor value in milliohm - unsigned long last_step_time; // time stamp in ms of when the last step was taken - unsigned long next_step_time; // time stamp in ms of when the last step was taken - - //driver control register copies to easily set & modify the registers - unsigned long driver_control_register_value; - unsigned long chopper_config_register; - unsigned long cool_step_register_value; - unsigned long stall_guard2_current_register_value; - unsigned long driver_configuration_register_value; - //the driver status result - unsigned long driver_status_result; - - //helper routione to get the top 10 bit of the readout - inline int getReadoutValue(); - - //the pins for the stepper driver - unsigned char cs_pin; - unsigned char step_pin; - unsigned char dir_pin; - - //status values - boolean started; //if the stepper has been started yet - int microsteps; //the current number of micro steps - char constant_off_time; //we need to remember this value in order to enable and disable the motor - unsigned char cool_step_lower_threshold; // we need to remember the threshold to enable and disable the CoolStep feature - boolean cool_step_enabled; //we need to remember this to configure the coolstep if it si enabled - - //SPI sender - inline void send262(unsigned long datagram); + unsigned long last_step_time; // Time stamp in ms of when the last step was taken + unsigned long next_step_time; // Time stamp in ms of when the last step was taken + + // Driver control register copies to easily set & modify the registers + unsigned long driver_control_register_value; + unsigned long chopper_config_register; + unsigned long cool_step_register_value; + unsigned long stall_guard2_current_register_value; + unsigned long driver_configuration_register_value; + // The driver status result + unsigned long driver_status_result; + + // Helper routione to get the top 10 bit of the readout + inline int getReadoutValue(); + + // The pins for the stepper driver + unsigned char cs_pin; + unsigned char step_pin; + unsigned char dir_pin; + + // Status values + boolean started; // If the stepper has been started yet + int microsteps; // The current number of micro steps + char constant_off_time; // We need to remember this value in order to enable and disable the motor + unsigned char cool_step_lower_threshold; // we need to remember the threshold to enable and disable the CoolStep feature + boolean cool_step_enabled; // We need to remember this to configure the coolstep if it si enabled + + // SPI sender + inline void send262(unsigned long datagram); }; -#endif - +#endif // _TMC26XSTEPPER_H_ diff --git a/Marlin/src/HAL/HAL_STM32F7/fastio_STM32F7.h b/Marlin/src/HAL/HAL_STM32F7/fastio_STM32F7.h index 0e53ce76f4..ed74161e01 100644 --- a/Marlin/src/HAL/HAL_STM32F7/fastio_STM32F7.h +++ b/Marlin/src/HAL/HAL_STM32F7/fastio_STM32F7.h @@ -26,10 +26,10 @@ * These use GPIO functions instead of Direct Port Manipulation, as on AVR. */ -#ifndef _FASTIO_STM32F7_H -#define _FASTIO_STM32F7_H +#ifndef _FASTIO_STM32F7_H +#define _FASTIO_STM32F7_H -#define _BV(bit) (1 << (bit)) +#define _BV(bit) (1 << (bit)) #define READ(IO) digitalRead(IO) #define WRITE(IO, v) digitalWrite(IO,v) @@ -38,17 +38,17 @@ #define _GET_MODE(IO) #define _SET_MODE(IO,M) pinMode(IO, M) -#define _SET_OUTPUT(IO) pinMode(IO, OUTPUT) /*!< Output Push Pull Mode & GPIO_NOPULL */ +#define _SET_OUTPUT(IO) pinMode(IO, OUTPUT) /*!< Output Push Pull Mode & GPIO_NOPULL */ -#define SET_INPUT(IO) _SET_MODE(IO, INPUT) /*!< Input Floating Mode */ -#define SET_INPUT_PULLUP(IO) _SET_MODE(IO, INPUT_PULLUP) /*!< Input with Pull-up activation */ -#define SET_INPUT_PULLDOW(IO) _SET_MODE(IO, INPUT_PULLDOWN) /*!< Input with Pull-down activation */ -#define SET_OUTPUT(IO) do{ _SET_OUTPUT(IO); WRITE(IO, LOW); }while(0) +#define SET_INPUT(IO) _SET_MODE(IO, INPUT) /*!< Input Floating Mode */ +#define SET_INPUT_PULLUP(IO) _SET_MODE(IO, INPUT_PULLUP) /*!< Input with Pull-up activation */ +#define SET_INPUT_PULLDOW(IO) _SET_MODE(IO, INPUT_PULLDOWN) /*!< Input with Pull-down activation */ +#define SET_OUTPUT(IO) do{ _SET_OUTPUT(IO); WRITE(IO, LOW); }while(0) -#define GET_INPUT(IO) -#define GET_OUTPUT(IO) -#define GET_TIMER(IO) +#define GET_INPUT(IO) +#define GET_OUTPUT(IO) +#define GET_TIMER(IO) #define OUT_WRITE(IO, v) { _SET_OUTPUT(IO); WRITE(IO, v); } -#endif /* _FASTIO_STM32F7_H */ +#endif // _FASTIO_STM32F7_H diff --git a/Marlin/src/HAL/HAL_STM32F7/watchdog_STM32F7.cpp b/Marlin/src/HAL/HAL_STM32F7/watchdog_STM32F7.cpp index 883c490e19..0b0031a236 100644 --- a/Marlin/src/HAL/HAL_STM32F7/watchdog_STM32F7.cpp +++ b/Marlin/src/HAL/HAL_STM32F7/watchdog_STM32F7.cpp @@ -1,24 +1,24 @@ /** -* Marlin 3D Printer Firmware -* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] -* -* Based on Sprinter and grbl. -* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm -* -* This program is free software: you can redistribute it and/or modify -* it under the terms of the GNU General Public License as published by -* the Free Software Foundation, either version 3 of the License, or -* (at your option) any later version. -* -* This program is distributed in the hope that it will be useful, -* but WITHOUT ANY WARRANTY; without even the implied warranty of -* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the -* GNU General Public License for more details. -* -* You should have received a copy of the GNU General Public License -* along with this program. If not, see . -* -*/ + * Marlin 3D Printer Firmware + * Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ #ifdef STM32F7 @@ -26,29 +26,26 @@ #if ENABLED(USE_WATCHDOG) - #include "watchdog_STM32F7.h" + #include "watchdog_STM32F7.h" - IWDG_HandleTypeDef hiwdg; + IWDG_HandleTypeDef hiwdg; - void watchdog_init() { - hiwdg.Instance = IWDG; - hiwdg.Init.Prescaler = IWDG_PRESCALER_32; //32kHz LSI clock and 32x prescalar = 1024Hz IWDG clock - hiwdg.Init.Reload = 4095; //4095 counts = 4 seconds at 1024Hz - if (HAL_IWDG_Init(&hiwdg) != HAL_OK) - { - //Error_Handler(); - } + void watchdog_init() { + hiwdg.Instance = IWDG; + hiwdg.Init.Prescaler = IWDG_PRESCALER_32; //32kHz LSI clock and 32x prescalar = 1024Hz IWDG clock + hiwdg.Init.Reload = 4095; //4095 counts = 4 seconds at 1024Hz + if (HAL_IWDG_Init(&hiwdg) != HAL_OK) { + //Error_Handler(); } + } - void watchdog_reset() { - /* Refresh IWDG: reload counter */ - if (HAL_IWDG_Refresh(&hiwdg) != HAL_OK) - { - /* Refresh Error */ - //Error_Handler(); - } + void watchdog_reset() { + /* Refresh IWDG: reload counter */ + if (HAL_IWDG_Refresh(&hiwdg) != HAL_OK) { + /* Refresh Error */ + //Error_Handler(); } - + } #endif // USE_WATCHDOG diff --git a/Marlin/src/HAL/HAL_SanityCheck.h b/Marlin/src/HAL/HAL_SanityCheck.h index 41794aaba9..e6859a7802 100644 --- a/Marlin/src/HAL/HAL_SanityCheck.h +++ b/Marlin/src/HAL/HAL_SanityCheck.h @@ -37,10 +37,10 @@ #elif defined(__STM32F1__) #include "HAL_STM32F1/SanityCheck_Stm32f1.h" - #elif defined(STM32F7) + #elif defined(STM32F7) #include "HAL_STM32F7/SanityCheck_STM32F7.h" - #else +#else #error Unsupported Platform! #endif diff --git a/Marlin/src/HAL/HAL_spi_pins.h b/Marlin/src/HAL/HAL_spi_pins.h index 9b3ae88669..495d039872 100644 --- a/Marlin/src/HAL/HAL_spi_pins.h +++ b/Marlin/src/HAL/HAL_spi_pins.h @@ -41,7 +41,7 @@ #elif defined(STM32F7) #include "HAL_STM32F7/spi_pins.h" - #else +#else #error "Unsupported Platform!" #endif diff --git a/Marlin/src/core/macros.h b/Marlin/src/core/macros.h index 738e41654c..2c62467232 100644 --- a/Marlin/src/core/macros.h +++ b/Marlin/src/core/macros.h @@ -120,6 +120,7 @@ // Macros to contrain values #define NOLESS(v,n) do{ if (v < n) v = n; }while(0) #define NOMORE(v,n) do{ if (v > n) v = n; }while(0) +#define LIMIT(v,n1,n2) do{ if (v < n1) v = n1; else if (v > n2) v = n2; }while(0) // Macros to support option testing #define _CAT(a, ...) a ## __VA_ARGS__ diff --git a/Marlin/src/module/stepper_indirection.cpp b/Marlin/src/module/stepper_indirection.cpp index 85a9114cde..0fb97957dd 100644 --- a/Marlin/src/module/stepper_indirection.cpp +++ b/Marlin/src/module/stepper_indirection.cpp @@ -42,7 +42,7 @@ #include - #if defined(STM32F7) + #ifdef STM32F7 #include "../HAL/HAL_STM32F7/TMC2660.h" #else #include diff --git a/Marlin/src/module/stepper_indirection.h b/Marlin/src/module/stepper_indirection.h index 56e634c234..67f516d075 100644 --- a/Marlin/src/module/stepper_indirection.h +++ b/Marlin/src/module/stepper_indirection.h @@ -49,7 +49,7 @@ // TMC26X drivers have STEP/DIR on normal pins, but ENABLE via SPI #if ENABLED(HAVE_TMCDRIVER) #include - #if defined(STM32F7) + #ifdef STM32F7 #include "../HAL/HAL_STM32F7/TMC2660.h" #else #include