mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-18 22:05:17 +03:00
STM32F4: Libraries
This commit is contained in:
parent
55d8eb57be
commit
d4e96ba8e7
206 changed files with 141406 additions and 0 deletions
187
lib/main/STM32_USB_Device_Library/Class/dfu/inc/usbd_dfu_core.h
Normal file
187
lib/main/STM32_USB_Device_Library/Class/dfu/inc/usbd_dfu_core.h
Normal file
|
@ -0,0 +1,187 @@
|
|||
/**
|
||||
******************************************************************************
|
||||
* @file usbd_dfu_core.h
|
||||
* @author MCD Application Team
|
||||
* @version V1.0.0
|
||||
* @date 22-July-2011
|
||||
* @brief header file for the usbd_dfu_core.c file.
|
||||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
|
||||
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
|
||||
* TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
|
||||
* DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
|
||||
* FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
|
||||
* CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
|
||||
*
|
||||
* <h2><center>© COPYRIGHT 2011 STMicroelectronics</center></h2>
|
||||
******************************************************************************
|
||||
*/
|
||||
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
|
||||
#ifndef __USB_DFU_CORE_H_
|
||||
#define __USB_DFU_CORE_H_
|
||||
|
||||
#include "usbd_ioreq.h"
|
||||
#include "usbd_dfu_mal.h"
|
||||
|
||||
/** @addtogroup STM32_USB_OTG_DEVICE_LIBRARY
|
||||
* @{
|
||||
*/
|
||||
|
||||
/** @defgroup usbd_dfu
|
||||
* @brief This file is the Header file for USBD_dfu.c
|
||||
* @{
|
||||
*/
|
||||
|
||||
|
||||
/** @defgroup usbd_dfu_Exported_Defines
|
||||
* @{
|
||||
*/
|
||||
#define USB_DFU_CONFIG_DESC_SIZ (18 + (9 * USBD_ITF_MAX_NUM))
|
||||
#define USB_DFU_DESC_SIZ 9
|
||||
|
||||
#define DFU_DESCRIPTOR_TYPE 0x21
|
||||
|
||||
|
||||
/*---------------------------------------------------------------------*/
|
||||
/* DFU definitions */
|
||||
/*---------------------------------------------------------------------*/
|
||||
|
||||
|
||||
|
||||
/**************************************************/
|
||||
/* DFU Requests DFU states */
|
||||
/**************************************************/
|
||||
|
||||
|
||||
#define STATE_appIDLE 0
|
||||
#define STATE_appDETACH 1
|
||||
#define STATE_dfuIDLE 2
|
||||
#define STATE_dfuDNLOAD_SYNC 3
|
||||
#define STATE_dfuDNBUSY 4
|
||||
#define STATE_dfuDNLOAD_IDLE 5
|
||||
#define STATE_dfuMANIFEST_SYNC 6
|
||||
#define STATE_dfuMANIFEST 7
|
||||
#define STATE_dfuMANIFEST_WAIT_RESET 8
|
||||
#define STATE_dfuUPLOAD_IDLE 9
|
||||
#define STATE_dfuERROR 10
|
||||
|
||||
/**************************************************/
|
||||
/* DFU Requests DFU status */
|
||||
/**************************************************/
|
||||
|
||||
#define STATUS_OK 0x00
|
||||
#define STATUS_ERRTARGET 0x01
|
||||
#define STATUS_ERRFILE 0x02
|
||||
#define STATUS_ERRWRITE 0x03
|
||||
#define STATUS_ERRERASE 0x04
|
||||
#define STATUS_ERRCHECK_ERASED 0x05
|
||||
#define STATUS_ERRPROG 0x06
|
||||
#define STATUS_ERRVERIFY 0x07
|
||||
#define STATUS_ERRADDRESS 0x08
|
||||
#define STATUS_ERRNOTDONE 0x09
|
||||
#define STATUS_ERRFIRMWARE 0x0A
|
||||
#define STATUS_ERRVENDOR 0x0B
|
||||
#define STATUS_ERRUSBR 0x0C
|
||||
#define STATUS_ERRPOR 0x0D
|
||||
#define STATUS_ERRUNKNOWN 0x0E
|
||||
#define STATUS_ERRSTALLEDPKT 0x0F
|
||||
|
||||
/**************************************************/
|
||||
/* DFU Requests DFU states Manifestation State */
|
||||
/**************************************************/
|
||||
|
||||
#define Manifest_complete 0x00
|
||||
#define Manifest_In_Progress 0x01
|
||||
|
||||
|
||||
/**************************************************/
|
||||
/* Special Commands with Download Request */
|
||||
/**************************************************/
|
||||
|
||||
#define CMD_GETCOMMANDS 0x00
|
||||
#define CMD_SETADDRESSPOINTER 0x21
|
||||
#define CMD_ERASE 0x41
|
||||
|
||||
/**************************************************/
|
||||
/* Other defines */
|
||||
/**************************************************/
|
||||
/* Bit Detach capable = bit 3 in bmAttributes field */
|
||||
#define DFU_DETACH_MASK (uint8_t)(1 << 4)
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
|
||||
/** @defgroup USBD_CORE_Exported_TypesDefinitions
|
||||
* @{
|
||||
*/
|
||||
/**************************************************/
|
||||
/* DFU Requests */
|
||||
/**************************************************/
|
||||
|
||||
typedef enum _DFU_REQUESTS {
|
||||
DFU_DETACH = 0,
|
||||
DFU_DNLOAD = 1,
|
||||
DFU_UPLOAD,
|
||||
DFU_GETSTATUS,
|
||||
DFU_CLRSTATUS,
|
||||
DFU_GETSTATE,
|
||||
DFU_ABORT
|
||||
} DFU_REQUESTS;
|
||||
|
||||
typedef void (*pFunction)(void);
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
|
||||
|
||||
/** @defgroup USBD_CORE_Exported_Macros
|
||||
* @{
|
||||
*/
|
||||
/********** Descriptor of DFU interface 0 Alternate setting n ****************/
|
||||
#define USBD_DFU_IF_DESC(n) 0x09, /* bLength: Interface Descriptor size */ \
|
||||
USB_INTERFACE_DESCRIPTOR_TYPE, /* bDescriptorType */ \
|
||||
0x00, /* bInterfaceNumber: Number of Interface */ \
|
||||
(n), /* bAlternateSetting: Alternate setting */ \
|
||||
0x00, /* bNumEndpoints*/ \
|
||||
0xFE, /* bInterfaceClass: Application Specific Class Code */ \
|
||||
0x01, /* bInterfaceSubClass : Device Firmware Upgrade Code */ \
|
||||
0x02, /* nInterfaceProtocol: DFU mode protocol */ \
|
||||
USBD_IDX_INTERFACE_STR + (n) + 1 /* iInterface: Index of string descriptor */ \
|
||||
/* 18 */
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/** @defgroup USBD_CORE_Exported_Variables
|
||||
* @{
|
||||
*/
|
||||
|
||||
extern USBD_Class_cb_TypeDef DFU_cb;
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/** @defgroup USB_CORE_Exported_Functions
|
||||
* @{
|
||||
*/
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
#endif // __USB_DFU_CORE_H_
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/
|
|
@ -0,0 +1,79 @@
|
|||
/**
|
||||
******************************************************************************
|
||||
* @file usbd_dfu_mal.h
|
||||
* @author MCD Application Team
|
||||
* @version V1.0.0
|
||||
* @date 22-July-2011
|
||||
* @brief Header for usbd_dfu_mal.c file.
|
||||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
|
||||
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
|
||||
* TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
|
||||
* DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
|
||||
* FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
|
||||
* CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
|
||||
*
|
||||
* <h2><center>© COPYRIGHT 2011 STMicroelectronics</center></h2>
|
||||
******************************************************************************
|
||||
*/
|
||||
|
||||
/* Define to prevent recursive inclusion -------------------------------------*/
|
||||
#ifndef __DFU_MAL_H
|
||||
#define __DFU_MAL_H
|
||||
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
#ifdef STM32F2XX
|
||||
#include "stm32f2xx.h"
|
||||
#elif defined(STM32F10X_CL)
|
||||
#include "stm32f10x.h"
|
||||
#endif /* STM32F2XX */
|
||||
|
||||
#include "usbd_conf.h"
|
||||
#include "usbd_dfu_core.h"
|
||||
|
||||
/* Exported types ------------------------------------------------------------*/
|
||||
typedef struct _DFU_MAL_PROP
|
||||
{
|
||||
const uint8_t* pStrDesc;
|
||||
uint16_t (*pMAL_Init) (void);
|
||||
uint16_t (*pMAL_DeInit) (void);
|
||||
uint16_t (*pMAL_Erase) (uint32_t Add);
|
||||
uint16_t (*pMAL_Write) (uint32_t Add, uint32_t Len);
|
||||
uint8_t *(*pMAL_Read) (uint32_t Add, uint32_t Len);
|
||||
uint16_t (*pMAL_CheckAdd) (uint32_t Add);
|
||||
const uint32_t EraseTiming;
|
||||
const uint32_t WriteTiming;
|
||||
}
|
||||
DFU_MAL_Prop_TypeDef;
|
||||
|
||||
|
||||
/* Exported constants --------------------------------------------------------*/
|
||||
#define MAL_OK 0
|
||||
#define MAL_FAIL 1
|
||||
|
||||
/* utils macro ---------------------------------------------------------------*/
|
||||
#define _1st_BYTE(x) (uint8_t)((x)&0xFF) /* 1st addressing cycle */
|
||||
#define _2nd_BYTE(x) (uint8_t)(((x)&0xFF00)>>8) /* 2nd addressing cycle */
|
||||
#define _3rd_BYTE(x) (uint8_t)(((x)&0xFF0000)>>16) /* 3rd addressing cycle */
|
||||
#define _4th_BYTE(x) (uint8_t)(((x)&0xFF000000)>>24) /* 4th addressing cycle */
|
||||
|
||||
/* Exported macro ------------------------------------------------------------*/
|
||||
#define SET_POLLING_TIMING(x) buffer[1] = _1st_BYTE(x);\
|
||||
buffer[2] = _2nd_BYTE(x);\
|
||||
buffer[3] = _3rd_BYTE(x);
|
||||
|
||||
/* Exported functions ------------------------------------------------------- */
|
||||
|
||||
uint16_t MAL_Init (void);
|
||||
uint16_t MAL_DeInit (void);
|
||||
uint16_t MAL_Erase (uint32_t SectorAddress);
|
||||
uint16_t MAL_Write (uint32_t SectorAddress, uint32_t DataLength);
|
||||
uint8_t *MAL_Read (uint32_t SectorAddress, uint32_t DataLength);
|
||||
uint16_t MAL_GetStatus(uint32_t SectorAddress ,uint8_t Cmd, uint8_t *buffer);
|
||||
|
||||
extern uint8_t MAL_Buffer[XFERSIZE]; /* RAM Buffer for Downloaded Data */
|
||||
#endif /* __DFU_MAL_H */
|
||||
|
||||
/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/
|
|
@ -0,0 +1,49 @@
|
|||
/**
|
||||
******************************************************************************
|
||||
* @file usbd_flash_if.h
|
||||
* @author MCD Application Team
|
||||
* @version V1.0.0RC1
|
||||
* @date 18-March-2011
|
||||
* @brief Header for usbd_flash_if.c file.
|
||||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
|
||||
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
|
||||
* TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
|
||||
* DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
|
||||
* FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
|
||||
* CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
|
||||
*
|
||||
* <h2><center>© COPYRIGHT 2011 STMicroelectronics</center></h2>
|
||||
******************************************************************************
|
||||
*/
|
||||
|
||||
/* Define to prevent recursive inclusion -------------------------------------*/
|
||||
#ifndef __FLASH_IF_MAL_H
|
||||
#define __FLASH_IF_MAL_H
|
||||
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
#include "usbd_dfu_mal.h"
|
||||
|
||||
/* Exported types ------------------------------------------------------------*/
|
||||
/* Exported constants --------------------------------------------------------*/
|
||||
#define FLASH_START_ADD 0x08000000
|
||||
|
||||
#ifdef STM32F2XX
|
||||
#define FLASH_END_ADD 0x08100000
|
||||
#define FLASH_IF_STRING "@Internal Flash /0x08000000/03*016Ka,01*016Kg,01*064Kg,07*128Kg"
|
||||
#elif defined(STM32F10X_CL)
|
||||
#define FLASH_END_ADD 0x08040000
|
||||
#define FLASH_IF_STRING "@Internal Flash /0x08000000/06*002Ka,122*002Kg"
|
||||
#endif /* STM32F2XX */
|
||||
|
||||
|
||||
extern DFU_MAL_Prop_TypeDef DFU_Flash_cb;
|
||||
|
||||
/* Exported macro ------------------------------------------------------------*/
|
||||
/* Exported functions ------------------------------------------------------- */
|
||||
|
||||
#endif /* __FLASH_IF_MAL_H */
|
||||
|
||||
/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/
|
|
@ -0,0 +1,46 @@
|
|||
/**
|
||||
******************************************************************************
|
||||
* @file usbd_mem_if_template.h
|
||||
* @author MCD Application Team
|
||||
* @version V1.0.0
|
||||
* @date 22-July-2011
|
||||
* @brief Header for usbd_mem_if_template.c file.
|
||||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
|
||||
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
|
||||
* TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
|
||||
* DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
|
||||
* FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
|
||||
* CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
|
||||
*
|
||||
* <h2><center>© COPYRIGHT 2011 STMicroelectronics</center></h2>
|
||||
******************************************************************************
|
||||
*/
|
||||
|
||||
/* Define to prevent recursive inclusion -------------------------------------*/
|
||||
#ifndef __MEM_IF_MAL_H
|
||||
#define __MEM_IF_MAL_H
|
||||
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
#ifdef STM32F2XX
|
||||
#include "stm32f2xx.h"
|
||||
#endif /* STM32F2XX */
|
||||
#include "usbd_dfu_mal.h"
|
||||
|
||||
/* Exported types ------------------------------------------------------------*/
|
||||
/* Exported constants --------------------------------------------------------*/
|
||||
#define MEM_START_ADD 0x00000000 /* Dummy start address */
|
||||
#define MEM_END_ADD (uint32_t)(MEM_START_ADD + (5 * 1024)) /* Dummy Size = 5KB */
|
||||
|
||||
#define MEM_IF_STRING "@Dummy Memory /0x00000000/01*002Kg,03*001Kg"
|
||||
|
||||
extern DFU_MAL_Prop_TypeDef DFU_Mem_cb;
|
||||
|
||||
/* Exported macro ------------------------------------------------------------*/
|
||||
/* Exported functions ------------------------------------------------------- */
|
||||
|
||||
#endif /* __MEM_IF_MAL_H */
|
||||
|
||||
/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/
|
|
@ -0,0 +1,43 @@
|
|||
/**
|
||||
******************************************************************************
|
||||
* @file usbd_otp_if.h
|
||||
* @author MCD Application Team
|
||||
* @version V1.0.0
|
||||
* @date 22-July-2011
|
||||
* @brief Header for usbd_otp_if.c file.
|
||||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
|
||||
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
|
||||
* TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
|
||||
* DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
|
||||
* FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
|
||||
* CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
|
||||
*
|
||||
* <h2><center>© COPYRIGHT 2011 STMicroelectronics</center></h2>
|
||||
******************************************************************************
|
||||
*/
|
||||
|
||||
/* Define to prevent recursive inclusion -------------------------------------*/
|
||||
#ifndef __OTP_IF_MAL_H
|
||||
#define __OTP_IF_MAL_H
|
||||
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
#include "usbd_dfu_mal.h"
|
||||
|
||||
/* Exported types ------------------------------------------------------------*/
|
||||
/* Exported constants --------------------------------------------------------*/
|
||||
#define OTP_START_ADD 0x1FFF7800
|
||||
#define OTP_END_ADD (uint32_t)(OTP_START_ADD + 528)
|
||||
|
||||
#define OTP_IF_STRING "@OTP Area /0x1FFF7800/01*512 g,01*016 g"
|
||||
|
||||
extern DFU_MAL_Prop_TypeDef DFU_Otp_cb;
|
||||
|
||||
/* Exported macro ------------------------------------------------------------*/
|
||||
/* Exported functions ------------------------------------------------------- */
|
||||
|
||||
#endif /* __OTP_IF_MAL_H */
|
||||
|
||||
/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/
|
1046
lib/main/STM32_USB_Device_Library/Class/dfu/src/usbd_dfu_core.c
Normal file
1046
lib/main/STM32_USB_Device_Library/Class/dfu/src/usbd_dfu_core.c
Normal file
File diff suppressed because it is too large
Load diff
281
lib/main/STM32_USB_Device_Library/Class/dfu/src/usbd_dfu_mal.c
Normal file
281
lib/main/STM32_USB_Device_Library/Class/dfu/src/usbd_dfu_mal.c
Normal file
|
@ -0,0 +1,281 @@
|
|||
/**
|
||||
******************************************************************************
|
||||
* @file usbd_dfu_mal.c
|
||||
* @author MCD Application Team
|
||||
* @version V1.0.0
|
||||
* @date 22-July-2011
|
||||
* @brief Generic media access Layer.
|
||||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
|
||||
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
|
||||
* TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
|
||||
* DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
|
||||
* FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
|
||||
* CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
|
||||
*
|
||||
* <h2><center>© COPYRIGHT 2011 STMicroelectronics</center></h2>
|
||||
******************************************************************************
|
||||
*/
|
||||
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
#include "usbd_dfu_mal.h"
|
||||
|
||||
#include "usbd_flash_if.h"
|
||||
|
||||
#ifdef DFU_MAL_SUPPORT_OTP
|
||||
#include "usbd_otp_if.h"
|
||||
#endif
|
||||
|
||||
#ifdef DFU_MAL_SUPPORT_MEM
|
||||
#include "usbd_mem_if_template.h"
|
||||
#endif
|
||||
|
||||
/* Private typedef -----------------------------------------------------------*/
|
||||
/* Private define ------------------------------------------------------------*/
|
||||
/* Private macro -------------------------------------------------------------*/
|
||||
/* Private variables ---------------------------------------------------------*/
|
||||
|
||||
/* Global Memories callback and string descriptors reference tables.
|
||||
To add a new memory, modify the value of MAX_USED_MEDIA in usbd_dfu_mal.h
|
||||
and add the pointer to the callback structure in this table.
|
||||
Then add the pointer to the memory string descriptor in usbd_dfu_StringDesc table.
|
||||
No other operation is required. */
|
||||
DFU_MAL_Prop_TypeDef* tMALTab[MAX_USED_MEDIA] = {
|
||||
&DFU_Flash_cb
|
||||
#ifdef DFU_MAL_SUPPORT_OTP
|
||||
, &DFU_Otp_cb
|
||||
#endif
|
||||
#ifdef DFU_MAL_SUPPORT_MEM
|
||||
, &DFU_Mem_cb
|
||||
#endif
|
||||
};
|
||||
|
||||
#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED
|
||||
#if defined ( __ICCARM__ ) /*!< IAR Compiler */
|
||||
#pragma data_alignment=4
|
||||
#endif
|
||||
#endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */
|
||||
|
||||
__ALIGN_BEGIN const uint8_t* usbd_dfu_StringDesc[MAX_USED_MEDIA] __ALIGN_END = {
|
||||
FLASH_IF_STRING
|
||||
#ifdef DFU_MAL_SUPPORT_OTP
|
||||
, OTP_IF_STRING
|
||||
#endif
|
||||
#ifdef DFU_MAL_SUPPORT_MEM
|
||||
, MEM_IF_STRING
|
||||
#endif
|
||||
};
|
||||
|
||||
#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED
|
||||
#if defined ( __ICCARM__ ) /*!< IAR Compiler */
|
||||
#pragma data_alignment=4
|
||||
#endif
|
||||
#endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */
|
||||
/* RAM Buffer for Downloaded Data */
|
||||
__ALIGN_BEGIN uint8_t MAL_Buffer[XFERSIZE] __ALIGN_END ;
|
||||
|
||||
/* Private function prototypes -----------------------------------------------*/
|
||||
static uint8_t MAL_CheckAdd (uint32_t Add);
|
||||
/* Private functions ---------------------------------------------------------*/
|
||||
|
||||
/**
|
||||
* @brief MAL_Init
|
||||
* Initializes the Media on the STM32
|
||||
* @param None
|
||||
* @retval Result of the opeartion (MAL_OK in all cases)
|
||||
*/
|
||||
uint16_t MAL_Init(void)
|
||||
{
|
||||
uint32_t memIdx = 0;
|
||||
|
||||
/* Init all supported memories */
|
||||
for(memIdx = 0; memIdx < MAX_USED_MEDIA; memIdx++)
|
||||
{
|
||||
/* If the check addres is positive, exit with the memory index */
|
||||
if (tMALTab[memIdx]->pMAL_Init != NULL)
|
||||
{
|
||||
tMALTab[memIdx]->pMAL_Init();
|
||||
}
|
||||
}
|
||||
|
||||
return MAL_OK;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief MAL_DeInit
|
||||
* DeInitializes the Media on the STM32
|
||||
* @param None
|
||||
* @retval Result of the opeartion (MAL_OK in all cases)
|
||||
*/
|
||||
uint16_t MAL_DeInit(void)
|
||||
{
|
||||
uint32_t memIdx = 0;
|
||||
|
||||
/* Init all supported memories */
|
||||
for(memIdx = 0; memIdx < MAX_USED_MEDIA; memIdx++)
|
||||
{
|
||||
/* Check if the command is supported */
|
||||
if (tMALTab[memIdx]->pMAL_DeInit != NULL)
|
||||
{
|
||||
tMALTab[memIdx]->pMAL_DeInit();
|
||||
}
|
||||
}
|
||||
|
||||
return MAL_OK;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief MAL_Erase
|
||||
* Erase a sector of memory.
|
||||
* @param Add: Sector address/code
|
||||
* @retval Result of the opeartion: MAL_OK if all operations are OK else MAL_FAIL
|
||||
*/
|
||||
uint16_t MAL_Erase(uint32_t Add)
|
||||
{
|
||||
uint32_t memIdx = MAL_CheckAdd(Add);
|
||||
|
||||
/* Check if the area is protected */
|
||||
if (DFU_MAL_IS_PROTECTED_AREA(Add))
|
||||
{
|
||||
return MAL_FAIL;
|
||||
}
|
||||
|
||||
if (memIdx < MAX_USED_MEDIA)
|
||||
{
|
||||
/* Check if the command is supported */
|
||||
if (tMALTab[memIdx]->pMAL_Erase != NULL)
|
||||
{
|
||||
return tMALTab[memIdx]->pMAL_Erase(Add);
|
||||
}
|
||||
else
|
||||
{
|
||||
return MAL_FAIL;
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
return MAL_FAIL;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief MAL_Write
|
||||
* Write sectors of memory.
|
||||
* @param Add: Sector address/code
|
||||
* @param Len: Number of data to be written (in bytes)
|
||||
* @retval Result of the opeartion: MAL_OK if all operations are OK else MAL_FAIL
|
||||
*/
|
||||
uint16_t MAL_Write (uint32_t Add, uint32_t Len)
|
||||
{
|
||||
uint32_t memIdx = MAL_CheckAdd(Add);
|
||||
|
||||
/* Check if the area is protected */
|
||||
if (DFU_MAL_IS_PROTECTED_AREA(Add))
|
||||
{
|
||||
return MAL_FAIL;
|
||||
}
|
||||
|
||||
if (memIdx < MAX_USED_MEDIA)
|
||||
{
|
||||
/* Check if the command is supported */
|
||||
if (tMALTab[memIdx]->pMAL_Write != NULL)
|
||||
{
|
||||
return tMALTab[memIdx]->pMAL_Write(Add, Len);
|
||||
}
|
||||
else
|
||||
{
|
||||
return MAL_FAIL;
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
return MAL_FAIL;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief MAL_Read
|
||||
* Read sectors of memory.
|
||||
* @param Add: Sector address/code
|
||||
* @param Len: Number of data to be written (in bytes)
|
||||
* @retval Buffer pointer
|
||||
*/
|
||||
uint8_t *MAL_Read (uint32_t Add, uint32_t Len)
|
||||
{
|
||||
uint32_t memIdx = MAL_CheckAdd(Add);
|
||||
|
||||
if (memIdx < MAX_USED_MEDIA)
|
||||
{
|
||||
/* Check if the command is supported */
|
||||
if (tMALTab[memIdx]->pMAL_Read != NULL)
|
||||
{
|
||||
return tMALTab[memIdx]->pMAL_Read(Add, Len);
|
||||
}
|
||||
else
|
||||
{
|
||||
return MAL_Buffer;
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
return MAL_Buffer;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief MAL_GetStatus
|
||||
* Get the status of a given memory.
|
||||
* @param Add: Sector address/code (allow to determine which memory will be addressed)
|
||||
* @param Cmd: 0 for erase and 1 for write
|
||||
* @param buffer: pointer to the buffer where the status data will be stored.
|
||||
* @retval Buffer pointer
|
||||
*/
|
||||
uint16_t MAL_GetStatus(uint32_t Add , uint8_t Cmd, uint8_t *buffer)
|
||||
{
|
||||
uint32_t memIdx = MAL_CheckAdd(Add);
|
||||
|
||||
if (memIdx < MAX_USED_MEDIA)
|
||||
{
|
||||
if (Cmd & 0x01)
|
||||
{
|
||||
SET_POLLING_TIMING(tMALTab[memIdx]->EraseTiming);
|
||||
}
|
||||
else
|
||||
{
|
||||
SET_POLLING_TIMING(tMALTab[memIdx]->WriteTiming);
|
||||
}
|
||||
|
||||
return MAL_OK;
|
||||
}
|
||||
else
|
||||
{
|
||||
return MAL_FAIL;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief MAL_CheckAdd
|
||||
* Determine which memory should be managed.
|
||||
* @param Add: Sector address/code (allow to determine which memory will be addressed)
|
||||
* @retval Index of the addressed memory.
|
||||
*/
|
||||
static uint8_t MAL_CheckAdd(uint32_t Add)
|
||||
{
|
||||
uint32_t memIdx = 0;
|
||||
|
||||
/* Check with all supported memories */
|
||||
for(memIdx = 0; memIdx < MAX_USED_MEDIA; memIdx++)
|
||||
{
|
||||
/* If the check addres is positive, exit with the memory index */
|
||||
if (tMALTab[memIdx]->pMAL_CheckAdd(Add) == MAL_OK)
|
||||
{
|
||||
return memIdx;
|
||||
}
|
||||
}
|
||||
/* If no memory found, return MAX_USED_MEDIA */
|
||||
return (MAX_USED_MEDIA);
|
||||
}
|
||||
|
||||
/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/
|
221
lib/main/STM32_USB_Device_Library/Class/dfu/src/usbd_flash_if.c
Normal file
221
lib/main/STM32_USB_Device_Library/Class/dfu/src/usbd_flash_if.c
Normal file
|
@ -0,0 +1,221 @@
|
|||
/**
|
||||
******************************************************************************
|
||||
* @file usbd_flash_if.c
|
||||
* @author MCD Application Team
|
||||
* @version V1.0.0
|
||||
* @date 22-July-2011
|
||||
* @brief Specific media access Layer for internal flash.
|
||||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
|
||||
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
|
||||
* TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
|
||||
* DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
|
||||
* FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
|
||||
* CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
|
||||
*
|
||||
* <h2><center>© COPYRIGHT 2011 STMicroelectronics</center></h2>
|
||||
******************************************************************************
|
||||
*/
|
||||
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
#include "usbd_flash_if.h"
|
||||
#include "usbd_dfu_mal.h"
|
||||
|
||||
/* Private typedef -----------------------------------------------------------*/
|
||||
/* Private define ------------------------------------------------------------*/
|
||||
/* Private macro -------------------------------------------------------------*/
|
||||
|
||||
/* Private function prototypes -----------------------------------------------*/
|
||||
uint16_t FLASH_If_Init(void);
|
||||
uint16_t FLASH_If_Erase (uint32_t Add);
|
||||
uint16_t FLASH_If_Write (uint32_t Add, uint32_t Len);
|
||||
uint8_t *FLASH_If_Read (uint32_t Add, uint32_t Len);
|
||||
uint16_t FLASH_If_DeInit(void);
|
||||
uint16_t FLASH_If_CheckAdd(uint32_t Add);
|
||||
|
||||
|
||||
/* Private variables ---------------------------------------------------------*/
|
||||
DFU_MAL_Prop_TypeDef DFU_Flash_cb =
|
||||
{
|
||||
FLASH_IF_STRING,
|
||||
FLASH_If_Init,
|
||||
FLASH_If_DeInit,
|
||||
FLASH_If_Erase,
|
||||
FLASH_If_Write,
|
||||
FLASH_If_Read,
|
||||
FLASH_If_CheckAdd,
|
||||
50, /* Erase Time in ms */
|
||||
50 /* Programming Time in ms */
|
||||
};
|
||||
|
||||
/* Private functions ---------------------------------------------------------*/
|
||||
|
||||
/**
|
||||
* @brief FLASH_If_Init
|
||||
* Memory initialization routine.
|
||||
* @param None
|
||||
* @retval MAL_OK if operation is successeful, MAL_FAIL else.
|
||||
*/
|
||||
uint16_t FLASH_If_Init(void)
|
||||
{
|
||||
/* Unlock the internal flash */
|
||||
FLASH_Unlock();
|
||||
|
||||
return MAL_OK;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief FLASH_If_DeInit
|
||||
* Memory deinitialization routine.
|
||||
* @param None
|
||||
* @retval MAL_OK if operation is successeful, MAL_FAIL else.
|
||||
*/
|
||||
uint16_t FLASH_If_DeInit(void)
|
||||
{
|
||||
/* Lock the internal flash */
|
||||
FLASH_Lock();
|
||||
|
||||
return MAL_OK;
|
||||
}
|
||||
|
||||
/*******************************************************************************
|
||||
* Function Name : FLASH_If_Erase
|
||||
* Description : Erase sector
|
||||
* Input : None
|
||||
* Output : None
|
||||
* Return : None
|
||||
*******************************************************************************/
|
||||
uint16_t FLASH_If_Erase(uint32_t Add)
|
||||
{
|
||||
#ifdef STM32F2XX
|
||||
/* Check which sector has to be erased */
|
||||
if (Add < 0x08004000)
|
||||
{
|
||||
FLASH_EraseSector(FLASH_Sector_0, VoltageRange_3);
|
||||
}
|
||||
else if (Add < 0x08008000)
|
||||
{
|
||||
FLASH_EraseSector(FLASH_Sector_1, VoltageRange_3);
|
||||
}
|
||||
else if (Add < 0x0800C000)
|
||||
{
|
||||
FLASH_EraseSector(FLASH_Sector_2, VoltageRange_3);
|
||||
}
|
||||
else if (Add < 0x08010000)
|
||||
{
|
||||
FLASH_EraseSector(FLASH_Sector_3, VoltageRange_3);
|
||||
}
|
||||
else if (Add < 0x08020000)
|
||||
{
|
||||
FLASH_EraseSector(FLASH_Sector_4, VoltageRange_3);
|
||||
}
|
||||
else if (Add < 0x08040000)
|
||||
{
|
||||
FLASH_EraseSector(FLASH_Sector_5, VoltageRange_3);
|
||||
}
|
||||
else if (Add < 0x08060000)
|
||||
{
|
||||
FLASH_EraseSector(FLASH_Sector_6, VoltageRange_3);
|
||||
}
|
||||
else if (Add < 0x08080000)
|
||||
{
|
||||
FLASH_EraseSector(FLASH_Sector_7, VoltageRange_3);
|
||||
}
|
||||
else if (Add < 0x080A0000)
|
||||
{
|
||||
FLASH_EraseSector(FLASH_Sector_8, VoltageRange_3);
|
||||
}
|
||||
else if (Add < 0x080C0000)
|
||||
{
|
||||
FLASH_EraseSector(FLASH_Sector_9, VoltageRange_3);
|
||||
}
|
||||
else if (Add < 0x080E0000)
|
||||
{
|
||||
FLASH_EraseSector(FLASH_Sector_10, VoltageRange_3);
|
||||
}
|
||||
else if (Add < 0x08100000)
|
||||
{
|
||||
FLASH_EraseSector(FLASH_Sector_11, VoltageRange_3);
|
||||
}
|
||||
else
|
||||
{
|
||||
return MAL_FAIL;
|
||||
}
|
||||
#elif defined(STM32F10X_CL)
|
||||
/* Call the standard Flash erase function */
|
||||
FLASH_ErasePage(Add);
|
||||
#endif /* STM32F2XX */
|
||||
|
||||
return MAL_OK;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief FLASH_If_Write
|
||||
* Memory write routine.
|
||||
* @param Add: Address to be written to.
|
||||
* @param Len: Number of data to be written (in bytes).
|
||||
* @retval MAL_OK if operation is successeful, MAL_FAIL else.
|
||||
*/
|
||||
uint16_t FLASH_If_Write(uint32_t Add, uint32_t Len)
|
||||
{
|
||||
uint32_t idx = 0;
|
||||
|
||||
if (Len & 0x3) /* Not an aligned data */
|
||||
{
|
||||
for (idx = Len; idx < ((Len & 0xFFFC) + 4); idx++)
|
||||
{
|
||||
MAL_Buffer[idx] = 0xFF;
|
||||
}
|
||||
}
|
||||
|
||||
/* Data received are Word multiple */
|
||||
for (idx = 0; idx < Len; idx = idx + 4)
|
||||
{
|
||||
FLASH_ProgramWord(Add, *(uint32_t *)(MAL_Buffer + idx));
|
||||
Add += 4;
|
||||
}
|
||||
return MAL_OK;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief FLASH_If_Read
|
||||
* Memory read routine.
|
||||
* @param Add: Address to be read from.
|
||||
* @param Len: Number of data to be read (in bytes).
|
||||
* @retval Pointer to the phyisical address where data should be read.
|
||||
*/
|
||||
uint8_t *FLASH_If_Read (uint32_t Add, uint32_t Len)
|
||||
{
|
||||
#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED
|
||||
uint32_t idx = 0;
|
||||
for (idx = 0; idx < Len; idx += 4)
|
||||
{
|
||||
*(uint32_t*)(MAL_Buffer + idx) = *(uint32_t *)(Add + idx);
|
||||
}
|
||||
return (uint8_t*)(MAL_Buffer);
|
||||
#else
|
||||
return (uint8_t *)(Add);
|
||||
#endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief FLASH_If_CheckAdd
|
||||
* Check if the address is an allowed address for this memory.
|
||||
* @param Add: Address to be checked.
|
||||
* @param Len: Number of data to be read (in bytes).
|
||||
* @retval MAL_OK if the address is allowed, MAL_FAIL else.
|
||||
*/
|
||||
uint16_t FLASH_If_CheckAdd(uint32_t Add)
|
||||
{
|
||||
if ((Add >= FLASH_START_ADD) && (Add < FLASH_END_ADD))
|
||||
{
|
||||
return MAL_OK;
|
||||
}
|
||||
else
|
||||
{
|
||||
return MAL_FAIL;
|
||||
}
|
||||
}
|
||||
/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/
|
|
@ -0,0 +1,133 @@
|
|||
/**
|
||||
******************************************************************************
|
||||
* @file usbd_mem_if_template.c
|
||||
* @author MCD Application Team
|
||||
* @version V1.0.0
|
||||
* @date 22-July-2011
|
||||
* @brief Specific media access Layer for a template memory. This file is
|
||||
provided as template example showing how to implement a new memory
|
||||
interface based on pre-defined API.
|
||||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
|
||||
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
|
||||
* TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
|
||||
* DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
|
||||
* FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
|
||||
* CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
|
||||
*
|
||||
* <h2><center>© COPYRIGHT 2011 STMicroelectronics</center></h2>
|
||||
******************************************************************************
|
||||
*/
|
||||
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
#include "usbd_mem_if_template.h"
|
||||
#include "usbd_dfu_mal.h"
|
||||
|
||||
/* Private typedef -----------------------------------------------------------*/
|
||||
/* Private define ------------------------------------------------------------*/
|
||||
/* Private macro -------------------------------------------------------------*/
|
||||
|
||||
/* Private function prototypes -----------------------------------------------*/
|
||||
uint16_t MEM_If_Init(void);
|
||||
uint16_t MEM_If_Erase (uint32_t Add);
|
||||
uint16_t MEM_If_Write (uint32_t Add, uint32_t Len);
|
||||
uint8_t *MEM_If_Read (uint32_t Add, uint32_t Len);
|
||||
uint16_t MEM_If_DeInit(void);
|
||||
uint16_t MEM_If_CheckAdd(uint32_t Add);
|
||||
|
||||
|
||||
/* Private variables ---------------------------------------------------------*/
|
||||
DFU_MAL_Prop_TypeDef DFU_Mem_cb =
|
||||
{
|
||||
MEM_IF_STRING,
|
||||
MEM_If_Init,
|
||||
MEM_If_DeInit,
|
||||
MEM_If_Erase,
|
||||
MEM_If_Write,
|
||||
MEM_If_Read,
|
||||
MEM_If_CheckAdd,
|
||||
10, /* Erase Time in ms */
|
||||
10 /* Programming Time in ms */
|
||||
};
|
||||
|
||||
/* Private functions ---------------------------------------------------------*/
|
||||
|
||||
/**
|
||||
* @brief MEM_If_Init
|
||||
* Memory initialization routine.
|
||||
* @param None
|
||||
* @retval MAL_OK if operation is successeful, MAL_FAIL else.
|
||||
*/
|
||||
uint16_t MEM_If_Init(void)
|
||||
{
|
||||
return MAL_OK;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief MEM_If_DeInit
|
||||
* Memory deinitialization routine.
|
||||
* @param None
|
||||
* @retval MAL_OK if operation is successeful, MAL_FAIL else.
|
||||
*/
|
||||
uint16_t MEM_If_DeInit(void)
|
||||
{
|
||||
return MAL_OK;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief MEM_If_Erase
|
||||
* Erase sector.
|
||||
* @param Add: Address of sector to be erased.
|
||||
* @retval MAL_OK if operation is successeful, MAL_FAIL else.
|
||||
*/
|
||||
uint16_t MEM_If_Erase(uint32_t Add)
|
||||
{
|
||||
return MAL_OK;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief MEM_If_Write
|
||||
* Memory write routine.
|
||||
* @param Add: Address to be written to.
|
||||
* @param Len: Number of data to be written (in bytes).
|
||||
* @retval MAL_OK if operation is successeful, MAL_FAIL else.
|
||||
*/
|
||||
uint16_t MEM_If_Write(uint32_t Add, uint32_t Len)
|
||||
{
|
||||
return MAL_OK;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief MEM_If_Read
|
||||
* Memory read routine.
|
||||
* @param Add: Address to be read from.
|
||||
* @param Len: Number of data to be read (in bytes).
|
||||
* @retval Pointer to the phyisical address where data should be read.
|
||||
*/
|
||||
uint8_t *MEM_If_Read (uint32_t Add, uint32_t Len)
|
||||
{
|
||||
/* Return a valid address to avoid HardFault */
|
||||
return (uint8_t*)(MAL_Buffer);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief MEM_If_CheckAdd
|
||||
* Check if the address is an allowed address for this memory.
|
||||
* @param Add: Address to be checked.
|
||||
* @param Len: Number of data to be read (in bytes).
|
||||
* @retval MAL_OK if the address is allowed, MAL_FAIL else.
|
||||
*/
|
||||
uint16_t MEM_If_CheckAdd(uint32_t Add)
|
||||
{
|
||||
if ((Add >= MEM_START_ADD) && (Add < MEM_END_ADD))
|
||||
{
|
||||
return MAL_OK;
|
||||
}
|
||||
else
|
||||
{
|
||||
return MAL_FAIL;
|
||||
}
|
||||
}
|
||||
/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/
|
120
lib/main/STM32_USB_Device_Library/Class/dfu/src/usbd_otp_if.c
Normal file
120
lib/main/STM32_USB_Device_Library/Class/dfu/src/usbd_otp_if.c
Normal file
|
@ -0,0 +1,120 @@
|
|||
/**
|
||||
******************************************************************************
|
||||
* @file usbd_otp_if.c
|
||||
* @author MCD Application Team
|
||||
* @version V1.0.0
|
||||
* @date 22-July-2011
|
||||
* @brief Specific media access Layer for OTP (One Time Programming) memory.
|
||||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
|
||||
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
|
||||
* TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
|
||||
* DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
|
||||
* FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
|
||||
* CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
|
||||
*
|
||||
* <h2><center>© COPYRIGHT 2011 STMicroelectronics</center></h2>
|
||||
******************************************************************************
|
||||
*/
|
||||
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
#include "usbd_otp_if.h"
|
||||
#include "usbd_dfu_mal.h"
|
||||
|
||||
/* Private typedef -----------------------------------------------------------*/
|
||||
/* Private define ------------------------------------------------------------*/
|
||||
/* Private macro -------------------------------------------------------------*/
|
||||
|
||||
/* Private function prototypes -----------------------------------------------*/
|
||||
uint16_t OTP_If_Write (uint32_t Add, uint32_t Len);
|
||||
uint8_t *OTP_If_Read (uint32_t Add, uint32_t Len);
|
||||
uint16_t OTP_If_DeInit(void);
|
||||
uint16_t OTP_If_CheckAdd(uint32_t Add);
|
||||
|
||||
|
||||
/* Private variables ---------------------------------------------------------*/
|
||||
DFU_MAL_Prop_TypeDef DFU_Otp_cb =
|
||||
{
|
||||
OTP_IF_STRING,
|
||||
NULL, /* Init not supported*/
|
||||
NULL, /* DeInit not supported */
|
||||
NULL, /* Erase not supported */
|
||||
OTP_If_Write,
|
||||
OTP_If_Read,
|
||||
OTP_If_CheckAdd,
|
||||
1, /* Erase Time in ms */
|
||||
10 /* Programming Time in ms */
|
||||
};
|
||||
|
||||
/* Private functions ---------------------------------------------------------*/
|
||||
|
||||
/**
|
||||
* @brief OTP_If_Write
|
||||
* Memory write routine.
|
||||
* @param Add: Address to be written to.
|
||||
* @param Len: Number of data to be written (in bytes).
|
||||
* @retval MAL_OK if operation is successeful, MAL_FAIL else.
|
||||
*/
|
||||
uint16_t OTP_If_Write(uint32_t Add, uint32_t Len)
|
||||
{
|
||||
uint32_t idx = 0;
|
||||
|
||||
if (Len & 0x3) /* Not an aligned data */
|
||||
{
|
||||
for (idx = Len; idx < ((Len & 0xFFFC) + 4); idx++)
|
||||
{
|
||||
MAL_Buffer[idx] = 0xFF;
|
||||
}
|
||||
}
|
||||
|
||||
/* Data received are Word multiple */
|
||||
for (idx = 0; idx < Len; idx = idx + 4)
|
||||
{
|
||||
FLASH_ProgramWord(Add, *(uint32_t *)(MAL_Buffer + idx));
|
||||
Add += 4;
|
||||
}
|
||||
return MAL_OK;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief OTP_If_Read
|
||||
* Memory read routine.
|
||||
* @param Add: Address to be read from.
|
||||
* @param Len: Number of data to be read (in bytes).
|
||||
* @retval Pointer to the phyisical address where data should be read.
|
||||
*/
|
||||
uint8_t *OTP_If_Read (uint32_t Add, uint32_t Len)
|
||||
{
|
||||
#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED
|
||||
uint32_t idx = 0;
|
||||
for (idx = 0; idx < Len; idx += 4)
|
||||
{
|
||||
*(uint32_t*)(MAL_Buffer + idx) = *(uint32_t *)(Add + idx);
|
||||
}
|
||||
return (uint8_t*)(MAL_Buffer);
|
||||
#else
|
||||
return (uint8_t*)(Add);
|
||||
#endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief OTP_If_CheckAdd
|
||||
* Check if the address is an allowed address for this memory.
|
||||
* @param Add: Address to be checked.
|
||||
* @param Len: Number of data to be read (in bytes).
|
||||
* @retval MAL_OK if the address is allowed, MAL_FAIL else.
|
||||
*/
|
||||
uint16_t OTP_If_CheckAdd(uint32_t Add)
|
||||
{
|
||||
if ((Add >= OTP_START_ADD) && (Add < OTP_END_ADD))
|
||||
{
|
||||
return MAL_OK;
|
||||
}
|
||||
else
|
||||
{
|
||||
return MAL_FAIL;
|
||||
}
|
||||
}
|
||||
/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/
|
Loading…
Add table
Add a link
Reference in a new issue