利用U盘通过FatFs烧写BIN文件到flash实现芯片的在线编程(stm32F407+FatFs+USBdisk+Flash)

利用U盘通过FatFs烧写BIN文件到flash实现芯片的在线编程(stm32F407+FatFs+USBdisk+Flash)

取消关注 | 14

...

通过U盘里面的image.bin文件来升级更新flash,实现脱机烧写程序
在昨天Fatfs+usbdisk能够写入文件和读出文件的基础上,增加一个读取二进制文件,并烧写到flash的功能即可.
 
关于配置和读写文件请看昨天的帖子:
利用stm32cube实现USB+FATFS的usbdisk程序--实现Fatfs对U盘文件操作
http://www.stm32cube.com/question/514
 
由于时间关系,我就只是贴出相关的代码,做简要的说明
在原有的工程中增加两个文件
flash_if.c

/**

  ******************************************************************************

  * @file    USB_Host/FWupgrade_Standalone/Src/flash_if.c

  * @author  MCD Application Team

  * @version V1.3.5

  * @date    03-June-2016

  * @brief   This file provides all the flash layer functions.

  ******************************************************************************

  * @attention

  *

  * <h2><center>&copy; Copyright ?2016 STMicroelectronics International N.V.

  * All rights reserved.</center></h2>

  *

  * Redistribution and use in source and binary forms, with or without

  * modification, are permitted, provided that the following conditions are met:

  *

  * 1. Redistribution of source code must retain the above copyright notice,

  *    this list of conditions and the following disclaimer.

  * 2. Redistributions in binary form must reproduce the above copyright notice,

  *    this list of conditions and the following disclaimer in the documentation

  *    and/or other materials provided with the distribution.

  * 3. Neither the name of STMicroelectronics nor the names of other

  *    contributors to this software may be used to endorse or promote products

  *    derived from this software without specific written permission.

  * 4. This software, including modifications and/or derivative works of this

  *    software, must execute solely and exclusively on microcontroller or

  *    microprocessor devices manufactured by or for STMicroelectronics.

  * 5. Redistribution and use of this software other than as permitted under

  *    this license is void and will automatically terminate your rights under

  *    this license.

  *

  * THIS SOFTWARE IS PROVIDED BY STMICROELECTRONICS AND CONTRIBUTORS "AS IS"

  * AND ANY EXPRESS, IMPLIED OR STATUTORY WARRANTIES, INCLUDING, BUT NOT

  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A

  * PARTICULAR PURPOSE AND NON-INFRINGEMENT OF THIRD PARTY INTELLECTUAL PROPERTY

  * RIGHTS ARE DISCLAIMED TO THE FULLEST EXTENT PERMITTED BY LAW. IN NO EVENT

  * SHALL STMICROELECTRONICS OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,

  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT

  * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA,

  * OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF

  * LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING

  * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE,

  * EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.

  *

  ******************************************************************************

  */

/* Includes ------------------------------------------------------------------*/

#include "flash_if.h"

#include "stm32f4xx_hal.h"

/* Private typedef -----------------------------------------------------------*/

/* Private define ------------------------------------------------------------*/

/* Private macros ------------------------------------------------------------*/

/* Private variables ---------------------------------------------------------*/

uint32_t FirstSector = 0;

uint32_t NbOfSectors = 0;

uint32_t SectorError = 0;

uint32_t OB_RDP_LEVEL;



/* Private function prototypes -----------------------------------------------*/

static uint32_t FLASH_If_GetSectorNumber(uint32_t Address);

static FLASH_OBProgramInitTypeDef FLASH_OBProgramInitStruct;

static FLASH_EraseInitTypeDef FLASH_EraseInitStruct;



/* Private functions ---------------------------------------------------------*/



/**

  * @brief  Unlocks the Flash to enable the flash control register access.

  * @param  None

  * @retval None

  */

void FLASH_If_FlashUnlock(void)

{

    HAL_FLASH_Unlock();

}



/**

  * @brief  Gets Flash readout protection status.

  * @param  None

  * @retval ReadOut protection status

  */

FlagStatus FLASH_If_ReadOutProtectionStatus(void)

{

    FlagStatus readoutstatus = RESET;



    FLASH_OBProgramInitStruct.RDPLevel = OB_RDP_LEVEL;



    HAL_FLASHEx_OBGetConfig(&FLASH_OBProgramInitStruct);



    if(OB_RDP_LEVEL == SET)

    {

        readoutstatus = SET;

    }

    else

    {

        readoutstatus = RESET;

    }



    return readoutstatus;

}



/**

  * @brief  Erases the required FLASH Sectors.

  * @param  Address: Start address for erasing data

  * @retval 0: Erase sectors done with success

  *         1: Erase error

  */

uint32_t FLASH_If_EraseSectors(uint32_t Address)

{

    /* Erase the user Flash area

      (area defined by APPLICATION_ADDRESS and USER_FLASH_LAST_PAGE_ADDRESS) ****/



    if(Address <= (uint32_t) USER_FLASH_LAST_PAGE_ADDRESS)

    {

        /* Get the 1st sector to erase */

        FirstSector = FLASH_If_GetSectorNumber(Address);

        /* Get the number of sector to erase from 1st sector */

        NbOfSectors = FLASH_If_GetSectorNumber(USER_FLASH_LAST_PAGE_ADDRESS) - FirstSector + 1;



        FLASH_EraseInitStruct.TypeErase = FLASH_TYPEERASE_SECTORS;

        FLASH_EraseInitStruct.Sector = FirstSector;

        FLASH_EraseInitStruct.NbSectors = NbOfSectors;

        FLASH_EraseInitStruct.VoltageRange = FLASH_VOLTAGE_RANGE_3;



        if(HAL_FLASHEx_Erase(&FLASH_EraseInitStruct, &SectorError) != HAL_OK)

            return (1);

    }

    else

    {

        return (1);

    }



    return (0);

}



/**

  * @brief  Writes a data buffer in flash (data are 32-bit aligned).

  * @note   After writing data buffer, the flash content is checked.

  * @param  Address: Start address for writing data buffer

  * @param  Data: Pointer on data buffer

  * @retval 0: Data successfully written to Flash memory

  *         1: Error occurred while writing data in Flash memory

  */

uint32_t FLASH_If_Write(uint32_t Address, uint32_t Data)

{

    /* Program the user Flash area word by word

      (area defined by FLASH_USER_START_ADDR and APPLICATION_ADDRESS) ***********/



    if(Address <= (uint32_t) USER_FLASH_LAST_PAGE_ADDRESS)

    {

        if(HAL_FLASH_Program(FLASH_TYPEPROGRAM_WORD, Address, Data)!= HAL_OK)

            return (1);

    }

    else

    {

        return (1);

    }



    return (0);

}



/**

  * @brief  Returns the Flash sector Number of the address

  * @param  None

  * @retval The Flash sector Number of the address

  */

static uint32_t FLASH_If_GetSectorNumber(uint32_t Address)

{

    uint32_t sector = 0;



    if(Address < ADDR_FLASH_SECTOR_1 && Address >= ADDR_FLASH_SECTOR_0)

    {

        sector = FLASH_SECTOR_0;

    }

    else if(Address < ADDR_FLASH_SECTOR_2 && Address >= ADDR_FLASH_SECTOR_1)

    {

        sector = FLASH_SECTOR_1;

    }

    else if(Address < ADDR_FLASH_SECTOR_3 && Address >= ADDR_FLASH_SECTOR_2)

    {

        sector = FLASH_SECTOR_2;

    }

    else if(Address < ADDR_FLASH_SECTOR_4 && Address >= ADDR_FLASH_SECTOR_3)

    {

        sector = FLASH_SECTOR_3;

    }

    else if(Address < ADDR_FLASH_SECTOR_5 && Address >= ADDR_FLASH_SECTOR_4)

    {

        sector = FLASH_SECTOR_4;

    }

    else if(Address < ADDR_FLASH_SECTOR_6 && Address >= ADDR_FLASH_SECTOR_5)

    {

        sector = FLASH_SECTOR_5;

    }

    else if(Address < ADDR_FLASH_SECTOR_7 && Address >= ADDR_FLASH_SECTOR_6)

    {

        sector = FLASH_SECTOR_6;

    }

    else if(Address < ADDR_FLASH_SECTOR_8 && Address >= ADDR_FLASH_SECTOR_7)

    {

        sector = FLASH_SECTOR_7;

    }

    else if(Address < ADDR_FLASH_SECTOR_9 && Address >= ADDR_FLASH_SECTOR_8)

    {

        sector = FLASH_SECTOR_8;

    }

    else if(Address < ADDR_FLASH_SECTOR_10 && Address >= ADDR_FLASH_SECTOR_9)

    {

        sector = FLASH_SECTOR_9;

    }

    else if(Address < ADDR_FLASH_SECTOR_11 && Address >= ADDR_FLASH_SECTOR_10)

    {

        sector = FLASH_SECTOR_10;

    }

    else /*(Address < FLASH_END_ADDR && Address >= ADDR_FLASH_SECTOR_11) */

    {

        sector = FLASH_SECTOR_11;

    }

    return sector;

}



/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/


flash_if.h

/**

  ******************************************************************************

  * @file    USB_Host/FWupgrade_Standalone/Inc/flash_if.h

  * @author  MCD Application Team

  * @version V1.3.5

  * @date    03-June-2016

  * @brief   Header file for flash_if.c

  ******************************************************************************

  * @attention

  *

  * <h2><center>&copy; Copyright ?2016 STMicroelectronics International N.V.

  * All rights reserved.</center></h2>

  *

  * Redistribution and use in source and binary forms, with or without

  * modification, are permitted, provided that the following conditions are met:

  *

  * 1. Redistribution of source code must retain the above copyright notice,

  *    this list of conditions and the following disclaimer.

  * 2. Redistributions in binary form must reproduce the above copyright notice,

  *    this list of conditions and the following disclaimer in the documentation

  *    and/or other materials provided with the distribution.

  * 3. Neither the name of STMicroelectronics nor the names of other

  *    contributors to this software may be used to endorse or promote products

  *    derived from this software without specific written permission.

  * 4. This software, including modifications and/or derivative works of this

  *    software, must execute solely and exclusively on microcontroller or

  *    microprocessor devices manufactured by or for STMicroelectronics.

  * 5. Redistribution and use of this software other than as permitted under

  *    this license is void and will automatically terminate your rights under

  *    this license.

  *

  * THIS SOFTWARE IS PROVIDED BY STMICROELECTRONICS AND CONTRIBUTORS "AS IS"

  * AND ANY EXPRESS, IMPLIED OR STATUTORY WARRANTIES, INCLUDING, BUT NOT

  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A

  * PARTICULAR PURPOSE AND NON-INFRINGEMENT OF THIRD PARTY INTELLECTUAL PROPERTY

  * RIGHTS ARE DISCLAIMED TO THE FULLEST EXTENT PERMITTED BY LAW. IN NO EVENT

  * SHALL STMICROELECTRONICS OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,

  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT

  * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA,

  * OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF

  * LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING

  * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE,

  * EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.

  *

  ******************************************************************************

  */

/* Define to prevent recursive inclusion -------------------------------------*/

#ifndef __FLASH_IF_H

#define __FLASH_IF_H



#ifdef __cplusplus

extern "C" {

#endif



/* Includes ------------------------------------------------------------------*/

#include "stm32f4xx_hal.h"



/* Exported types ------------------------------------------------------------*/

typedef  void (*pFunction)(void);



/* Exported constants --------------------------------------------------------*/

/* Define the flash memory start address */

#define USER_FLASH_STARTADDRESS    ((uint32_t)0x08000000)



/* Define the address from where user application will be loaded.

Note: the 1st and the second sectors 0x08000000-0x0800BFFF are reserved

for the Firmware upgrade code */

#define APPLICATION_ADDRESS        (uint32_t)0x0800C000



/* Last Page Adress */

#define USER_FLASH_LAST_PAGE_ADDRESS  0x080FFFFF - 4



/* Define the user application size */

#define USER_FLASH_SIZE   (USER_FLASH_LAST_PAGE_ADDRESS - APPLICATION_ADDRESS + 1)



/* Base address of the Flash sectors */

#define ADDR_FLASH_SECTOR_0     ((uint32_t)0x08000000) /* Base @ of Sector 0, 16 Kbyte */

#define ADDR_FLASH_SECTOR_1     ((uint32_t)0x08004000) /* Base @ of Sector 1, 16 Kbyte */

#define ADDR_FLASH_SECTOR_2     ((uint32_t)0x08008000) /* Base @ of Sector 2, 16 Kbyte */

#define ADDR_FLASH_SECTOR_3     ((uint32_t)0x0800C000) /* Base @ of Sector 3, 16 Kbyte */

#define ADDR_FLASH_SECTOR_4     ((uint32_t)0x08010000) /* Base @ of Sector 4, 64 Kbyte */

#define ADDR_FLASH_SECTOR_5     ((uint32_t)0x08020000) /* Base @ of Sector 5, 128 Kbyte */

#define ADDR_FLASH_SECTOR_6     ((uint32_t)0x08040000) /* Base @ of Sector 6, 128 Kbyte */

#define ADDR_FLASH_SECTOR_7     ((uint32_t)0x08060000) /* Base @ of Sector 7, 128 Kbyte */

#define ADDR_FLASH_SECTOR_8     ((uint32_t)0x08080000) /* Base @ of Sector 8, 128 Kbyte */

#define ADDR_FLASH_SECTOR_9     ((uint32_t)0x080A0000) /* Base @ of Sector 9, 128 Kbyte */

#define ADDR_FLASH_SECTOR_10    ((uint32_t)0x080C0000) /* Base @ of Sector 10, 128 Kbyte */

#define ADDR_FLASH_SECTOR_11    ((uint32_t)0x080E0000) /* Base @ of Sector 11, 128 Kbyte */



/* Exported macros -----------------------------------------------------------*/

/* Exported functions ------------------------------------------------------- */

void FLASH_If_FlashUnlock(void);

FlagStatus FLASH_If_ReadOutProtectionStatus(void);

uint32_t FLASH_If_EraseSectors(uint32_t Address);

uint32_t FLASH_If_Write(uint32_t Address, uint32_t Data);



#ifdef __cplusplus

}

#endif



#endif  /* __FLASH_IF_H */



/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/


为了演示方便,模仿官方的做法,将按键加入到工程,PA0
在GPIO.c文件中添加

    /*Configure GPIO pin : PA0 */

    GPIO_InitStruct.Pin = GPIO_PIN_0;

    GPIO_InitStruct.Mode = GPIO_MODE_INPUT;

    GPIO_InitStruct.Pull = GPIO_NOPULL;

    HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);

我把所有的flash操作都放在了main.c文件中,你可以剪切到自己建立的C文件中
我在main.c中要用到flash操作,所以,添加头文件

#include "flash_if.h"

添加一个FatFs读出image.bin内容并写入flash的方程

/**

  * @brief  Programs the internal Flash memory.

  * @param  None

  * @retval None

  */

static void COMMAND_ProgramFlashMemory(void)

{

    uint32_t programcounter = 0x00;

    uint8_t readflag = TRUE;

    uint16_t bytesread;



    /* RAM Address Initialization */

    RamAddress = (uint32_t) &RAM_Buf;



    /* Erase address init */

    LastPGAddress = APPLICATION_ADDRESS;



    /* While file still contain data */

    while (readflag == TRUE)

    {

        /* Read maximum 512 Kbyte from the selected file */

        f_read (&MyFile, RAM_Buf, BUFFER_SIZE, (void *)&bytesread);



        /* Temp variable */

        TmpReadSize = bytesread;



        /* The read data < "BUFFER_SIZE" Kbyte */

        if(TmpReadSize < BUFFER_SIZE)

        {

            readflag = FALSE;

        }



        /* Program flash memory */

        for(programcounter = TmpReadSize; programcounter != 0; programcounter -= 4)

        {

            TmpProgramCounter = programcounter;

            /* Write word into flash memory */

            if( FLASH_If_Write((LastPGAddress- TmpProgramCounter + TmpReadSize), \

                               *(uint32_t *)(RamAddress - programcounter + TmpReadSize )) != 0x00)

            {

                Error_Handler();

            }

        }

        /* Update last programmed address value */

        LastPGAddress = LastPGAddress + TmpReadSize;

    }

}

改造原来的写入测试代码:

static void MSC_Application(void)

{

    /* Register the file system object to the FatFs module */

    if(f_mount(&USBDISKFatFs, (TCHAR const*)USBH_Path, 0) != FR_OK)

    {

        /* FatFs Initialization Error */

        Error_Handler();

    }

    else

    {

        /* Open the binary file to be downloaded */

        if(f_open(&MyFile, "image.bin", FA_READ) == FR_OK)

        {

            if(MyFile.fsize > USER_FLASH_SIZE)

            {

                /* No available Flash memory size for the binary file: Turn LED4 On and*/

                Error_Handler();

            }

            else

            {

                /* Download On Going: Turn LED4 On */

                HAL_GPIO_WritePin(GPIOD,GPIO_PIN_12,GPIO_PIN_SET);



                /* Erase FLASH sectors to download image */

                if(FLASH_If_EraseSectors(APPLICATION_ADDRESS) != 0x00)

                {

                    Error_Handler();

                }



                /* Program flash memory */

                COMMAND_ProgramFlashMemory();

                HAL_GPIO_WritePin(GPIOD,GPIO_PIN_12|GPIO_PIN_13,GPIO_PIN_SET);

                /* Close file */

                f_close(&MyFile);

            }

        }

        else {



            Error_Handler();

        }





    }

}

由于上面的改造,必须增加相应的变量定义:

扫描二维码关注公众号,回复: 10396788 查看本文章
/* This value can be equal to (512 * x) according to RAM size availability with x=[1, 128]

   In this project x is fixed to 64 => 512 * 64 = 32768bytes = 32 Kbytes */

#define BUFFER_SIZE        ((uint16_t)512*64)

static uint32_t RamAddress = 0x00;

static __IO uint32_t LastPGAddress = APPLICATION_ADDRESS;

static uint8_t RAM_Buf[BUFFER_SIZE] = {0x00};

static uint32_t TmpProgramCounter = 0x00;

static uint32_t TmpReadSize = 0x00;


参考官方的跳转代码,先增加一些跳转相关变量

uint32_t JumpAddress;

pFunction Jump_To_Application;

在到主函数main()中添加

   if(HAL_GPIO_ReadPin(GPIOA,GPIO_PIN_0) == GPIO_PIN_RESET)

    {

        /* Check Vector Table: Test if user code is programmed starting from address

        "APPLICATION_ADDRESS" */

        if ((((*(__IO uint32_t*)APPLICATION_ADDRESS) & 0xFF000000 ) == 0x20000000) || \

                (((*(__IO uint32_t*)APPLICATION_ADDRESS) & 0xFF000000 ) == 0x10000000))

        {

            /* Jump to user application */

            JumpAddress = *(__IO uint32_t*) (APPLICATION_ADDRESS + 4);

            Jump_To_Application = (pFunction) JumpAddress;

            /* Initialize user application's Stack Pointer */

            __set_MSP(*(__IO uint32_t*) APPLICATION_ADDRESS);

            Jump_To_Application();

        }



    }

同时,为了烧写完成后,自动运行代码,改造以前的App状态机如下:

        switch(Appli_state)

        {

        case APPLICATION_READY:

            MSC_Application();

            Appli_state = APPLICATION_DISCONNECT;

            break;



        case APPLICATION_DISCONNECT:

            f_mount(NULL, (TCHAR const*)"", 0);

            HAL_Delay(2000);

            NVIC_SystemReset();

            break;

        default:

            break;

        }

对了,烧写代码之前要先解锁flash,于是在while(1)之前添加

HAL_Flash_Unlock();

这里所有的改造就完成了.
下面附上完成后的main.c完整代码:

/* Includes ------------------------------------------------------------------*/

#include "stm32f4xx_hal.h"

#include "fatfs.h"

#include "usb_host.h"

#include "gpio.h"



/* USER CODE BEGIN Includes */

#include "flash_if.h"

/* USER CODE END Includes */



/* Private variables ---------------------------------------------------------*/



/* USER CODE BEGIN PV */

/* Private variables ---------------------------------------------------------*/

extern ApplicationTypeDef Appli_state;

extern USBH_HandleTypeDef hUsbHostFS;

extern char USBH_Path[4];  /* USBH logical drive path */

/* USER CODE END PV */



/* Private function prototypes -----------------------------------------------*/

void SystemClock_Config(void);

void Error_Handler(void);

void MX_USB_HOST_Process(void);



/* USER CODE BEGIN PFP */

/* Private function prototypes -----------------------------------------------*/

static void MSC_Application(void);

/* USER CODE END PFP */



/* USER CODE BEGIN 0 */

FATFS USBDISKFatFs;           /* File system object for USB disk logical drive */

FIL MyFile;                   /* File object */



uint32_t JumpAddress;

pFunction Jump_To_Application;



#define DOWNLOAD_FILENAME          "image.bin"



/* USER CODE END 0 */



int main(void)

{



    /* USER CODE BEGIN 1 */



    /* USER CODE END 1 */



    /* MCU Configuration----------------------------------------------------------*/



    /* Reset of all peripherals, Initializes the Flash interface and the Systick. */

    HAL_Init();



    /* Configure the system clock */

    SystemClock_Config();



    /* Initialize all configured peripherals */

    MX_GPIO_Init();



    /* USER CODE BEGIN 2 */

    if(HAL_GPIO_ReadPin(GPIOA,GPIO_PIN_0) == GPIO_PIN_RESET)

    {

        /* Check Vector Table: Test if user code is programmed starting from address

        "APPLICATION_ADDRESS" */

        if ((((*(__IO uint32_t*)APPLICATION_ADDRESS) & 0xFF000000 ) == 0x20000000) || \

                (((*(__IO uint32_t*)APPLICATION_ADDRESS) & 0xFF000000 ) == 0x10000000))

        {

            /* Jump to user application */

            JumpAddress = *(__IO uint32_t*) (APPLICATION_ADDRESS + 4);

            Jump_To_Application = (pFunction) JumpAddress;

            /* Initialize user application's Stack Pointer */

            __set_MSP(*(__IO uint32_t*) APPLICATION_ADDRESS);

            Jump_To_Application();

        }



    }



    MX_FATFS_Init();

    MX_USB_HOST_Init();



    FLASH_If_FlashUnlock();



    /* USER CODE END 2 */



    /* Infinite loop */

    /* USER CODE BEGIN WHILE */

    while (1)

    {

        /* USER CODE END WHILE */

        MX_USB_HOST_Process();



        /* USER CODE BEGIN 3 */

        switch(Appli_state)

        {

        case APPLICATION_READY:

            MSC_Application();

            Appli_state = APPLICATION_DISCONNECT;

            break;



        case APPLICATION_DISCONNECT:

            f_mount(NULL, (TCHAR const*)"", 0);

            HAL_Delay(2000);

            NVIC_SystemReset();

            break;

        default:

            break;

        }

    }

    /* USER CODE END 3 */



}



/** System Clock Configuration

*/

void SystemClock_Config(void)

{



    RCC_OscInitTypeDef RCC_OscInitStruct;

    RCC_ClkInitTypeDef RCC_ClkInitStruct;



    __HAL_RCC_PWR_CLK_ENABLE();



    __HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE1);



    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 = 4;

    RCC_OscInitStruct.PLL.PLLN = 168;

    RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV2;

    RCC_OscInitStruct.PLL.PLLQ = 7;

    if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK)

    {

        Error_Handler();

    }



    RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK|RCC_CLOCKTYPE_SYSCLK

                                  |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;

    if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_5) != HAL_OK)

    {

        Error_Handler();

    }



    HAL_SYSTICK_Config(HAL_RCC_GetHCLKFreq()/1000);



    HAL_SYSTICK_CLKSourceConfig(SYSTICK_CLKSOURCE_HCLK);



    /* SysTick_IRQn interrupt configuration */

    HAL_NVIC_SetPriority(SysTick_IRQn, 0, 0);

}



/* USER CODE BEGIN 4 */

/* This value can be equal to (512 * x) according to RAM size availability with x=[1, 128]

   In this project x is fixed to 64 => 512 * 64 = 32768bytes = 32 Kbytes */

#define BUFFER_SIZE        ((uint16_t)512*64)

static uint32_t RamAddress = 0x00;

static __IO uint32_t LastPGAddress = APPLICATION_ADDRESS;

static uint8_t RAM_Buf[BUFFER_SIZE] = {0x00};

static uint32_t TmpProgramCounter = 0x00;

static uint32_t TmpReadSize = 0x00;



/**

  * @brief  Programs the internal Flash memory.

  * @param  None

  * @retval None

  */

static void COMMAND_ProgramFlashMemory(void)

{

    uint32_t programcounter = 0x00;

    uint8_t readflag = TRUE;

    uint16_t bytesread;



    /* RAM Address Initialization */

    RamAddress = (uint32_t) &RAM_Buf;



    /* Erase address init */

    LastPGAddress = APPLICATION_ADDRESS;



    /* While file still contain data */

    while (readflag == TRUE)

    {

        /* Read maximum 512 Kbyte from the selected file */

        f_read (&MyFile, RAM_Buf, BUFFER_SIZE, (void *)&bytesread);



        /* Temp variable */

        TmpReadSize = bytesread;



        /* The read data < "BUFFER_SIZE" Kbyte */

        if(TmpReadSize < BUFFER_SIZE)

        {

            readflag = FALSE;

        }



        /* Program flash memory */

        for(programcounter = TmpReadSize; programcounter != 0; programcounter -= 4)

        {

            TmpProgramCounter = programcounter;

            /* Write word into flash memory */

            if( FLASH_If_Write((LastPGAddress- TmpProgramCounter + TmpReadSize), \

                               *(uint32_t *)(RamAddress - programcounter + TmpReadSize )) != 0x00)

            {

                Error_Handler();

            }

        }

        /* Update last programmed address value */

        LastPGAddress = LastPGAddress + TmpReadSize;

    }

}





static void MSC_Application(void)

{

    /* Register the file system object to the FatFs module */

    if(f_mount(&USBDISKFatFs, (TCHAR const*)USBH_Path, 0) != FR_OK)

    {

        /* FatFs Initialization Error */

        Error_Handler();

    }

    else

    {

        /* Open the binary file to be downloaded */

        if(f_open(&MyFile, DOWNLOAD_FILENAME, FA_READ) == FR_OK)

        {

            if(MyFile.fsize > USER_FLASH_SIZE)

            {

                /* No available Flash memory size for the binary file: Turn LED4 On and*/

                Error_Handler();

            }

            else

            {

                /* Download On Going: Turn LED4 On */

                HAL_GPIO_WritePin(GPIOD,GPIO_PIN_12,GPIO_PIN_SET);



                /* Erase FLASH sectors to download image */

                if(FLASH_If_EraseSectors(APPLICATION_ADDRESS) != 0x00)

                {

                    Error_Handler();

                }



                /* Program flash memory */

                COMMAND_ProgramFlashMemory();

                HAL_GPIO_WritePin(GPIOD,GPIO_PIN_12|GPIO_PIN_13,GPIO_PIN_SET);

                /* Close file */

                f_close(&MyFile);

            }

        }

        else {



            Error_Handler();

        }









//        /* Create and Open a new text file object with write access */

//        if(f_open(&MyFile, "stm32cubeasdfgfhgjghjkytu.txt", FA_CREATE_ALWAYS | FA_WRITE) != FR_OK)

//        {

//            /* 'STM32.TXT' file Open for write Error */

//            Error_Handler();

//        }

//        else

//        {

//            /* Write data to the text file */

//            res = f_write(&MyFile, wtext, sizeof(wtext), (void *)&byteswritten);



//            if((byteswritten == 0) || (res != FR_OK))

//            {

//                /* 'STM32.TXT' file Write or EOF Error */

//                Error_Handler();

//            }

//            else

//            {

//                /* Close the open text file */

//                f_close(&MyFile);

//            }

//        }

    }

}

/* USER CODE END 4 */



/**

  * @brief  This function is executed in case of error occurrence.

  * @param  None

  * @retval None

  */

void Error_Handler(void)

{

    /* USER CODE BEGIN Error_Handler */

    /* User can add his own implementation to report the HAL error return state */

    while(1)

    {

        HAL_Delay(500);

        HAL_GPIO_TogglePin(GPIOD,GPIO_PIN_12|GPIO_PIN_13);

    }

    /* USER CODE END Error_Handler */

}



#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



/**

  * @}

  */



/**

  * @}

*/



/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/


 
 
 
 2016-07-27 添加评论 邀请 1感谢

分享

举报

没有找到相关结果

已邀请:

><

与内容相关的链接

提交

1 个回复

01_avatar_mid.jpguploading.4e448015.gif转存失败重新上传取消

admin

赞同来自: rzx1990 /ka 忆忘3019 297348939

由于最近要外出,所以这段时间要很少更新了,
上面烧写完成后,你可以单独弄个app程序,
注意要将起始地址改成0x800C000
还有中断向量的偏移地址改成0xc000
编译后,生成bin文件,
将这个bin文件重命名为image.bin 然后拷贝到U盘中
,板子上电,如果你没烧录过bin,那么会插上u盘会自动烧录开始,
耐心等待几秒,成功后,系统自动重启,运动app程序
如果烧录过,那么需要你按住reset键重启单片机的同时按住user按键,程序即开始烧录.完成后自动重启开始app

发布了61 篇原创文章 · 获赞 0 · 访问量 1073

猜你喜欢

转载自blog.csdn.net/qq_20312079/article/details/105134736