Skip to content

Commit

Permalink
🎨 Misc. variant cleanup, translation
Browse files Browse the repository at this point in the history
  • Loading branch information
thinkyhead committed Dec 16, 2022
1 parent a913b24 commit 682a9b6
Show file tree
Hide file tree
Showing 5 changed files with 57 additions and 58 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -411,7 +411,7 @@ in voltage and temperature. */
#endif /* HAL_SPI_MODULE_ENABLED */

#ifdef HAL_TIM_MODULE_ENABLED
#include "stm32f4xx_hal_tim.h"
#include "stm32f4xx_hal_tim.h"
#endif /* HAL_TIM_MODULE_ENABLED */

#ifdef HAL_UART_MODULE_ENABLED
Expand Down
102 changes: 50 additions & 52 deletions buildroot/share/PlatformIO/variants/MARLIN_F446Zx_TRONXY/variant.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -170,69 +170,69 @@ extern "C" {
#endif

uint32_t myvar[] = {1,2,3,4,5,6,7,8};
void myshow(int fre,int times)//YSZ-WORK
void myshow(int fre, int times) // YSZ-WORK
{
uint32_t index = 10;
RCC->AHB1ENR |= 1 << 6;//端口G时钟
GPIOG->MODER &= ~(3UL << 2 * index);//清除旧模式
GPIOG->MODER |= 1 << 2 * index;//模式为输出
GPIOG->OSPEEDR &= ~(3UL << 2 * index); //清除旧输出速度
GPIOG->OSPEEDR |= 2 << 2 * index;//设置输出速度
GPIOG->OTYPER &= ~(1UL << index);//清除旧输出方式
GPIOG->OTYPER |= 0 << index;//设置输出方式为推挽
GPIOG->PUPDR &= ~(3 << 2 * index);//先清除原来的设置
GPIOG->PUPDR |= 1 << 2 * index;//设置新的上下拉
while(times != 0) {
RCC->AHB1ENR |= 1 << 6; // port G clock
GPIOG->MODER &= ~(3UL << 2 * index); // clear old mode
GPIOG->MODER |= 1 << 2 * index; // mode is output
GPIOG->OSPEEDR &= ~(3UL << 2 * index) // Clear old output speed
GPIOG->OSPEEDR |= 2 << 2 * index; // Set output speed
GPIOG->OTYPER &= ~(1UL << index) // clear old output
GPIOG->OTYPER |= 0 << index; // Set the output mode to push-pull
GPIOG->PUPDR &= ~(3 << 2 * index) // Clear the original settings first
GPIOG->PUPDR |= 1 << 2 * index; // Set new up and down
while (times != 0) {
GPIOG->BSRR = 1UL << index;
for(int i = 0;i < fre; i++)
for(int j = 0; j < 1000000; j++)__NOP();
for (int i = 0; i < fre; i++)
for (int j = 0; j < 1000000; j++) __NOP();
GPIOG->BSRR = 1UL << (index + 16);
for(int i = 0;i < fre; i++)
for(int j = 0; j < 1000000; j++)__NOP();
if(times > 0)times--;
for (int i = 0; i < fre; i++)
for (int j = 0; j < 1000000; j++) __NOP();
if (times > 0) times--;
}
}

HAL_StatusTypeDef SDMMC_IsProgramming(SDIO_TypeDef *SDIOx,uint32_t RCA)
{
HAL_SD_CardStateTypeDef CardState;
volatile uint32_t respR1 = 0, status = 0;
SDIO_CmdInitTypeDef sdmmc_cmdinit;
volatile uint32_t respR1 = 0, status = 0;
SDIO_CmdInitTypeDef sdmmc_cmdinit;
do {
sdmmc_cmdinit.Argument = RCA << 16;
sdmmc_cmdinit.CmdIndex = SDMMC_CMD_SEND_STATUS;
sdmmc_cmdinit.Response = SDIO_RESPONSE_SHORT;
sdmmc_cmdinit.WaitForInterrupt = SDIO_WAIT_NO;
sdmmc_cmdinit.CPSM = SDIO_CPSM_ENABLE;
SDIO_SendCommand(SDIOx,&sdmmc_cmdinit);//发送CMD13
SDIO_SendCommand(SDIOx,&sdmmc_cmdinit); // send CMD13
do status = SDIOx->STA;
while(!(status & ((1 << 0) | (1 << 6) | (1 << 2))));//等待操作完成
if(status & (1 << 0)) //CRC检测失败
{
SDIOx->ICR |= 1 << 0; //清除错误标记
while (!(status & ((1 << 0) | (1 << 6) | (1 << 2)))); // wait for the operation to complete
if (status & (1 << 0)) { // CRC check failed
SDIOx->ICR |= 1 << 0; // clear error flag
return HAL_ERROR;
}
if(status & (1 << 2)) //命令超时
{
SDIOx->ICR |= 1 << 2; //清除错误标记
if (status & (1 << 2)) { // command timed out
SDIOx->ICR |= 1 << 2; // clear error flag
return HAL_ERROR;
}
if(SDIOx->RESPCMD != SDMMC_CMD_SEND_STATUS)return HAL_ERROR;
SDIOx->ICR = 0X5FF; //清除所有标记
if (SDIOx->RESPCMD != SDMMC_CMD_SEND_STATUS) return HAL_ERROR;
SDIOx->ICR = 0X5FF; // clear all tags
respR1 = SDIOx->RESP1;
CardState = (respR1 >> 9) & 0x0000000F;
}while((CardState == HAL_SD_CARD_RECEIVING) || (CardState == HAL_SD_CARD_SENDING) || (CardState == HAL_SD_CARD_PROGRAMMING));
} while ((CardState == HAL_SD_CARD_RECEIVING) || (CardState == HAL_SD_CARD_SENDING) || (CardState == HAL_SD_CARD_PROGRAMMING));
return HAL_OK;
}
void debugStr(const char*str) {
while(*str) {
while((USART1->SR & 0x40) == 0);
USART1->DR = *str++;
}

void debugStr(const char *str) {
while (*str) {
while ((USART1->SR & 0x40) == 0);
USART1->DR = *str++;
}
}

/**
* @brief System Clock Configuration
* The system Clock is configured as follow :
* The system Clock is configured as follows:
* System Clock source = PLL (HSE)
* SYSCLK(Hz) = 168000000/120000000/180000000
* HCLK(Hz) = 168000000/120000000/180000000
Expand Down Expand Up @@ -265,8 +265,8 @@ WEAK void SystemClock_Config(void)
/* Enable Power Control clock */
__HAL_RCC_PWR_CLK_ENABLE();

/* The voltage scaling allows optimizing the power consumption when the device is
clocked below the maximum system frequency, to update the voltage scaling value
/* The voltage scaling allows optimizing the power consumption when the device is
clocked below the maximum system frequency, to update the voltage scaling value
regarding system frequency refer to product datasheet. */
__HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE1);

Expand All @@ -281,42 +281,40 @@ WEAK void SystemClock_Config(void)
RCC_OscInitStruct.PLL.PLLQ = 7;
RCC_OscInitStruct.PLL.PLLR = 2;
ret = HAL_RCC_OscConfig(&RCC_OscInitStruct);
if(ret != HAL_OK)myshow(10,-1);

if (ret != HAL_OK) myshow(10,-1);
HAL_PWREx_EnableOverDrive();

/* Select PLLSAI output as USB clock source */
PeriphClkInitStruct.PLLSAI.PLLSAIM = 8;
PeriphClkInitStruct.PLLSAI.PLLSAIN = 192;
PeriphClkInitStruct.PLLSAI.PLLSAIP = RCC_PLLSAIP_DIV4;
PeriphClkInitStruct.PeriphClockSelection = RCC_PERIPHCLK_CLK48 | RCC_PERIPHCLK_SDIO;
PeriphClkInitStruct.Clk48ClockSelection = RCC_CK48CLKSOURCE_PLLSAIP;
PeriphClkInitStruct.SdioClockSelection = RCC_SDIOCLKSOURCE_CLK48;//SDIO Clock Mux
PeriphClkInitStruct.SdioClockSelection = RCC_SDIOCLKSOURCE_CLK48; // SDIO Clock Mux
HAL_RCCEx_PeriphCLKConfig(&PeriphClkInitStruct);

/* Select PLL as system clock source and configure the HCLK, PCLK1 and PCLK2
clocks dividers */
/* Select PLL as system clock source and configure the HCLK, PCLK1 and PCLK2 clocks dividers */
RCC_ClkInitStruct.ClockType = (RCC_CLOCKTYPE_SYSCLK | RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2);
RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK;
RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1;
RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV4;
RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV2;
RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV4;
RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV2;
ret = HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_5);
if(ret != HAL_OK)myshow(10,-1);
if (ret != HAL_OK) myshow(10,-1);

SystemCoreClockUpdate();//更新系统时钟SystemCoreClock
/**Configure the Systick interrupt time
*/
SystemCoreClockUpdate();
/* Configure the Systick interrupt time */
HAL_SYSTICK_Config(HAL_RCC_GetHCLKFreq() / 1000);

/**Configure the Systick
*/
/* Configure the Systick */
HAL_SYSTICK_CLKSourceConfig(SYSTICK_CLKSOURCE_HCLK);

/* SysTick_IRQn interrupt configuration */
HAL_NVIC_SetPriority(SysTick_IRQn, 0, 0);
__enable_irq();//打开中断,因为在bootloader中关闭了,所以这里要打开
__enable_irq(); // Turn on the interrupt here because it is turned off in the bootloader
}

#ifdef __cplusplus
}
#endif
Original file line number Diff line number Diff line change
Expand Up @@ -24,8 +24,9 @@ extern "C" {
#endif // __cplusplus

extern unsigned long myvar[];
void myshow(int fre,int times);
void debugStr(const char*str);
void myshow(int fre, int times);
void debugStr(const char *str);

/*----------------------------------------------------------------------------
* Pins
*----------------------------------------------------------------------------*/
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -76,8 +76,8 @@ WEAK const PinMap PinMap_PWM[] = {
{PA_0, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1 Fan2
{PA_1, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 2, 0)}, // TIM2_CH2 Fan1
{PA_2, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 3, 0)}, // TIM5_CH3 Fan0
{PA_3, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 4, 0)}, // TIM5_CH4 HE2
{PA_8, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 0)}, // TIM1_CH1 Servo
{PA_3, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 4, 0)}, // TIM5_CH4 HE2
{PA_8, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 0)}, // TIM1_CH1 Servo
{PB_0, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N HE1
{PB_1, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N HE0
{PB_2, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 4, 0)}, // TIM2_CH4 BEEPER
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@
#ifdef __cplusplus
extern "C" {
#endif // __cplusplus
//
//
/*----------------------------------------------------------------------------
* Pins
*----------------------------------------------------------------------------*/
Expand Down

0 comments on commit 682a9b6

Please sign in to comment.