update booter, can run without STM32 package

This commit is contained in:
pikastech 2021-11-12 09:21:18 +08:00
parent 988d5e691b
commit 4ef93cf6c0
12 changed files with 1846 additions and 0 deletions

View File

@ -0,0 +1,54 @@
/**
******************************************************************************
* @file gpio.c
* @brief This file provides code for the configuration
* of all used GPIO pins.
******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2021 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software component is licensed by ST under BSD 3-Clause license,
* the "License"; You may not use this file except in compliance with the
* License. You may obtain a copy of the License at:
* opensource.org/licenses/BSD-3-Clause
*
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "gpio.h"
/* USER CODE BEGIN 0 */
/* USER CODE END 0 */
/*----------------------------------------------------------------------------*/
/* Configure GPIO */
/*----------------------------------------------------------------------------*/
/* USER CODE BEGIN 1 */
/* USER CODE END 1 */
/** Configure pins as
* Analog
* Input
* Output
* EVENT_OUT
* EXTI
*/
void MX_GPIO_Init(void)
{
/* GPIO Ports Clock Enable */
LL_IOP_GRP1_EnableClock(LL_IOP_GRP1_PERIPH_GPIOF);
LL_IOP_GRP1_EnableClock(LL_IOP_GRP1_PERIPH_GPIOA);
}
/* USER CODE BEGIN 2 */
/* USER CODE END 2 */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -0,0 +1,49 @@
/**
******************************************************************************
* @file gpio.h
* @brief This file contains all the function prototypes for
* the gpio.c file
******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2021 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software component is licensed by ST under BSD 3-Clause license,
* the "License"; You may not use this file except in compliance with the
* License. You may obtain a copy of the License at:
* opensource.org/licenses/BSD-3-Clause
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __GPIO_H__
#define __GPIO_H__
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include "main.h"
/* USER CODE BEGIN Includes */
/* USER CODE END Includes */
/* USER CODE BEGIN Private defines */
/* USER CODE END Private defines */
void MX_GPIO_Init(void);
/* USER CODE BEGIN Prototypes */
/* USER CODE END Prototypes */
#ifdef __cplusplus
}
#endif
#endif /*__ GPIO_H__ */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -0,0 +1,210 @@
/* USER CODE BEGIN Header */
/**
******************************************************************************
* @file : main.c
* @brief : Main program body
******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2021 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software component is licensed by ST under BSD 3-Clause license,
* the "License"; You may not use this file except in compliance with the
* License. You may obtain a copy of the License at:
* opensource.org/licenses/BSD-3-Clause
*
******************************************************************************
*/
/* USER CODE END Header */
/* Includes ------------------------------------------------------------------*/
#include "main.h"
#include "gpio.h"
/* Private includes ----------------------------------------------------------*/
/* USER CODE BEGIN Includes */
#include "pikaScript.h"
#include "pikaVM.h"
#include "stdbool.h"
#include "stm32g030_pika_msp.h"
/* USER CODE END Includes */
/* Private typedef -----------------------------------------------------------*/
/* USER CODE BEGIN PTD */
/* USER CODE END PTD */
/* Private define ------------------------------------------------------------*/
/* USER CODE BEGIN PD */
/* USER CODE END PD */
/* Private macro -------------------------------------------------------------*/
/* USER CODE BEGIN PM */
/* USER CODE END PM */
/* Private variables ---------------------------------------------------------*/
/* USER CODE BEGIN PV */
/* USER CODE END PV */
/* Private function prototypes -----------------------------------------------*/
void SystemClock_Config(void);
/* USER CODE BEGIN PFP */
/* USER CODE END PFP */
/* Private user code ---------------------------------------------------------*/
/* USER CODE BEGIN 0 */
/* supply the main object */
PikaObj* pikaMain;
char Shell_Buff[RX_BUFF_LENGTH] = {0};
uint8_t Shell_Ready = 0;
/* USER CODE END 0 */
/**
* @brief The application entry point.
* @retval int
*/
int main(void) {
/* support bootLoader */
__disable_irq();
SCB->VTOR = FLASH_BASE | 0x2000;
__enable_irq();
/* system init */
HAL_Init();
SystemClock_Config();
MX_GPIO_Init();
HARDWARE_PRINTF_Init();
printf("stm32 hardware init ok\r\n");
/* boot pikaScript */
char* code = (char*)FLASH_SCRIPT_START_ADDR;
uint16_t codeOffset = 0;
if (code[0] != 0xFF) {
/* boot from flash */
pikaMain = newRootObj("pikaMain", New_PikaMain);
if (code[0] == 'i') {
printf("[info]: boot from Script.\r\n");
Arg* codeBuff = arg_setStr(NULL, "", code);
obj_run(pikaMain, arg_getStr(codeBuff));
arg_deinit(codeBuff);
goto main_loop;
}
if (code[0] == 'B') {
printf("==============[Pika ASM]==============\r\n");
for (int i = 0; i < strGetSize(code); i++) {
if ('\n' == code[i]) {
fputc('\r', (FILE*)!NULL);
}
fputc(code[i], (FILE*)!NULL);
}
printf("==============[Pika ASM]==============\r\n");
printf("asm size: %d\r\n", strGetSize(code));
printf("[info]: boot from Pika Asm.\r\n");
pikaVM_runAsm(pikaMain, code);
goto main_loop;
}
} else {
/* boot from firmware */
pikaMain = pikaScriptInit();
goto main_loop;
}
pikaMain = pikaScriptInit();
goto main_loop;
main_loop:
while (1) {
if(Shell_Ready){
Shell_Ready = 0;
obj_run(pikaMain, Shell_Buff);
}
}
}
/**
* @brief System Clock Configuration
* @retval None
*/
void SystemClock_Config(void) {
RCC_OscInitTypeDef RCC_OscInitStruct = {0};
RCC_ClkInitTypeDef RCC_ClkInitStruct = {0};
RCC_PeriphCLKInitTypeDef PeriphClkInit = {0};
/** Configure the main internal regulator output voltage
*/
HAL_PWREx_ControlVoltageScaling(PWR_REGULATOR_VOLTAGE_SCALE1);
/** Initializes the RCC Oscillators according to the specified parameters
* in the RCC_OscInitTypeDef structure.
*/
RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE;
RCC_OscInitStruct.HSEState = RCC_HSE_ON;
RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON;
RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE;
RCC_OscInitStruct.PLL.PLLM = RCC_PLLM_DIV1;
RCC_OscInitStruct.PLL.PLLN = 16;
RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV2;
RCC_OscInitStruct.PLL.PLLR = RCC_PLLR_DIV3;
if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK) {
Error_Handler();
}
/** Initializes the CPU, AHB and APB buses clocks
*/
RCC_ClkInitStruct.ClockType =
RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_SYSCLK | RCC_CLOCKTYPE_PCLK1;
RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK;
RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1;
RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV1;
if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_2) != HAL_OK) {
Error_Handler();
}
/** Initializes the peripherals clocks
*/
PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_USART1;
PeriphClkInit.Usart1ClockSelection = RCC_USART1CLKSOURCE_PCLK1;
if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInit) != HAL_OK) {
Error_Handler();
}
}
/* USER CODE BEGIN 4 */
/* USER CODE END 4 */
/**
* @brief This function is executed in case of error occurrence.
* @retval None
*/
void Error_Handler(void) {
/* USER CODE BEGIN Error_Handler_Debug */
/* User can add his own implementation to report the HAL error return state
*/
__disable_irq();
while (1) {
}
/* USER CODE END Error_Handler_Debug */
}
#ifdef USE_FULL_ASSERT
/**
* @brief Reports the name of the source file and the source line number
* where the assert_param error has occurred.
* @param file: pointer to the source file name
* @param line: assert_param error line source number
* @retval None
*/
void assert_failed(uint8_t* file, uint32_t line) {
/* USER CODE BEGIN 6 */
/* User can add his own implementation to report the file name and line
number, ex: printf("Wrong parameters value: file %s on line %d\r\n",
file, line) */
/* USER CODE END 6 */
}
#endif /* USE_FULL_ASSERT */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -0,0 +1,86 @@
/* USER CODE BEGIN Header */
/**
******************************************************************************
* @file : main.h
* @brief : Header for main.c file.
* This file contains the common defines of the application.
******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2021 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software component is licensed by ST under BSD 3-Clause license,
* the "License"; You may not use this file except in compliance with the
* License. You may obtain a copy of the License at:
* opensource.org/licenses/BSD-3-Clause
*
******************************************************************************
*/
/* USER CODE END Header */
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __MAIN_H
#define __MAIN_H
#ifdef __cplusplus
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
#include <stdio.h>
#include "stm32g0xx_hal.h"
#include "stm32g0xx_ll_bus.h"
#include "stm32g0xx_ll_cortex.h"
#include "stm32g0xx_ll_dma.h"
#include "stm32g0xx_ll_exti.h"
#include "stm32g0xx_ll_gpio.h"
#include "stm32g0xx_ll_pwr.h"
#include "stm32g0xx_ll_rcc.h"
#include "stm32g0xx_ll_system.h"
#include "stm32g0xx_ll_usart.h"
#include "stm32g0xx_ll_utils.h"
#if defined(USE_FULL_ASSERT)
#include "stm32_assert.h"
#endif /* USE_FULL_ASSERT */
/* Private includes ----------------------------------------------------------*/
/* USER CODE BEGIN Includes */
/* USER CODE END Includes */
/* Exported types ------------------------------------------------------------*/
/* USER CODE BEGIN ET */
/* USER CODE END ET */
/* Exported constants --------------------------------------------------------*/
/* USER CODE BEGIN EC */
/* USER CODE END EC */
/* Exported macro ------------------------------------------------------------*/
/* USER CODE BEGIN EM */
/* USER CODE END EM */
/* Exported functions prototypes ---------------------------------------------*/
void Error_Handler(void);
/* USER CODE BEGIN EFP */
/* USER CODE END EFP */
/* Private defines -----------------------------------------------------------*/
/* USER CODE BEGIN Private defines */
/* USER CODE END Private defines */
#ifdef __cplusplus
}
#endif
#endif /* __MAIN_H */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -0,0 +1,237 @@
;******************************************************************************
;* File Name : startup_stm32g030xx.s
;* Author : MCD Application Team
;* Description : STM32G030xx devices vector table for MDK-ARM toolchain.
;* This module performs:
;* - Set the initial SP
;* - Set the initial PC == Reset_Handler
;* - Set the vector table entries with the exceptions ISR address
;* - Branches to __main in the C library (which eventually
;* calls main()).
;* After Reset the CortexM0 processor is in Thread mode,
;* priority is Privileged, and the Stack is set to Main.
;* <<< Use Configuration Wizard in Context Menu >>>
;******************************************************************************
;* @attention
;*
;* Copyright (c) 2019 STMicroelectronics. All rights reserved.
;*
;* This software component is licensed by ST under Apache License, Version 2.0,
;* the "License"; You may not use this file except in compliance with the
;* License. You may obtain a copy of the License at:
;* opensource.org/licenses/Apache-2.0
;*
;******************************************************************************
; Amount of memory (in bytes) allocated for Stack
; Tailor this value to your application needs
; <h> Stack Configuration
; <o> Stack Size (in Bytes) <0x0-0xFFFFFFFF:8>
; </h>
Stack_Size EQU 0x400
AREA STACK, NOINIT, READWRITE, ALIGN=3
Stack_Mem SPACE Stack_Size
__initial_sp
; <h> Heap Configuration
; <o> Heap Size (in Bytes) <0x0-0xFFFFFFFF:8>
; </h>
Heap_Size EQU 0x1B00
AREA HEAP, NOINIT, READWRITE, ALIGN=3
__heap_base
Heap_Mem SPACE Heap_Size
__heap_limit
PRESERVE8
THUMB
; Vector Table Mapped to Address 0 at Reset
AREA RESET, DATA, READONLY
EXPORT __Vectors
EXPORT __Vectors_End
EXPORT __Vectors_Size
__Vectors DCD __initial_sp ; Top of Stack
DCD Reset_Handler ; Reset Handler
DCD NMI_Handler ; NMI Handler
DCD HardFault_Handler ; Hard Fault Handler
DCD 0 ; Reserved
DCD 0 ; Reserved
DCD 0 ; Reserved
DCD 0 ; Reserved
DCD 0 ; Reserved
DCD 0 ; Reserved
DCD 0 ; Reserved
DCD SVC_Handler ; SVCall Handler
DCD 0 ; Reserved
DCD 0 ; Reserved
DCD PendSV_Handler ; PendSV Handler
DCD SysTick_Handler ; SysTick Handler
; External Interrupts
DCD WWDG_IRQHandler ; Window Watchdog
DCD 0 ; Reserved
DCD RTC_TAMP_IRQHandler ; RTC through EXTI Line
DCD FLASH_IRQHandler ; FLASH
DCD RCC_IRQHandler ; RCC
DCD EXTI0_1_IRQHandler ; EXTI Line 0 and 1
DCD EXTI2_3_IRQHandler ; EXTI Line 2 and 3
DCD EXTI4_15_IRQHandler ; EXTI Line 4 to 15
DCD 0 ; Reserved
DCD DMA1_Channel1_IRQHandler ; DMA1 Channel 1
DCD DMA1_Channel2_3_IRQHandler ; DMA1 Channel 2 and Channel 3
DCD DMA1_Ch4_5_DMAMUX1_OVR_IRQHandler ; DMA1 Channel 4 to Channel 5, DMAMUX1 overrun
DCD ADC1_IRQHandler ; ADC1
DCD TIM1_BRK_UP_TRG_COM_IRQHandler ; TIM1 Break, Update, Trigger and Commutation
DCD TIM1_CC_IRQHandler ; TIM1 Capture Compare
DCD 0 ; Reserved
DCD TIM3_IRQHandler ; TIM3
DCD 0 ; Reserved
DCD 0 ; Reserved
DCD TIM14_IRQHandler ; TIM14
DCD 0 ; Reserved
DCD TIM16_IRQHandler ; TIM16
DCD TIM17_IRQHandler ; TIM17
DCD I2C1_IRQHandler ; I2C1
DCD I2C2_IRQHandler ; I2C2
DCD SPI1_IRQHandler ; SPI1
DCD SPI2_IRQHandler ; SPI2
DCD USART1_IRQHandler ; USART1
DCD USART2_IRQHandler ; USART2
DCD 0 ; Reserved
DCD 0 ; Reserved
DCD 0 ; Reserved
__Vectors_End
__Vectors_Size EQU __Vectors_End - __Vectors
AREA |.text|, CODE, READONLY
; Reset handler routine
Reset_Handler PROC
EXPORT Reset_Handler [WEAK]
IMPORT __main
IMPORT SystemInit
LDR R0, =SystemInit
BLX R0
LDR R0, =__main
BX R0
ENDP
; Dummy Exception Handlers (infinite loops which can be modified)
NMI_Handler PROC
EXPORT NMI_Handler [WEAK]
B .
ENDP
HardFault_Handler\
PROC
EXPORT HardFault_Handler [WEAK]
B .
ENDP
SVC_Handler PROC
EXPORT SVC_Handler [WEAK]
B .
ENDP
PendSV_Handler PROC
EXPORT PendSV_Handler [WEAK]
B .
ENDP
SysTick_Handler PROC
EXPORT SysTick_Handler [WEAK]
B .
ENDP
Default_Handler PROC
EXPORT WWDG_IRQHandler [WEAK]
EXPORT RTC_TAMP_IRQHandler [WEAK]
EXPORT FLASH_IRQHandler [WEAK]
EXPORT RCC_IRQHandler [WEAK]
EXPORT EXTI0_1_IRQHandler [WEAK]
EXPORT EXTI2_3_IRQHandler [WEAK]
EXPORT EXTI4_15_IRQHandler [WEAK]
EXPORT DMA1_Channel1_IRQHandler [WEAK]
EXPORT DMA1_Channel2_3_IRQHandler [WEAK]
EXPORT DMA1_Ch4_5_DMAMUX1_OVR_IRQHandler [WEAK]
EXPORT ADC1_IRQHandler [WEAK]
EXPORT TIM1_BRK_UP_TRG_COM_IRQHandler [WEAK]
EXPORT TIM1_CC_IRQHandler [WEAK]
EXPORT TIM3_IRQHandler [WEAK]
EXPORT TIM14_IRQHandler [WEAK]
EXPORT TIM16_IRQHandler [WEAK]
EXPORT TIM17_IRQHandler [WEAK]
EXPORT I2C1_IRQHandler [WEAK]
EXPORT I2C2_IRQHandler [WEAK]
EXPORT SPI1_IRQHandler [WEAK]
EXPORT SPI2_IRQHandler [WEAK]
EXPORT USART1_IRQHandler [WEAK]
EXPORT USART2_IRQHandler [WEAK]
WWDG_IRQHandler
RTC_TAMP_IRQHandler
FLASH_IRQHandler
RCC_IRQHandler
EXTI0_1_IRQHandler
EXTI2_3_IRQHandler
EXTI4_15_IRQHandler
DMA1_Channel1_IRQHandler
DMA1_Channel2_3_IRQHandler
DMA1_Ch4_5_DMAMUX1_OVR_IRQHandler
ADC1_IRQHandler
TIM1_BRK_UP_TRG_COM_IRQHandler
TIM1_CC_IRQHandler
TIM3_IRQHandler
TIM14_IRQHandler
TIM16_IRQHandler
TIM17_IRQHandler
I2C1_IRQHandler
I2C2_IRQHandler
SPI1_IRQHandler
SPI2_IRQHandler
USART1_IRQHandler
USART2_IRQHandler
B .
ENDP
ALIGN
;*******************************************************************************
; User Stack and Heap initialization
;*******************************************************************************
IF :DEF:__MICROLIB
EXPORT __initial_sp
EXPORT __heap_base
EXPORT __heap_limit
ELSE
IMPORT __use_two_region_memory
EXPORT __user_initial_stackheap
__user_initial_stackheap
LDR R0, = Heap_Mem
LDR R1, =(Stack_Mem + Stack_Size)
LDR R2, = (Heap_Mem + Heap_Size)
LDR R3, = Stack_Mem
BX LR
ALIGN
ENDIF
END
;************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE*****

View File

@ -0,0 +1,295 @@
#include "stm32g030_pika_msp.h"
#include "main.h"
/* support printf */
void HARDWARE_PRINTF_Init(void) {
LL_USART_InitTypeDef USART_InitStruct = {0};
LL_GPIO_InitTypeDef GPIO_InitStruct = {0};
/* Peripheral clock enable */
LL_APB2_GRP1_EnableClock(LL_APB2_GRP1_PERIPH_USART1);
LL_IOP_GRP1_EnableClock(LL_IOP_GRP1_PERIPH_GPIOA);
/**USART1 GPIO Configuration
PA9 ------> USART1_TX
PA10 ------> USART1_RX
*/
GPIO_InitStruct.Pin = LL_GPIO_PIN_9;
GPIO_InitStruct.Mode = LL_GPIO_MODE_ALTERNATE;
GPIO_InitStruct.Speed = LL_GPIO_SPEED_FREQ_LOW;
GPIO_InitStruct.OutputType = LL_GPIO_OUTPUT_PUSHPULL;
GPIO_InitStruct.Pull = LL_GPIO_PULL_NO;
GPIO_InitStruct.Alternate = LL_GPIO_AF_1;
LL_GPIO_Init(GPIOA, &GPIO_InitStruct);
GPIO_InitStruct.Pin = LL_GPIO_PIN_10;
GPIO_InitStruct.Mode = LL_GPIO_MODE_ALTERNATE;
GPIO_InitStruct.Speed = LL_GPIO_SPEED_FREQ_LOW;
GPIO_InitStruct.OutputType = LL_GPIO_OUTPUT_PUSHPULL;
GPIO_InitStruct.Pull = LL_GPIO_PULL_NO;
GPIO_InitStruct.Alternate = LL_GPIO_AF_1;
LL_GPIO_Init(GPIOA, &GPIO_InitStruct);
/* USART1 interrupt Init */
NVIC_SetPriority(USART1_IRQn, 0);
NVIC_EnableIRQ(USART1_IRQn);
USART_InitStruct.PrescalerValue = LL_USART_PRESCALER_DIV1;
USART_InitStruct.BaudRate = 115200;
USART_InitStruct.DataWidth = LL_USART_DATAWIDTH_8B;
USART_InitStruct.StopBits = LL_USART_STOPBITS_1;
USART_InitStruct.Parity = LL_USART_PARITY_NONE;
USART_InitStruct.TransferDirection = LL_USART_DIRECTION_TX_RX;
USART_InitStruct.HardwareFlowControl = LL_USART_HWCONTROL_NONE;
USART_InitStruct.OverSampling = LL_USART_OVERSAMPLING_16;
LL_USART_Init(USART1, &USART_InitStruct);
LL_USART_SetTXFIFOThreshold(USART1, LL_USART_FIFOTHRESHOLD_1_8);
LL_USART_SetRXFIFOThreshold(USART1, LL_USART_FIFOTHRESHOLD_1_8);
LL_USART_DisableFIFO(USART1);
LL_USART_ConfigAsyncMode(USART1);
LL_USART_Enable(USART1);
/* Polling USART1 initialisation */
while ((!(LL_USART_IsActiveFlag_TEACK(USART1))) ||
(!(LL_USART_IsActiveFlag_REACK(USART1)))) {
}
/* open interrupt */
LL_USART_EnableIT_RXNE(USART1);
LL_USART_EnableIT_PE(USART1);
}
int fputc(int ch, FILE* f) {
char ch_ = ch;
LL_USART_TransmitData8(USART1, ch);
while (LL_USART_IsActiveFlag_TC(USART1) != 1)
;
return ch;
}
/* support pika Asm to flash */
uint32_t globalWriteAddress = 0;
uint32_t GetPage(uint32_t Addr) {
return (Addr - FLASH_BASE) / FLASH_PAGE_SIZE;
}
int32_t __eriseSelecttedFlash(uint32_t flashStart, uint32_t flashEnd) {
uint32_t FirstPage = 0, NbOfPages = 0;
uint32_t PageError = 0;
__IO uint32_t data32 = 0, MemoryProgramStatus = 0;
static FLASH_EraseInitTypeDef EraseInitStruct = {0};
HAL_FLASH_Unlock();
/* Get the 1st page to erase */
FirstPage = GetPage(flashStart);
/* Get the number of pages to erase from 1st page */
NbOfPages = GetPage(flashEnd) - FirstPage + 1;
/* Fill EraseInit structure*/
EraseInitStruct.TypeErase = FLASH_TYPEERASE_PAGES;
EraseInitStruct.Page = FirstPage;
EraseInitStruct.NbPages = NbOfPages;
if (HAL_FLASHEx_Erase(&EraseInitStruct, &PageError) != HAL_OK) {
return 1;
}
return 0;
}
uint32_t flash_write_char(uint32_t bassAddr,
uint32_t flash_addr,
char ch_input) {
static uint8_t writeBuff[8] = {0};
static uint8_t offset = 0;
if (offset > 7) {
offset = 0;
uint64_t writeData64 = 0;
for (int i = 7; i >= 0; i--) {
char ch = writeBuff[i];
writeData64 = writeData64 << 8;
writeData64 += ch;
}
__platformDisableIrqHandle();
if (HAL_FLASH_Program(FLASH_TYPEPROGRAM_DOUBLEWORD,
bassAddr + flash_addr, writeData64) != HAL_OK) {
while (1) {
offset = 0;
}
}
__platformDisableIrqHandle();
flash_addr = flash_addr + 8;
}
writeBuff[offset] = ch_input;
offset++;
return flash_addr;
}
uint8_t __platformAsmIsToFlash(char* pyMultiLine) {
if (strCountSign(pyMultiLine, '\n') > 1) {
return 1;
}
return 0;
}
int32_t __saveStrToFlash(char* str,
uint32_t flashStart,
uint32_t flashEnd,
uint32_t* writeAddress_p) {
uint32_t size = strGetSize(str);
for (int i = 0; i < size; i++) {
(*writeAddress_p) =
flash_write_char(flashStart, (*writeAddress_p), str[i]);
}
return 0;
}
char* __platformLoadPikaAsm() {
return (char*)FLASH_PIKA_ASM_START_ADDR;
}
int32_t __platformSavePikaAsm(char* PikaAsm) {
if (0 == globalWriteAddress) {
__eriseSelecttedFlash(FLASH_PIKA_ASM_START_ADDR,
FLASH_PIKA_ASM_END_ADDR);
}
return __saveStrToFlash(PikaAsm, FLASH_PIKA_ASM_START_ADDR,
FLASH_PIKA_ASM_END_ADDR, &globalWriteAddress);
}
int32_t __platformSavePikaAsmEOF() {
for (int i = 0; i < 16; i++) {
globalWriteAddress = flash_write_char(FLASH_PIKA_ASM_START_ADDR,
globalWriteAddress, '\0');
}
return 0;
}
/* support download python script by uart1 */
CodeHeap codeHeap;
void STM32_Code_Init() {
codeHeap.size = 0;
codeHeap.content = pikaMalloc(codeHeap.size + 1);
codeHeap.ena = 0;
}
uint8_t STM32_Code_reciveHandler(char* data, uint32_t rxSize) {
char buff[RX_BUFF_LENGTH] = {0};
if (0 == codeHeap.ena) {
char* strLine = strGetLastLine(buff, data);
if (strIsStartWith(strLine, "import ")) {
codeHeap.reciveTime = uwTick;
codeHeap.ena = 1;
data = strLine;
}
}
if (1 == codeHeap.ena) {
codeHeap.reciveTime = uwTick;
codeHeap.oldSize = codeHeap.size;
codeHeap.size += rxSize;
codeHeap.content = realloc(codeHeap.content, codeHeap.size + 1);
memcpy(codeHeap.content + codeHeap.oldSize, data, rxSize);
codeHeap.content[codeHeap.size] = 0;
/* reciving code */
return 1;
}
/* not work */
return 0;
}
void STM32_Code_flashHandler() {
if (!codeHeap.ena) {
/* recive not activate */
return;
}
if (uwTick - codeHeap.reciveTime < 200) {
/* still reciving */
return;
}
/* transmite is finished */
STM32_Code_reciveHandler("\n\n", 2);
uint32_t FirstPage = 0, NbOfPages = 0;
uint32_t PageError = 0;
__IO uint32_t data32 = 0, MemoryProgramStatus = 0;
static FLASH_EraseInitTypeDef EraseInitStruct = {0};
printf("==============[Programer]==============\r\n");
printf("[info]: Recived byte: %d\r\n", codeHeap.size);
printf("[info]: Programing... \r\n");
HAL_FLASH_Unlock();
/* Get the 1st page to erase */
FirstPage = GetPage(FLASH_SCRIPT_START_ADDR);
/* Get the number of pages to erase from 1st page */
NbOfPages = GetPage(FLASH_SCRIPT_END_ADDR) - FirstPage + 1;
/* Fill EraseInit structure*/
EraseInitStruct.TypeErase = FLASH_TYPEERASE_PAGES;
EraseInitStruct.Page = FirstPage;
EraseInitStruct.NbPages = NbOfPages;
printf("[info]: Erasing flash... \r\n");
if (HAL_FLASHEx_Erase(&EraseInitStruct, &PageError) != HAL_OK) {
printf("[error]: Erase faild! \r\n");
while (1) {
}
}
printf("[ OK ]: Erase flash ok! \r\n");
printf("[info]: Writing flash... \r\n");
uint32_t baseAddress = FLASH_SCRIPT_START_ADDR;
uint32_t writeAddress = 0;
uint64_t writeData64 = 0;
while (writeAddress < codeHeap.size + 1) {
writeData64 = 0;
for (int i = 7; i >= 0; i--) {
char ch = codeHeap.content[writeAddress + i];
writeData64 = writeData64 << 8;
writeData64 += ch;
}
if (HAL_FLASH_Program(FLASH_TYPEPROGRAM_DOUBLEWORD,
baseAddress + writeAddress,
writeData64) == HAL_OK) {
writeAddress = writeAddress + 8;
} else {
printf("[error]: Write flash faild. \r\n");
while (1) {
}
}
}
HAL_FLASH_Lock();
printf("[ OK ]: Write flash ok! \r\n");
baseAddress = FLASH_SCRIPT_START_ADDR;
MemoryProgramStatus = 0x0;
printf("[info]: Checking flash... \r\n");
char* codeInFlash = (char*)baseAddress;
printf("\r\n");
printf("----[code in flash]-----\r\n");
printf("%s", codeInFlash);
printf("----[code in flash]-----\r\n");
printf("\r\n");
if (!strEqu(codeInFlash, codeHeap.content)) {
printf("[error]: Check flash faild.\r\n");
printf("\r\n");
printf("\r\n\r\n");
printf("---------[code in heap]----------\r\n");
printf("\r\n");
printf("%s", codeHeap.content);
printf("\r\n\r\n");
printf("---------[code in heap]----------\r\n");
while (1) {
}
}
printf("[ OK ]: Checking flash ok! \r\n");
printf("[ OK ]: Programing ok! \r\n");
printf("[info]: Restarting... \r\n");
printf("==============[Programer]==============\r\n");
printf("\r\n");
HAL_NVIC_SystemReset();
}

View File

@ -0,0 +1,53 @@
#ifndef __STM32G030_PIKA_PORT__H
#define __STM32G030_PIKA_PORT__H
#include <stdint.h>
#include "pikaObj.h"
typedef struct _CodeHeap{
char *content;
uint32_t size;
uint8_t ena;
uint32_t reciveTime;
uint32_t oldSize;
}CodeHeap;
/* support std lib for stm32 */
#define delay_ms HAL_Delay
typedef uint16_t u16;
typedef uint8_t u8;
typedef uint32_t u32;
#define GPIO_Pin_0 GPIO_PIN_0
#define GPIO_Pin_1 GPIO_PIN_1
#define GPIO_Pin_2 GPIO_PIN_2
#define GPIO_Pin_3 GPIO_PIN_3
#define GPIO_Pin_4 GPIO_PIN_4
#define GPIO_Pin_5 GPIO_PIN_5
#define GPIO_Pin_6 GPIO_PIN_6
#define GPIO_Pin_7 GPIO_PIN_7
#define GPIO_Pin_8 GPIO_PIN_8
#define GPIO_Pin_9 GPIO_PIN_9
#define GPIO_Pin_10 GPIO_PIN_10
#define GPIO_Pin_11 GPIO_PIN_11
#define GPIO_Pin_12 GPIO_PIN_12
#define GPIO_Pin_13 GPIO_PIN_13
#define GPIO_Pin_14 GPIO_PIN_14
#define GPIO_Pin_15 GPIO_PIN_15
/* support pinrtf */
void HARDWARE_PRINTF_Init(void);
/* support write asm to flash */
#define FLASH_SCRIPT_START_ADDR (FLASH_BASE + ((FLASH_PAGE_NB - 2) * FLASH_PAGE_SIZE))
#define FLASH_SCRIPT_END_ADDR (FLASH_BASE + FLASH_SIZE - 1)
#define FLASH_PIKA_ASM_START_ADDR FLASH_SCRIPT_START_ADDR
#define FLASH_PIKA_ASM_END_ADDR FLASH_SCRIPT_END_ADDR
#define RX_BUFF_LENGTH 32
/* support download python script by uart1 */
uint8_t STM32_Code_reciveHandler(char *data, uint32_t rxSize);
void STM32_Code_Init();
void STM32_Code_flashHandler();
#endif

View File

@ -0,0 +1,368 @@
/**
******************************************************************************
* @file stm32g0xx_hal_conf.h
* @author MCD Application Team
* @brief HAL configuration file.
******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2018 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software component is licensed by ST under BSD 3-Clause license,
* the "License"; You may not use this file except in compliance with the
* License. You may obtain a copy of the License at:
* opensource.org/licenses/BSD-3-Clause
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef STM32G0xx_HAL_CONF_H
#define STM32G0xx_HAL_CONF_H
#ifdef __cplusplus
extern "C" {
#endif
/* Exported types ------------------------------------------------------------*/
/* Exported constants --------------------------------------------------------*/
/* ########################## Module Selection ############################## */
/**
* @brief This is the list of modules to be used in the HAL driver
*/
#define HAL_MODULE_ENABLED
/* #define HAL_ADC_MODULE_ENABLED */
/* #define HAL_CEC_MODULE_ENABLED */
/* #define HAL_COMP_MODULE_ENABLED */
/* #define HAL_CRC_MODULE_ENABLED */
/* #define HAL_CRYP_MODULE_ENABLED */
/* #define HAL_DAC_MODULE_ENABLED */
/* #define HAL_EXTI_MODULE_ENABLED */
/* #define HAL_FDCAN_MODULE_ENABLED */
/* #define HAL_HCD_MODULE_ENABLED */
/* #define HAL_I2C_MODULE_ENABLED */
/* #define HAL_I2S_MODULE_ENABLED */
/* #define HAL_IWDG_MODULE_ENABLED */
/* #define HAL_IRDA_MODULE_ENABLED */
/* #define HAL_LPTIM_MODULE_ENABLED */
/* #define HAL_PCD_MODULE_ENABLED */
/* #define HAL_RNG_MODULE_ENABLED */
/* #define HAL_RTC_MODULE_ENABLED */
/* #define HAL_SMARTCARD_MODULE_ENABLED */
/* #define HAL_SMBUS_MODULE_ENABLED */
/* #define HAL_SPI_MODULE_ENABLED */
/* #define HAL_TIM_MODULE_ENABLED */
/* #define HAL_UART_MODULE_ENABLED */
/* #define HAL_USART_MODULE_ENABLED */
/* #define HAL_WWDG_MODULE_ENABLED */
#define HAL_GPIO_MODULE_ENABLED
#define HAL_EXTI_MODULE_ENABLED
#define HAL_DMA_MODULE_ENABLED
#define HAL_RCC_MODULE_ENABLED
#define HAL_FLASH_MODULE_ENABLED
#define HAL_PWR_MODULE_ENABLED
#define HAL_CORTEX_MODULE_ENABLED
#define HAL_ADC_MODULE_ENABLED
#define HAL_UART_MODULE_ENABLED
#define HAL_USART_MODULE_ENABLED
#define HAL_TIM_MODULE_ENABLED
#define HAL_SPI_MODULE_ENABLED
/* ########################## Register Callbacks selection
* ############################## */
/**
* @brief This is the list of modules where register callback can be used
*/
#define USE_HAL_ADC_REGISTER_CALLBACKS 0u
#define USE_HAL_CEC_REGISTER_CALLBACKS 0u
#define USE_HAL_COMP_REGISTER_CALLBACKS 0u
#define USE_HAL_CRYP_REGISTER_CALLBACKS 0u
#define USE_HAL_DAC_REGISTER_CALLBACKS 0u
#define USE_HAL_FDCAN_REGISTER_CALLBACKS 0u
#define USE_HAL_HCD_REGISTER_CALLBACKS 0u
#define USE_HAL_I2C_REGISTER_CALLBACKS 0u
#define USE_HAL_I2S_REGISTER_CALLBACKS 0u
#define USE_HAL_IRDA_REGISTER_CALLBACKS 0u
#define USE_HAL_LPTIM_REGISTER_CALLBACKS 0u
#define USE_HAL_PCD_REGISTER_CALLBACKS 0u
#define USE_HAL_RNG_REGISTER_CALLBACKS 0u
#define USE_HAL_RTC_REGISTER_CALLBACKS 0u
#define USE_HAL_SMBUS_REGISTER_CALLBACKS 0u
#define USE_HAL_SPI_REGISTER_CALLBACKS 0u
#define USE_HAL_TIM_REGISTER_CALLBACKS 0u
#define USE_HAL_UART_REGISTER_CALLBACKS 0u
#define USE_HAL_USART_REGISTER_CALLBACKS 0u
#define USE_HAL_WWDG_REGISTER_CALLBACKS 0u
/* ########################## Oscillator Values adaptation
* ####################*/
/**
* @brief Adjust the value of External High Speed oscillator (HSE) used in your
* application. This value is used by the RCC HAL module to compute the system
* frequency (when HSE is used as system clock source, directly or through the
* PLL).
*/
#if !defined(HSE_VALUE)
#define HSE_VALUE (12000000UL) /*!< Value of the External oscillator in Hz */
#endif /* HSE_VALUE */
#if !defined(HSE_STARTUP_TIMEOUT)
#define HSE_STARTUP_TIMEOUT (100UL) /*!< Time out for HSE start up, in ms */
#endif /* HSE_STARTUP_TIMEOUT */
/**
* @brief Internal High Speed oscillator (HSI) value.
* This value is used by the RCC HAL module to compute the system
* frequency (when HSI is used as system clock source, directly or through the
* PLL).
*/
#if !defined(HSI_VALUE)
#define HSI_VALUE (16000000UL) /*!< Value of the Internal oscillator in Hz*/
#endif /* HSI_VALUE */
#if defined(STM32G0C1xx) || defined(STM32G0B1xx) || defined(STM32G0B0xx)
/**
* @brief Internal High Speed oscillator (HSI48) value for USB FS, SDMMC and
* RNG. This internal oscillator is mainly dedicated to provide a high precision
* clock to the USB peripheral by means of a special Clock Recovery System (CRS)
* circuitry. When the CRS is not used, the HSI48 RC oscillator runs on it
* default frequency which is subject to manufacturing process variations.
*/
#if !defined(HSI48_VALUE)
#define HSI48_VALUE \
48000000U /*!< Value of the Internal High Speed oscillator for USB \
FS/SDMMC/RNG in Hz. The real value my vary depending on \
manufacturing process variations.*/
#endif /* HSI48_VALUE */
#endif
/**
* @brief Internal Low Speed oscillator (LSI) value.
*/
#if !defined(LSI_VALUE)
#define LSI_VALUE (32000UL) /*!< LSI Typical Value in Hz*/
#endif /* LSI_VALUE */ /*!< Value of the Internal Low Speed oscillator in Hz \
The real value may vary depending on the variations \
in voltage and temperature.*/
/**
* @brief External Low Speed oscillator (LSE) value.
* This value is used by the UART, RTC HAL module to compute the system
* frequency
*/
#if !defined(LSE_VALUE)
#define LSE_VALUE (32768UL) /*!< Value of the External oscillator in Hz*/
#endif /* LSE_VALUE */
#if !defined(LSE_STARTUP_TIMEOUT)
#define LSE_STARTUP_TIMEOUT (5000UL) /*!< Time out for LSE start up, in ms */
#endif /* LSE_STARTUP_TIMEOUT */
/**
* @brief External clock source for I2S1 peripheral
* This value is used by the RCC HAL module to compute the I2S1 clock
* source frequency.
*/
#if !defined(EXTERNAL_I2S1_CLOCK_VALUE)
#define EXTERNAL_I2S1_CLOCK_VALUE \
(12288000UL) /*!< Value of the I2S1 External clock source in Hz*/
#endif /* EXTERNAL_I2S1_CLOCK_VALUE */
#if defined(STM32G0C1xx) || defined(STM32G0B1xx) || defined(STM32G0B0xx)
/**
* @brief External clock source for I2S2 peripheral
* This value is used by the RCC HAL module to compute the I2S2 clock
* source frequency.
*/
#if !defined(EXTERNAL_I2S2_CLOCK_VALUE)
#define EXTERNAL_I2S2_CLOCK_VALUE \
48000U /*!< Value of the I2S2 External clock source in Hz*/
#endif /* EXTERNAL_I2S2_CLOCK_VALUE */
#endif
/* Tip: To avoid modifying this file each time you need to use different HSE,
=== you can define the HSE value in your toolchain compiler preprocessor. */
/* ########################### System Configuration ######################### */
/**
* @brief This is the HAL system configuration section
*/
#define VDD_VALUE (3300UL) /*!< Value of VDD in mv */
#define TICK_INT_PRIORITY 0U /*!< tick interrupt priority */
#define USE_RTOS 0U
#define PREFETCH_ENABLE 1U
#define INSTRUCTION_CACHE_ENABLE 1U
/* ################## SPI peripheral configuration ########################## */
/* CRC FEATURE: Use to activate CRC feature inside HAL SPI Driver
* Activated: CRC code is present inside driver
* Deactivated: CRC code cleaned from driver
*/
#define USE_SPI_CRC 0U
/* ################## CRYP peripheral configuration ##########################
*/
#define USE_HAL_CRYP_SUSPEND_RESUME 1U
/* ########################## Assert Selection ############################## */
/**
* @brief Uncomment the line below to expanse the "assert_param" macro in the
* HAL drivers code
*/
/* #define USE_FULL_ASSERT 1U */
/* Includes ------------------------------------------------------------------*/
/**
* @brief Include modules header file
*/
#ifdef HAL_RCC_MODULE_ENABLED
#include "stm32g0xx_hal_rcc.h"
#endif /* HAL_RCC_MODULE_ENABLED */
#ifdef HAL_GPIO_MODULE_ENABLED
#include "stm32g0xx_hal_gpio.h"
#endif /* HAL_GPIO_MODULE_ENABLED */
#ifdef HAL_DMA_MODULE_ENABLED
#include "stm32g0xx_hal_dma.h"
#endif /* HAL_DMA_MODULE_ENABLED */
#ifdef HAL_CORTEX_MODULE_ENABLED
#include "stm32g0xx_hal_cortex.h"
#endif /* HAL_CORTEX_MODULE_ENABLED */
#ifdef HAL_ADC_MODULE_ENABLED
#include "stm32g0xx_hal_adc.h"
#include "stm32g0xx_hal_adc_ex.h"
#endif /* HAL_ADC_MODULE_ENABLED */
#ifdef HAL_CEC_MODULE_ENABLED
#include "stm32g0xx_hal_cec.h"
#endif /* HAL_CEC_MODULE_ENABLED */
#ifdef HAL_COMP_MODULE_ENABLED
#include "stm32g0xx_hal_comp.h"
#endif /* HAL_COMP_MODULE_ENABLED */
#ifdef HAL_CRC_MODULE_ENABLED
#include "stm32g0xx_hal_crc.h"
#endif /* HAL_CRC_MODULE_ENABLED */
#ifdef HAL_CRYP_MODULE_ENABLED
#include "stm32g0xx_hal_cryp.h"
#endif /* HAL_CRYP_MODULE_ENABLED */
#ifdef HAL_DAC_MODULE_ENABLED
#include "stm32g0xx_hal_dac.h"
#endif /* HAL_DAC_MODULE_ENABLED */
#ifdef HAL_EXTI_MODULE_ENABLED
#include "stm32g0xx_hal_exti.h"
#endif /* HAL_EXTI_MODULE_ENABLED */
#ifdef HAL_FLASH_MODULE_ENABLED
#include "stm32g0xx_hal_flash.h"
#endif /* HAL_FLASH_MODULE_ENABLED */
#ifdef HAL_FDCAN_MODULE_ENABLED
#include "stm32g0xx_hal_fdcan.h"
#endif /* HAL_FDCAN_MODULE_ENABLED */
#ifdef HAL_HCD_MODULE_ENABLED
#include "stm32g0xx_hal_hcd.h"
#endif /* HAL_HCD_MODULE_ENABLED */
#ifdef HAL_I2C_MODULE_ENABLED
#include "stm32g0xx_hal_i2c.h"
#endif /* HAL_I2C_MODULE_ENABLED */
#ifdef HAL_I2S_MODULE_ENABLED
#include "stm32g0xx_hal_i2s.h"
#endif /* HAL_I2S_MODULE_ENABLED */
#ifdef HAL_IRDA_MODULE_ENABLED
#include "stm32g0xx_hal_irda.h"
#endif /* HAL_IRDA_MODULE_ENABLED */
#ifdef HAL_IWDG_MODULE_ENABLED
#include "stm32g0xx_hal_iwdg.h"
#endif /* HAL_IWDG_MODULE_ENABLED */
#ifdef HAL_LPTIM_MODULE_ENABLED
#include "stm32g0xx_hal_lptim.h"
#endif /* HAL_LPTIM_MODULE_ENABLED */
#ifdef HAL_PCD_MODULE_ENABLED
#include "stm32g0xx_hal_pcd.h"
#endif /* HAL_PCD_MODULE_ENABLED */
#ifdef HAL_PWR_MODULE_ENABLED
#include "stm32g0xx_hal_pwr.h"
#endif /* HAL_PWR_MODULE_ENABLED */
#ifdef HAL_RNG_MODULE_ENABLED
#include "stm32g0xx_hal_rng.h"
#endif /* HAL_RNG_MODULE_ENABLED */
#ifdef HAL_RTC_MODULE_ENABLED
#include "stm32g0xx_hal_rtc.h"
#endif /* HAL_RTC_MODULE_ENABLED */
#ifdef HAL_SMARTCARD_MODULE_ENABLED
#include "stm32g0xx_hal_smartcard.h"
#endif /* HAL_SMARTCARD_MODULE_ENABLED */
#ifdef HAL_SMBUS_MODULE_ENABLED
#include "stm32g0xx_hal_smbus.h"
#endif /* HAL_SMBUS_MODULE_ENABLED */
#ifdef HAL_SPI_MODULE_ENABLED
#include "stm32g0xx_hal_spi.h"
#endif /* HAL_SPI_MODULE_ENABLED */
#ifdef HAL_TIM_MODULE_ENABLED
#include "stm32g0xx_hal_tim.h"
#endif /* HAL_TIM_MODULE_ENABLED */
#ifdef HAL_UART_MODULE_ENABLED
#include "stm32g0xx_hal_uart.h"
#endif /* HAL_UART_MODULE_ENABLED */
#ifdef HAL_USART_MODULE_ENABLED
#include "stm32g0xx_hal_usart.h"
#endif /* HAL_USART_MODULE_ENABLED */
#ifdef HAL_WWDG_MODULE_ENABLED
#include "stm32g0xx_hal_wwdg.h"
#endif /* HAL_WWDG_MODULE_ENABLED */
/* Exported macro ------------------------------------------------------------*/
#ifdef USE_FULL_ASSERT
/**
* @brief The assert_param macro is used for functions parameters check.
* @param expr If expr is false, it calls assert_failed function
* which reports the name of the source file and the source
* line number of the call that failed.
* If expr is true, it returns no value.
* @retval None
*/
#define assert_param(expr) \
((expr) ? (void)0U : assert_failed((uint8_t*)__FILE__, __LINE__))
/* Exported functions ------------------------------------------------------- */
void assert_failed(uint8_t* file, uint32_t line);
#else
#define assert_param(expr) ((void)0U)
#endif /* USE_FULL_ASSERT */
#ifdef __cplusplus
}
#endif
#endif /* STM32G0xx_HAL_CONF_H */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -0,0 +1,84 @@
/* USER CODE BEGIN Header */
/**
******************************************************************************
* @file stm32g0xx_hal_msp.c
* @brief This file provides code for the MSP Initialization
* and de-Initialization codes.
******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2021 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software component is licensed by ST under BSD 3-Clause license,
* the "License"; You may not use this file except in compliance with the
* License. You may obtain a copy of the License at:
* opensource.org/licenses/BSD-3-Clause
*
******************************************************************************
*/
/* USER CODE END Header */
/* Includes ------------------------------------------------------------------*/
#include "main.h"
/* USER CODE BEGIN Includes */
/* USER CODE END Includes */
/* Private typedef -----------------------------------------------------------*/
/* USER CODE BEGIN TD */
/* USER CODE END TD */
/* Private define ------------------------------------------------------------*/
/* USER CODE BEGIN Define */
/* USER CODE END Define */
/* Private macro -------------------------------------------------------------*/
/* USER CODE BEGIN Macro */
/* USER CODE END Macro */
/* Private variables ---------------------------------------------------------*/
/* USER CODE BEGIN PV */
/* USER CODE END PV */
/* Private function prototypes -----------------------------------------------*/
/* USER CODE BEGIN PFP */
/* USER CODE END PFP */
/* External functions --------------------------------------------------------*/
/* USER CODE BEGIN ExternalFunctions */
/* USER CODE END ExternalFunctions */
/* USER CODE BEGIN 0 */
/* USER CODE END 0 */
/**
* Initializes the Global MSP.
*/
void HAL_MspInit(void)
{
/* USER CODE BEGIN MspInit 0 */
/* USER CODE END MspInit 0 */
__HAL_RCC_SYSCFG_CLK_ENABLE();
__HAL_RCC_PWR_CLK_ENABLE();
/* System interrupt init*/
/* USER CODE BEGIN MspInit 1 */
/* USER CODE END MspInit 1 */
}
/* USER CODE BEGIN 1 */
/* USER CODE END 1 */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -0,0 +1,55 @@
/* Includes ------------------------------------------------------------------*/
#include "stm32g0xx_it.h"
#include "main.h"
#include "stm32g030_pika_msp.h"
char UART1_RxBuff[RX_BUFF_LENGTH] = {0};
uint16_t UART1_RXBuff_offset = 0;
extern char Shell_Buff[RX_BUFF_LENGTH];
extern uint8_t Shell_Ready;
void NMI_Handler(void) {
while (1) {
}
}
void HardFault_Handler(void) {
while (1) {
}
}
void SVC_Handler(void) {}
void PendSV_Handler(void) {}
void SysTick_Handler(void) {
HAL_IncTick();
STM32_Code_flashHandler();
}
void USART1_IRQHandler(void) {
if (LL_USART_IsActiveFlag_RXNE(USART1)) {
uint8_t inputChar = LL_USART_ReceiveData8(USART1);
/* clear buff when overflow */
if (UART1_RXBuff_offset >= RX_BUFF_LENGTH) {
UART1_RXBuff_offset = 0;
memset(UART1_RxBuff, 0, sizeof(UART1_RxBuff));
}
/* recive char */
UART1_RxBuff[UART1_RXBuff_offset] = inputChar;
UART1_RXBuff_offset++;
if ('\n' == inputChar) {
/* handle python script download */
if (STM32_Code_reciveHandler(UART1_RxBuff, UART1_RXBuff_offset)) {
goto line_exit;
}
/* handle python shell invoke */
memcpy(Shell_Buff, UART1_RxBuff, sizeof(Shell_Buff));
Shell_Ready = 1;
goto line_exit;
line_exit:
UART1_RXBuff_offset = 0;
memset(UART1_RxBuff, 0, sizeof(UART1_RxBuff));
return;
}
}
}

View File

@ -0,0 +1,65 @@
/* USER CODE BEGIN Header */
/**
******************************************************************************
* @file stm32g0xx_it.h
* @brief This file contains the headers of the interrupt handlers.
******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2021 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software component is licensed by ST under BSD 3-Clause license,
* the "License"; You may not use this file except in compliance with the
* License. You may obtain a copy of the License at:
* opensource.org/licenses/BSD-3-Clause
*
******************************************************************************
*/
/* USER CODE END Header */
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32G0xx_IT_H
#define __STM32G0xx_IT_H
#ifdef __cplusplus
extern "C" {
#endif
/* Private includes ----------------------------------------------------------*/
/* USER CODE BEGIN Includes */
/* USER CODE END Includes */
/* Exported types ------------------------------------------------------------*/
/* USER CODE BEGIN ET */
/* USER CODE END ET */
/* Exported constants --------------------------------------------------------*/
/* USER CODE BEGIN EC */
/* USER CODE END EC */
/* Exported macro ------------------------------------------------------------*/
/* USER CODE BEGIN EM */
/* USER CODE END EM */
/* Exported functions prototypes ---------------------------------------------*/
void NMI_Handler(void);
void HardFault_Handler(void);
void SVC_Handler(void);
void PendSV_Handler(void);
void SysTick_Handler(void);
/* USER CODE BEGIN EFP */
/* USER CODE END EFP */
#ifdef __cplusplus
}
#endif
#endif /* __STM32G0xx_IT_H */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -0,0 +1,290 @@
/**
******************************************************************************
* @file system_stm32g0xx.c
* @author MCD Application Team
* @brief CMSIS Cortex-M0+ Device Peripheral Access Layer System Source File
*
* This file provides two functions and one global variable to be called from
* user application:
* - SystemInit(): This function is called at startup just after reset and
* before branch to main program. This call is made inside
* the "startup_stm32g0xx.s" file.
*
* - SystemCoreClock variable: Contains the core clock (HCLK), it can be used
* by the user application to setup the SysTick
* timer or configure other parameters.
*
* - SystemCoreClockUpdate(): Updates the variable SystemCoreClock and must
* be called whenever the core clock is changed
* during program execution.
*
* After each device reset the HSI (8 MHz then 16 MHz) is used as system clock source.
* Then SystemInit() function is called, in "startup_stm32g0xx.s" file, to
* configure the system clock before to branch to main program.
*
* This file configures the system clock as follows:
*=============================================================================
*-----------------------------------------------------------------------------
* System Clock source | HSI
*-----------------------------------------------------------------------------
* SYSCLK(Hz) | 16000000
*-----------------------------------------------------------------------------
* HCLK(Hz) | 16000000
*-----------------------------------------------------------------------------
* AHB Prescaler | 1
*-----------------------------------------------------------------------------
* APB Prescaler | 1
*-----------------------------------------------------------------------------
* HSI Division factor | 1
*-----------------------------------------------------------------------------
* PLL_M | 1
*-----------------------------------------------------------------------------
* PLL_N | 8
*-----------------------------------------------------------------------------
* PLL_P | 7
*-----------------------------------------------------------------------------
* PLL_Q | 2
*-----------------------------------------------------------------------------
* PLL_R | 2
*-----------------------------------------------------------------------------
* Require 48MHz for RNG | Disabled
*-----------------------------------------------------------------------------
*=============================================================================
******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2018 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software component is licensed by ST under Apache License, Version 2.0,
* the "License"; You may not use this file except in compliance with the
* License. You may obtain a copy of the License at:
* opensource.org/licenses/Apache-2.0
*
******************************************************************************
*/
/** @addtogroup CMSIS
* @{
*/
/** @addtogroup stm32g0xx_system
* @{
*/
/** @addtogroup STM32G0xx_System_Private_Includes
* @{
*/
#include "stm32g0xx.h"
#if !defined (HSE_VALUE)
#define HSE_VALUE (8000000UL) /*!< Value of the External oscillator in Hz */
#endif /* HSE_VALUE */
#if !defined (HSI_VALUE)
#define HSI_VALUE (16000000UL) /*!< Value of the Internal oscillator in Hz*/
#endif /* HSI_VALUE */
#if !defined (LSI_VALUE)
#define LSI_VALUE (32000UL) /*!< Value of LSI in Hz*/
#endif /* LSI_VALUE */
#if !defined (LSE_VALUE)
#define LSE_VALUE (32768UL) /*!< Value of LSE in Hz*/
#endif /* LSE_VALUE */
/**
* @}
*/
/** @addtogroup STM32G0xx_System_Private_TypesDefinitions
* @{
*/
/**
* @}
*/
/** @addtogroup STM32G0xx_System_Private_Defines
* @{
*/
/************************* Miscellaneous Configuration ************************/
/*!< Uncomment the following line if you need to relocate your vector Table in
Internal SRAM. */
/* #define VECT_TAB_SRAM */
#define VECT_TAB_OFFSET 0x0U /*!< Vector Table base offset field.
This value must be a multiple of 0x100. */
/******************************************************************************/
/**
* @}
*/
/** @addtogroup STM32G0xx_System_Private_Macros
* @{
*/
/**
* @}
*/
/** @addtogroup STM32G0xx_System_Private_Variables
* @{
*/
/* The SystemCoreClock variable is updated in three ways:
1) by calling CMSIS function SystemCoreClockUpdate()
2) by calling HAL API function HAL_RCC_GetHCLKFreq()
3) each time HAL_RCC_ClockConfig() is called to configure the system clock frequency
Note: If you use this function to configure the system clock; then there
is no need to call the 2 first functions listed above, since SystemCoreClock
variable is updated automatically.
*/
uint32_t SystemCoreClock = 16000000UL;
const uint32_t AHBPrescTable[16UL] = {0UL, 0UL, 0UL, 0UL, 0UL, 0UL, 0UL, 0UL, 1UL, 2UL, 3UL, 4UL, 6UL, 7UL, 8UL, 9UL};
const uint32_t APBPrescTable[8UL] = {0UL, 0UL, 0UL, 0UL, 1UL, 2UL, 3UL, 4UL};
/**
* @}
*/
/** @addtogroup STM32G0xx_System_Private_FunctionPrototypes
* @{
*/
/**
* @}
*/
/** @addtogroup STM32G0xx_System_Private_Functions
* @{
*/
/**
* @brief Setup the microcontroller system.
* @param None
* @retval None
*/
void SystemInit(void)
{
/* Configure the Vector Table location add offset address ------------------*/
#ifdef VECT_TAB_SRAM
SCB->VTOR = SRAM_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal SRAM */
#else
SCB->VTOR = FLASH_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal FLASH */
#endif
}
/**
* @brief Update SystemCoreClock variable according to Clock Register Values.
* The SystemCoreClock variable contains the core clock (HCLK), it can
* be used by the user application to setup the SysTick timer or configure
* other parameters.
*
* @note Each time the core clock (HCLK) changes, this function must be called
* to update SystemCoreClock variable value. Otherwise, any configuration
* based on this variable will be incorrect.
*
* @note - The system frequency computed by this function is not the real
* frequency in the chip. It is calculated based on the predefined
* constant and the selected clock source:
*
* - If SYSCLK source is HSI, SystemCoreClock will contain the HSI_VALUE(**) / HSI division factor
*
* - If SYSCLK source is HSE, SystemCoreClock will contain the HSE_VALUE(***)
*
* - If SYSCLK source is LSI, SystemCoreClock will contain the LSI_VALUE
*
* - If SYSCLK source is LSE, SystemCoreClock will contain the LSE_VALUE
*
* - If SYSCLK source is PLL, SystemCoreClock will contain the HSE_VALUE(***)
* or HSI_VALUE(*) multiplied/divided by the PLL factors.
*
* (**) HSI_VALUE is a constant defined in stm32g0xx_hal_conf.h file (default value
* 16 MHz) but the real value may vary depending on the variations
* in voltage and temperature.
*
* (***) HSE_VALUE is a constant defined in stm32g0xx_hal_conf.h file (default value
* 8 MHz), user has to ensure that HSE_VALUE is same as the real
* frequency of the crystal used. Otherwise, this function may
* have wrong result.
*
* - The result of this function could be not correct when using fractional
* value for HSE crystal.
*
* @param None
* @retval None
*/
void SystemCoreClockUpdate(void)
{
uint32_t tmp;
uint32_t pllvco;
uint32_t pllr;
uint32_t pllsource;
uint32_t pllm;
uint32_t hsidiv;
/* Get SYSCLK source -------------------------------------------------------*/
switch (RCC->CFGR & RCC_CFGR_SWS)
{
case RCC_CFGR_SWS_0: /* HSE used as system clock */
SystemCoreClock = HSE_VALUE;
break;
case (RCC_CFGR_SWS_1 | RCC_CFGR_SWS_0): /* LSI used as system clock */
SystemCoreClock = LSI_VALUE;
break;
case RCC_CFGR_SWS_2: /* LSE used as system clock */
SystemCoreClock = LSE_VALUE;
break;
case RCC_CFGR_SWS_1: /* PLL used as system clock */
/* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLLM) * PLLN
SYSCLK = PLL_VCO / PLLR
*/
pllsource = (RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC);
pllm = ((RCC->PLLCFGR & RCC_PLLCFGR_PLLM) >> RCC_PLLCFGR_PLLM_Pos) + 1UL;
if(pllsource == 0x03UL) /* HSE used as PLL clock source */
{
pllvco = (HSE_VALUE / pllm);
}
else /* HSI used as PLL clock source */
{
pllvco = (HSI_VALUE / pllm);
}
pllvco = pllvco * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> RCC_PLLCFGR_PLLN_Pos);
pllr = (((RCC->PLLCFGR & RCC_PLLCFGR_PLLR) >> RCC_PLLCFGR_PLLR_Pos) + 1UL);
SystemCoreClock = pllvco/pllr;
break;
case 0x00000000U: /* HSI used as system clock */
default: /* HSI used as system clock */
hsidiv = (1UL << ((READ_BIT(RCC->CR, RCC_CR_HSIDIV))>> RCC_CR_HSIDIV_Pos));
SystemCoreClock = (HSI_VALUE/hsidiv);
break;
}
/* Compute HCLK clock frequency --------------------------------------------*/
/* Get HCLK prescaler */
tmp = AHBPrescTable[((RCC->CFGR & RCC_CFGR_HPRE) >> RCC_CFGR_HPRE_Pos)];
/* HCLK clock frequency */
SystemCoreClock >>= tmp;
}
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/