support hc32 irq and spi and spi flash

This commit is contained in:
wlyu 2022-11-29 14:16:37 +08:00
parent e5bf0cee41
commit 9b83bc586e
35 changed files with 4472 additions and 1638 deletions

View File

@ -11,4 +11,27 @@ config HC32F4A0_BOARD
---help---
Select if you are using the HC32F4A0 base board with the HC32F4A0.
config HC32_ROMFS
bool "Automount baked-in ROMFS image"
default n
depends on FS_ROMFS
---help---
Select HC32_ROMFS_IMAGEFILE, HC32_ROMFS_DEV_MINOR, HC32_ROMFS_MOUNTPOINT
config HC32_ROMFS_DEV_MINOR
int "Minor for the block device backing the data"
depends on HC32_ROMFS
default 64
config HC32_ROMFS_MOUNTPOINT
string "Mountpoint of the custom romfs image"
depends on HC32_ROMFS
default "/rom"
config HC32_ROMFS_IMAGEFILE
string "ROMFS image file to include into build"
depends on HC32_ROMFS
default "../../../../../rom.img"
endif

View File

@ -57,38 +57,42 @@
/* for lowputc device output */
/* UART RX/TX Port/Pin definition */
#define LP_RX_PORT (GPIO_PORT_H) /* PH6: USART6_RX */
#define LP_RX_PIN (GPIO_PIN_06)
#define LP_RX_GPIO_FUNC (GPIO_FUNC_37_USART6_RX)
#define DBG_RX_PORT (GPIO_PORT_H) /* PH6: USART6_RX */
#define DBG_RX_PIN (GPIO_PIN_06)
#define DBG_RX_GPIO_FUNC (GPIO_FUNC_37_USART6_RX)
#define LP_TX_PORT (GPIO_PORT_E) /* PE6: USART6_TX */
#define LP_TX_PIN (GPIO_PIN_06)
#define LP_TX_GPIO_FUNC (GPIO_FUNC_36_USART6_TX)
#define DBG_TX_PORT (GPIO_PORT_E) /* PE6: USART6_TX */
#define DBG_TX_PIN (GPIO_PIN_06)
#define DBG_TX_GPIO_FUNC (GPIO_FUNC_36_USART6_TX)
/* UART unit definition */
#define LP_UNIT (M4_USART6)
#define LP_FUNCTION_CLK_GATE (PWC_FCG3_USART6)
#define DBG_UNIT (M4_USART6)
#define DBG_BAUDRATE (115200UL)
#define DBG_FUNCTION_CLK_GATE (PWC_FCG3_USART6)
/* UART unit interrupt definition */
#define LP_UNIT_ERR_INT_SRC (INT_USART6_EI)
#define LP_UNIT_ERR_INT_IRQn (Int015_IRQn + HC32_IRQ_FIRST)
#define DBG_UNIT_ERR_INT_SRC (INT_USART6_EI)
#define DBG_UNIT_ERR_INT_IRQn (Int010_IRQn)
#define LP_UNIT_RX_INT_SRC (INT_USART6_RI)
#define LP_UNIT_RX_INT_IRQn (Int103_IRQn + HC32_IRQ_FIRST)
#define DBG_UNIT_RX_INT_SRC (INT_USART6_RI)
#define DBG_UNIT_RX_INT_IRQn (Int011_IRQn)
#define LP_UNIT_TX_INT_SRC (INT_USART6_TI)
#define LP_UNIT_TX_INT_IRQn (Int102_IRQn + HC32_IRQ_FIRST)
#define DBG_RXTO_INT_SRC (INT_USART6_RTO)
#define DBG_RXTO_INT_IRQn (Int012_IRQn)
#define LP_UNIT_TCI_INT_SRC (INT_USART6_TCI)
#define LP_UNIT_TCI_INT_IRQn (Int099_IRQn + HC32_IRQ_FIRST)
#define DBG_UNIT_TX_INT_SRC (INT_USART6_TI)
#define DBG_UNIT_TX_INT_IRQn (Int013_IRQn)
#define DBG_UNIT_TCI_INT_SRC (INT_USART6_TCI)
#define DBG_UNIT_TCI_INT_IRQn (Int014_IRQn)
/* printf device s*/
#define BSP_PRINTF_DEVICE LP_UNIT
#define BSP_PRINTF_BAUDRATE (115200)
#define BSP_PRINTF_DEVICE DBG_UNIT
#define BSP_PRINTF_BAUDRATE DBG_BAUDRATE
#define BSP_PRINTF_PORT LP_TX_PORT
#define BSP_PRINTF_PORT DBG_TX_PORT
#define BSP_PRINTF_PIN LP_TX_PIN
#define BSP_PRINTF_PORT_FUNC LP_TX_GPIO_FUNC
#define BSP_PRINTF_PIN DBG_TX_PIN
#define BSP_PRINTF_PORT_FUNC DBG_TX_GPIO_FUNC
#endif /* __BOARDS_ARM_HC32_HC32F4A0_INCLUDE_BOARD_H */

View File

@ -41,7 +41,7 @@ USER_LIBGCC = "${shell "$(CC)" $(ARCHCPUFLAGS) -print-libgcc-file-name}"
# Source files
CSRCS = stm32_userspace.c
CSRCS = hc32_userspace.c
COBJS = $(CSRCS:.c=$(OBJEXT))
OBJS = $(COBJS)

View File

@ -52,7 +52,7 @@
# error "CONFIG_NUTTX_USERSPACE not defined"
#endif
#if CONFIG_NUTTX_USERSPACE != 0x20060000
#if CONFIG_NUTTX_USERSPACE != 0x20062000
# error "CONFIG_NUTTX_USERSPACE must be 0x20060000 to match memory.ld"
#endif

View File

@ -1,5 +1,5 @@
/****************************************************************************
* boards/arm/stm32/aiit-arm32-board/scripts/gnu-elf.ld
* boards/arm/hc32/hc32f4a0/scripts/gnu-elf.ld
*
* Licensed to the Apache Software Foundation (ASF) under one or more
* contributor license agreements. See the NOTICE file distributed with

View File

@ -1,5 +1,5 @@
/****************************************************************************
* boards/arm/stm32/aiit-arm32-board/scripts/kernel-space.ld
* boards/arm/hc32/hc32f4a0/scripts/kernel-space.ld
*
* Licensed to the Apache Software Foundation (ASF) under one or more
* contributor license agreements. See the NOTICE file distributed with

View File

@ -32,7 +32,7 @@
* For MPU support, the kernel-mode NuttX section is assumed to be 128Kb of
* FLASH and 4Kb of SRAM. That is an excessive amount for the kernel which
* should fit into 64KB and, of course, can be optimized as needed (See
* also boards/arm/stm32/aiit-arm32-board/scripts/kernel-space.ld). Allowing the
* also boards/arm/hc32/hc32f4a0/scripts/kernel-space.ld). Allowing the
* additional does permit addition debug instrumentation to be added to the
* kernel space without overflowing the partition.
*
@ -73,13 +73,13 @@ MEMORY
{
/* 2Mb FLASH */
kflash (rx) : ORIGIN = 0x00000000, LENGTH = 2M
uflash (rx) : ORIGIN = 0x00200000, LENGTH = 128K
xflash (rx) : ORIGIN = 0x00220000, LENGTH = 768K
kflash (rx) : ORIGIN = 0x00000000, LENGTH = 64K
uflash (rx) : ORIGIN = 0x00010000, LENGTH = 1M
xflash (rx) : ORIGIN = 0x00110000, LENGTH = 128K
/* 512Kb of contiguous SRAM */
ksram (rwx) : ORIGIN = 0x1FFE0000, LENGTH = 512K
usram (rwx) : ORIGIN = 0x20060000, LENGTH = 4K
xsram (rwx) : ORIGIN = 0x20062000, LENGTH = 4K
ksram (rwx) : ORIGIN = 0x1FFE0000, LENGTH = 64K
usram (rwx) : ORIGIN = 0x1FFF0000, LENGTH = 448K
xsram (rwx) : ORIGIN = 0x20070000, LENGTH = 4K
}

View File

@ -48,16 +48,16 @@ SECTIONS
_sinit = ABSOLUTE(.);
*(.init_array .init_array.*)
_einit = ABSOLUTE(.);
} > kflash
} > uflash
.ARM.extab : {
*(.ARM.extab*)
} > kflash
} > uflash
__exidx_start = ABSOLUTE(.);
.ARM.exidx : {
*(.ARM.exidx*)
} > kflash
} > uflash
__exidx_end = ABSOLUTE(.);
@ -70,7 +70,7 @@ SECTIONS
CONSTRUCTORS
. = ALIGN(4);
_edata = ABSOLUTE(.);
} > ksram AT > kflash
} > usram AT > uflash
.bss : {
_sbss = ABSOLUTE(.);
@ -79,7 +79,7 @@ SECTIONS
*(COMMON)
. = ALIGN(4);
_ebss = ABSOLUTE(.);
} > ksram
} > usram
/* Stabs debugging sections */

View File

@ -26,6 +26,10 @@ ifeq ($(CONFIG_ARCH_LEDS),y)
CSRCS +=
endif
ifeq ($(CONFIG_STM32_ROMFS),y)
CSRCS += hc32_romfs_initialize.c
endif
DEPPATH += --dep-path board
VPATH += :board
CFLAGS += $(shell $(INCDIR) "$(CC)" $(TOPDIR)$(DELIM)arch$(DELIM)$(CONFIG_ARCH)$(DELIM)src$(DELIM)board$(DELIM)board)

View File

@ -38,6 +38,7 @@
****************************************************************************/
extern int hc32_bringup(void);
extern int hc32_spidev_initialized;
/****************************************************************************
* Name: hc32_boardinitialize
@ -52,57 +53,57 @@ extern int hc32_bringup(void);
void hc32_boardinitialize(void)
{
//#ifdef CONFIG_SCHED_CRITMONITOR
// /* Enable ITM and DWT resources, if not left enabled by debugger. */
//
// modifyreg32(NVIC_DEMCR, 0, NVIC_DEMCR_TRCENA);
//
// /* Make sure the high speed cycle counter is running. It will be started
// * automatically only if a debugger is connected.
// */
//
// putreg32(0xc5acce55, ITM_LAR);
// modifyreg32(DWT_CTRL, 0, DWT_CTRL_CYCCNTENA_MASK);
//#endif
//
//#if defined(CONFIG_HC32_SPI1) || defined(CONFIG_HC32_SPI2) || defined(CONFIG_HC32_SPI3)
// /* Configure SPI chip selects if 1) SPI is not disabled, and 2) the weak
// * function hc32_spidev_initialize() has been brought into the link.
// */
//
// if (hc32_spidev_initialize)
// {
// hc32_spidev_initialize();
// }
//#endif
//
//#ifdef CONFIG_HC32_OTGFS
// /* Initialize USB if the 1) OTG FS controller is in the configuration and
// * 2) disabled, and 3) the weak function hc32_usbinitialize() has been
// * brought into the build. Presumably either CONFIG_USBDEV or
// * CONFIG_USBHOST is also selected.
// */
//
// if (hc32_usbinitialize)
// {
// hc32_usbinitialize();
// }
//#endif
//
//#ifdef HAVE_NETMONITOR
// /* Configure board resources to support networking. */
//
// if (hc32_netinitialize)
// {
// hc32_netinitialize();
// }
//#endif
//
//#ifdef CONFIG_ARCH_LEDS
// /* Configure on-board LEDs if LED support has been selected. */
//
// board_autoled_initialize();
//#endif
#ifdef CONFIG_SCHED_CRITMONITOR
/* Enable ITM and DWT resources, if not left enabled by debugger. */
modifyreg32(NVIC_DEMCR, 0, NVIC_DEMCR_TRCENA);
/* Make sure the high speed cycle counter is running. It will be started
* automatically only if a debugger is connected.
*/
putreg32(0xc5acce55, ITM_LAR);
modifyreg32(DWT_CTRL, 0, DWT_CTRL_CYCCNTENA_MASK);
#endif
#if defined(CONFIG_HC32_SPI1) || defined(CONFIG_HC32_SPI2) || defined(CONFIG_HC32_SPI3)
/* Configure SPI chip selects if 1) SPI is not disabled, and 2) the weak
* function hc32_spidev_initialize() has been brought into the link.
*/
if (hc32_spidev_initialized)
{
hc32_spidev_initialize();
}
#endif
#ifdef CONFIG_HC32_OTGFS
/* Initialize USB if the 1) OTG FS controller is in the configuration and
* 2) disabled, and 3) the weak function hc32_usbinitialize() has been
* brought into the build. Presumably either CONFIG_USBDEV or
* CONFIG_USBHOST is also selected.
*/
if (hc32_usbinitialize)
{
hc32_usbinitialize();
}
#endif
#ifdef HAVE_NETMONITOR
/* Configure board resources to support networking. */
if (hc32_netinitialize)
{
hc32_netinitialize();
}
#endif
#ifdef CONFIG_ARCH_LEDS
/* Configure on-board LEDs if LED support has been selected. */
board_autoled_initialize();
#endif
}
/****************************************************************************

View File

@ -31,6 +31,8 @@
#include <nuttx/fs/fs.h>
#include <hc32_common.h>
/****************************************************************************
* Name: hc32_bringup
*
@ -48,6 +50,27 @@
int hc32_bringup(void)
{
int ret = 0;
#ifdef CONFIG_FS_PROCFS
/* Mount the procfs file system */
ret = nx_mount(NULL, HC32_PROCFS_MOUNTPOINT, "procfs", 0, NULL);
if (ret < 0)
{
serr("ERROR: Failed to mount procfs at %s: %d\n",
HC32_PROCFS_MOUNTPOINT, ret);
}
#endif
#ifdef CONFIG_HC32_ROMFS
ret = hc32_romfs_initialize();
if (ret < 0)
{
serr("ERROR: Failed to mount romfs at %s: %d\n",
CONFIG_HC32_ROMFS_MOUNTPOINT, ret);
}
#endif
printf("start %s\n", __func__);
return ret;
}

View File

@ -0,0 +1,76 @@
/****************************************************************************
* boards/arm/hc32/hc32f4a0/src/hc32_romfs.h
*
* Copyright (C) 2017 Tomasz Wozniak. All rights reserved.
* Author: Tomasz Wozniak <t.wozniak@samsung.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions 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 NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER 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.
*
****************************************************************************/
#ifndef __BOARDS_ARM_HC32_HC32F4A0_SRC_HC32_ROMFS_H
#define __BOARDS_ARM_HC32_HC32F4A0_SRC_HC32_ROMFS_H
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#ifdef CONFIG_HC32_ROMFS
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
#define ROMFS_SECTOR_SIZE 64
/****************************************************************************
* Public Function Prototypes
****************************************************************************/
/****************************************************************************
* Name: stm32_romfs_initialize
*
* Description:
* Registers built-in ROMFS image as block device and mounts it.
*
* Returned Value:
* Zero (OK) on success, a negated errno value on error.
*
* Assumptions/Limitations:
* Memory addresses [&romfs_data_begin .. &romfs_data_begin) should contain
* ROMFS volume data, as included in the assembly snippet above (l. 84).
*
****************************************************************************/
int hc32_romfs_initialize(void);
#endif /* CONFIG_STM32_ROMFS */
#endif /* __BOARDS_ARM_HC32_HC32F4A0_SRC_HC32_ROMFS_H */

View File

@ -0,0 +1,158 @@
/****************************************************************************
* boards/arm/hc32/hc32f4a0/src/hc32_romfs_initialize.c
* This file provides contents of an optional ROMFS volume, mounted at boot.
*
* Copyright (C) 2017 Tomasz Wozniak. All rights reserved.
* Author: Tomasz Wozniak <t.wozniak@samsung.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions 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 NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER 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.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <sys/mount.h>
#include <sys/types.h>
#include <stdint.h>
#include <debug.h>
#include <errno.h>
#include <nuttx/fs/fs.h>
#include <nuttx/drivers/ramdisk.h>
#include "hc32_romfs.h"
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
#ifndef CONFIG_HC32_ROMFS
# error "CONFIG_HC32_ROMFS must be defined"
#else
#ifndef CONFIG_HC32_ROMFS_IMAGEFILE
# error "CONFIG_HC32_ROMFS_IMAGEFILE must be defined"
#endif
#ifndef CONFIG_HC32_ROMFS_DEV_MINOR
# error "CONFIG_HC32_ROMFS_DEV_MINOR must be defined"
#endif
#ifndef CONFIG_HC32_ROMFS_MOUNTPOINT
# error "CONFIG_HC32_ROMFS_MOUNTPOINT must be defined"
#endif
#define NSECTORS(size) (((size) + ROMFS_SECTOR_SIZE - 1)/ROMFS_SECTOR_SIZE)
#define STR2(m) #m
#define STR(m) STR2(m)
#define MKMOUNT_DEVNAME(m) "/dev/ram" STR(m)
#define MOUNT_DEVNAME MKMOUNT_DEVNAME(CONFIG_HC32_ROMFS_DEV_MINOR)
/****************************************************************************
* Private Data
****************************************************************************/
__asm__ (
".section .rodata\n"
".balign 16\n"
".globl romfs_data_begin\n"
"romfs_data_begin:\n"
".incbin " STR(CONFIG_HC32_ROMFS_IMAGEFILE) "\n"\
\
".balign " STR(ROMFS_SECTOR_SIZE) "\n"
".globl romfs_data_end\n"
"romfs_data_end:\n"
".globl romfs_data_size\n"
"romfs_data_size:\n"
".word romfs_data_end - romfs_data_begin\n"
".previous\n");
extern const char romfs_data_begin;
extern const char romfs_data_end;
extern const int romfs_data_size;
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: hc32_romfs_initialize
*
* Description:
* Registers the aboveincluded binary file as block device.
* Then mounts the block device as ROMFS filesystems.
*
* Returned Value:
* Zero (OK) on success, a negated errno value on error.
*
* Assumptions/Limitations:
* Memory addresses [&romfs_data_begin .. &romfs_data_begin) should contain
* ROMFS volume data, as included in the assembly snippet above (l. 84).
*
****************************************************************************/
int hc32_romfs_initialize(void)
{
uintptr_t romfs_data_len;
int ret;
/* Create a ROM disk for the /etc filesystem */
romfs_data_len = (uintptr_t)&romfs_data_end - (uintptr_t)&romfs_data_begin;
ret = romdisk_register(CONFIG_HC32_ROMFS_DEV_MINOR, &romfs_data_begin,
NSECTORS(romfs_data_len), ROMFS_SECTOR_SIZE);
if (ret < 0)
{
ferr("ERROR: romdisk_register failed: %d\n", -ret);
return ret;
}
/* Mount the file system */
finfo("Mounting ROMFS filesystem at target=%s with source=%s\n",
CONFIG_HC32_ROMFS_MOUNTPOINT, MOUNT_DEVNAME);
ret = nx_mount(MOUNT_DEVNAME, CONFIG_HC32_ROMFS_MOUNTPOINT,
"romfs", MS_RDONLY, NULL);
if (ret < 0)
{
ferr("ERROR: nx_mount(%s,%s,romfs) failed: %d\n",
MOUNT_DEVNAME, CONFIG_HC32_ROMFS_MOUNTPOINT, ret);
return ret;
}
return OK;
}
#endif /* CONFIG_HC32_ROMFS */

View File

@ -172,3 +172,26 @@ config HC32_UART8
endmenu # HC32 U[S]ART Selection
config HC32_SPI1
bool "SPI1"
default n
select SPI
select HC32_SPI
config HC32_SPI2
bool "SPI2"
default n
depends on HC32_HAVE_SPI2
select SPI
select HC32_SPI
config HC32_SPI
bool
config HC32_I2C
bool
config HC32_CAN
bool

View File

@ -44,7 +44,6 @@ CMN_ASRCS += arm_lazyexception.S
else
CMN_ASRCS += arm_exception.S
endif
CMN_CSRCS += arm_vectors.c
ifeq ($(CONFIG_ARCH_RAMVECTORS),y)
CMN_CSRCS += arm_ramvec_initialize.c arm_ramvec_attach.c
@ -77,12 +76,19 @@ ifeq ($(CONFIG_SCHED_THREAD_LOCAL),y)
CMN_CSRCS += arm_tls.c
endif
CMN_CSRCS += hc32_vectors.c
CHIP_CSRCS = hc32_allocateheap.c hc32_gpio.c
CHIP_CSRCS += hc32_irq.c hc32_idle.c hc32_mpuinit.c
CHIP_CSRCS += hc32_rcc.c hc32_start.c hc32_serial.c
CHIP_CSRCS += hc32_pm.c hc32_timerisr.c hc32_lowputc.c
CHIP_CSRCS += hc32_console.c
CHIP_CSRCS += hc32f4a0_clk.c hc32f4a0_efm.c hc32f4a0_gpio.c
CHIP_CSRCS += hc32f4a0_interrupts.c hc32f4a0_usart.c hc32f4a0_utility.c
CHIP_CSRCS += hc32f4a0_sram.c hc32f4a0_pwc.c
CHIP_CSRCS += hc32f4a0_spi.c
CHIP_CSRCS += hc32_spiflash.c hc32_spi.c

View File

@ -89,7 +89,7 @@ extern "C"
#define DDL_RTC_ENABLE (DDL_OFF)
#define DDL_SDIOC_ENABLE (DDL_OFF)
#define DDL_SMC_ENABLE (DDL_OFF)
#define DDL_SPI_ENABLE (DDL_OFF)
#define DDL_SPI_ENABLE (DDL_ON)
#define DDL_SRAM_ENABLE (DDL_ON)
#define DDL_SWDT_ENABLE (DDL_OFF)
#define DDL_TMR0_ENABLE (DDL_OFF)
@ -134,7 +134,7 @@ extern "C"
#define BSP_OV5640_ENABLE (BSP_OFF)
#define BSP_S29GL064N90TFI03_ENABLE (BSP_OFF)
#define BSP_TCA9539_ENABLE (BSP_OFF)
#define BSP_W25QXX_ENABLE (BSP_ON)
#define BSP_W25QXX_ENABLE (BSP_OFF)
#define BSP_WM8731_ENABLE (BSP_OFF)
/**

View File

@ -83,20 +83,20 @@
/* The HC32 F4A0 have no CCM SRAM */
# if defined(CONFIG_HC32_HC32F4A0)
# if defined(CONFIG_HC32_HC32F4A0)
# undef CONFIG_HC32_CCMEXCLUDE
# define CONFIG_HC32_CCMEXCLUDE 1
# endif
/* Set the end of system SRAM */
#define SRAM1_END 0x20073880
#define SRAM1_END 0x1FFF0000
/* Set the range of CCM SRAM as well (although we may not use it) */
#define SRAM2_START 0x1FE00000
#define SRAM2_END 0x20073880
#define SRAM2_START 0x1FFF0000
#define SRAM2_END 0x20070000
/* There are 4 possible SRAM configurations:

View File

@ -37,6 +37,15 @@ extern "C"
#define HC32F4A0 1
#define USE_DDL_DRIVER 1
#ifdef CONFIG_FS_PROCFS
# ifdef CONFIG_NSH_PROC_MOUNTPOINT
# define HC32_PROCFS_MOUNTPOINT CONFIG_NSH_PROC_MOUNTPOINT
# else
# define HC32_PROCFS_MOUNTPOINT "/proc"
# endif
#endif
#define getreg32(a) (*(volatile uint32_t *)(a))
#define putreg32(v,a) (*(volatile uint32_t *)(a) = (v))
#define getreg16(a) (*(volatile uint16_t *)(a))

View File

@ -0,0 +1,46 @@
#include <nuttx/config.h>
#include <sys/types.h>
#include <stdint.h>
#include <string.h>
#include <stdio.h>
#include <stdbool.h>
#include <unistd.h>
#include <string.h>
#include <assert.h>
#include <errno.h>
#include <fcntl.h>
#include <debug.h>
#include <arch/board/board.h>
#include "chip.h"
#include "hc32_uart.h"
#include "hc32_spi.h"
void hc32_test_console(void)
{
char *dev_str = "/dev/console";
char *test_chr = "test";
int fd = 0, ret;
fd = open(dev_str, 0x6);
hc32_print("%s: open <%s> ret = %d\n", __func__, dev_str, fd);
ret = write(fd, test_chr, strlen(test_chr));
hc32_print("%s: open %d ret %d\n", __func__, fd, ret);
close(fd);
}
void hc32_console_handle(char *buf)
{
if(strncmp(buf, "console", 7) == 0)
{
hc32_test_console();
}
else if(strncmp(buf, "spi", 7) == 0)
{
hc32_print("start flash test ...\n");
hc32_spiflash_test();
}
}

View File

@ -0,0 +1,43 @@
#ifndef __HC32_CONSOLE_H_
#define __HC32_CONSOLE_H_
#include <nuttx/config.h>
#include <sys/types.h>
#include <stdint.h>
#include <string.h>
#include <stdio.h>
#include <stdbool.h>
#include <unistd.h>
#include <string.h>
#include <assert.h>
#include <errno.h>
#include <debug.h>
#include <nuttx/irq.h>
#include <nuttx/arch.h>
#include <nuttx/fs/ioctl.h>
#include <nuttx/serial/serial.h>
#include <nuttx/power/pm.h>
#ifdef CONFIG_SERIAL_TERMIOS
# include <termios.h>
#endif
#include <arch/board/board.h>
#include "chip.h"
#include "hc32_uart.h"
#include "hc32_rcc.h"
#include "hc32_gpio.h"
#include "arm_internal.h"
#include "hc32f4a0.h"
#include "hc32f4a0_usart.h"
#include "hc32f4a0_gpio.h"
#include "hc32f4a0_interrupts.h"
#include "hc32f4a0_sram.h"
#include "hc32f4a0_pwc.h"
#include "hc32f4a0_efm.h"
void hc32_console_handle(char *buf);
#endif

View File

@ -119,7 +119,7 @@ void hc32_gpioinit(void)
****************************************************************************/
/****************************************************************************
* Name: hc32_configgpio (for the HC32F10xxx family)
* Name: hc32_configgpio (for the HC32F4A0)
****************************************************************************/
int hc32_configgpio(uint32_t cfgset)

View File

@ -152,6 +152,12 @@ static void up_idlepm(void)
void up_idle(void)
{
#if defined (CONFIG_HC32F4A0_BOARD)
extern void hc32_uart_handle(void);
hc32_uart_handle();
#endif
#if defined(CONFIG_SUPPRESS_INTERRUPTS) || defined(CONFIG_SUPPRESS_TIMER_INTS)
/* If the system is idle and there are no timer interrupts, then process
* "fake" timer interrupts. Hopefully, something will wake up.

View File

@ -37,34 +37,12 @@
#include "hc32_lowputc.h"
#include "hc32f4a0_usart.h"
#include "hc32_ddl.h"
#include "hc32_uart.h"
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/* UART multiple processor ID definition */
#define UART_MASTER_STATION_ID (0x20U)
#define UART_SLAVE_STATION_ID (0x21U)
/* Ring buffer size */
#define IS_RING_BUFFER_EMPTY(x) (0U == ((x)->u16UsedSize))
/* Multi-processor silence mode */
#define LP_UART_NORMAL_MODE (0U)
#define LP_UART_SILENCE_MODE (1U)
/**
* @brief Ring buffer structure definition
*/
typedef struct
{
uint16_t u16Capacity;
__IO uint16_t u16UsedSize;
uint16_t u16InIdx;
uint16_t u16OutIdx;
uint8_t au8Buf[50];
} stc_ring_buffer_t;
/****************************************************************************
* Private Types
****************************************************************************/
@ -81,212 +59,10 @@ typedef struct
* Private Data
****************************************************************************/
static uint8_t m_u8UartSilenceMode = LP_UART_NORMAL_MODE;
static stc_ring_buffer_t m_stcRingBuf = {
.u16InIdx = 0U,
.u16OutIdx = 0U,
.u16UsedSize = 0U,
.u16Capacity = sizeof (m_stcRingBuf.au8Buf),
};
/****************************************************************************
* Private Functions
****************************************************************************/
/**
* @brief Set silence mode.
* @param [in] u8Mode Silence mode
* This parameter can be one of the following values:
* @arg LP_UART_SILENCE_MODE: UART silence mode
* @arg LP_UART_NORMAL_MODE: UART normal mode
* @retval None
*/
static void UsartSetSilenceMode(uint8_t u8Mode)
{
m_u8UartSilenceMode = u8Mode;
}
/**
* @brief Get silence mode.
* @param [in] None
* @retval Returned value can be one of the following values:
* @arg LP_UART_SILENCE_MODE: UART silence mode
* @arg LP_UART_NORMAL_MODE: UART normal mode
*/
static uint8_t UsartGetSilenceMode(void)
{
return m_u8UartSilenceMode;
}
/**
* @brief Instal IRQ handler.
* @param [in] pstcConfig Pointer to struct @ref stc_irq_signin_config_t
* @param [in] u32Priority Interrupt priority
* @retval None
*/
static void InstalIrqHandler(const stc_irq_signin_config_t *pstcConfig,
uint32_t u32Priority)
{
if (NULL != pstcConfig)
{
(void)INTC_IrqSignIn(pstcConfig);
NVIC_ClearPendingIRQ(pstcConfig->enIRQn);
NVIC_SetPriority(pstcConfig->enIRQn, u32Priority);
NVIC_EnableIRQ(pstcConfig->enIRQn);
}
}
/**
* @brief Write ring buffer.
* @param [in] pstcBuffer Pointer to a @ref stc_ring_buffer_t structure
* @param [in] pu8Data Pointer to data buffer to read
* @retval An en_result_t enumeration value:
* - Ok: Write success.
* - ErrorNotReady: Buffer is empty.
*/
static en_result_t RingBufRead(stc_ring_buffer_t *pstcBuffer, uint8_t *pu8Data)
{
en_result_t enRet = Ok;
if (pstcBuffer->u16UsedSize == 0U)
{
enRet = ErrorNotReady;
}
else
{
*pu8Data = pstcBuffer->au8Buf[pstcBuffer->u16OutIdx++];
pstcBuffer->u16OutIdx %= pstcBuffer->u16Capacity;
pstcBuffer->u16UsedSize--;
}
return enRet;
}
/**
* @brief UART TX Empty IRQ callback.
* @param None
* @retval None
*/
static void USART_TxEmpty_IrqCallback(void)
{
uint8_t u8Data = 0U;
en_flag_status_t enFlag = USART_GetStatus(LP_UNIT, USART_FLAG_TXE);
en_functional_state_t enState = USART_GetFuncState(LP_UNIT, USART_INT_TXE);
if ((Set == enFlag) && (Enable == enState))
{
USART_SendId(LP_UNIT, UART_SLAVE_STATION_ID);
while (Reset == USART_GetStatus(LP_UNIT, USART_FLAG_TC)) /* Wait Tx data register empty */
{
}
if (Ok == RingBufRead(&m_stcRingBuf, &u8Data))
{
USART_SendData(LP_UNIT, (uint16_t)u8Data);
}
if (IS_RING_BUFFER_EMPTY(&m_stcRingBuf))
{
USART_FuncCmd(LP_UNIT, USART_INT_TXE, Disable);
USART_FuncCmd(LP_UNIT, USART_INT_TC, Enable);
}
}
}
/**
* @brief UART TX Complete IRQ callback.
* @param None
* @retval None
*/
static void USART_TxComplete_IrqCallback(void)
{
en_flag_status_t enFlag = USART_GetStatus(LP_UNIT, USART_FLAG_TC);
en_functional_state_t enState = USART_GetFuncState(LP_UNIT, USART_INT_TC);
if ((Set == enFlag) && (Enable == enState))
{
/* Disable TX function */
USART_FuncCmd(LP_UNIT, (USART_TX | USART_RX | USART_INT_TC), Disable);
/* Enable RX function */
USART_FuncCmd(LP_UNIT, (USART_RX | USART_INT_RX), Enable);
}
}
/**
* @brief Write ring buffer.
* @param [in] pstcBuffer Pointer to a @ref stc_ring_buffer_t structure
* @param [in] u8Data Data to write
* @retval An en_result_t enumeration value:
* - Ok: Write success.
* - ErrorBufferFull: Buffer is full.
*/
static en_result_t write_ring_buf(stc_ring_buffer_t *pstcBuffer, uint8_t u8Data)
{
en_result_t enRet = Ok;
if (pstcBuffer->u16UsedSize >= pstcBuffer->u16Capacity)
{
enRet = ErrorBufferFull;
}
else
{
pstcBuffer->au8Buf[pstcBuffer->u16InIdx++] = u8Data;
pstcBuffer->u16InIdx %= pstcBuffer->u16Capacity;
pstcBuffer->u16UsedSize++;
}
return enRet;
}
/**
* @brief UART RX IRQ callback.
* @param None
* @retval None
*/
static void USART_Rx_IrqCallback(void)
{
uint8_t u8RxData;
en_flag_status_t enFlag = USART_GetStatus(LP_UNIT, USART_FLAG_RXNE);
en_functional_state_t enState = USART_GetFuncState(LP_UNIT, USART_INT_RX);
if ((Set == enFlag) && (Enable == enState))
{
u8RxData = (uint8_t)USART_RecData(LP_UNIT);
if ((Reset == USART_GetStatus(LP_UNIT, USART_FLAG_MPB)) &&
(LP_UART_NORMAL_MODE == UsartGetSilenceMode()))
{
write_ring_buf(&m_stcRingBuf, u8RxData);
}
else
{
if (UART_MASTER_STATION_ID != u8RxData)
{
USART_SilenceCmd(LP_UNIT, Enable);
UsartSetSilenceMode(LP_UART_SILENCE_MODE);
}
else
{
UsartSetSilenceMode(LP_UART_NORMAL_MODE);
}
}
}
}
/**
* @brief UART RX Error IRQ callback.
* @param None
* @retval None
*/
static void USART_RxErr_IrqCallback(void)
{
USART_ClearStatus(LP_UNIT, (USART_CLEAR_FLAG_FE | USART_CLEAR_FLAG_PE | USART_CLEAR_FLAG_ORE));
}
void hc32_unlock(void)
{
/* Unlock GPIO register: PSPCR, PCCR, PINAER, PCRxy, PFSRxy */
@ -342,30 +118,19 @@ void hc32_print_portinit(void)
void arm_lowputc(char ch)
{
while(Set != USART_GetStatus(LP_UNIT, USART_FLAG_TXE));
USART_SendData(LP_UNIT, ch);
while(Set != USART_GetStatus(DBG_UNIT, USART_FLAG_TXE));
USART_SendData(DBG_UNIT, ch);
}
/****************************************************************************
* Name: hc32_lowsetup
*
* Description:
* This performs basic initialization of the USART used for the serial
* console. Its purpose is to get the console output available as soon
* as possible.
*
****************************************************************************/
void hc32_lowsetup(void)
{
stc_irq_signin_config_t stcIrqSigninCfg;
const stc_usart_multiprocessor_init_t stcUartMultiProcessorInit = {
.u32Baudrate = 115200UL,
const stc_usart_uart_init_t stcUartInit = {
.u32Baudrate = BSP_PRINTF_BAUDRATE,
.u32BitDirection = USART_LSB,
.u32StopBit = USART_STOPBIT_1BIT,
.u32Parity = USART_PARITY_NONE,
.u32DataWidth = USART_DATA_LENGTH_8BIT,
.u32ClkMode = USART_INTERNCLK_NONE_OUTPUT,
.u32ClkMode = USART_INTERNCLK_OUTPUT,
.u32PclkDiv = USART_PCLK_DIV64,
.u32OversamplingBits = USART_OVERSAMPLING_8BIT,
.u32NoiseFilterState = USART_NOISE_FILTER_DISABLE,
@ -380,42 +145,18 @@ void hc32_lowsetup(void)
DDL_PrintfInit(BSP_PRINTF_DEVICE, BSP_PRINTF_BAUDRATE, hc32_print_portinit);
/* Configure USART RX/TX pin. */
GPIO_SetFunc(LP_RX_PORT, LP_RX_PIN, LP_RX_GPIO_FUNC, PIN_SUBFUNC_DISABLE);
GPIO_SetFunc(LP_TX_PORT, LP_TX_PIN, LP_TX_GPIO_FUNC, PIN_SUBFUNC_DISABLE);
GPIO_SetFunc(DBG_RX_PORT, DBG_RX_PIN, DBG_RX_GPIO_FUNC, PIN_SUBFUNC_DISABLE);
GPIO_SetFunc(DBG_TX_PORT, DBG_TX_PIN, DBG_TX_GPIO_FUNC, PIN_SUBFUNC_DISABLE);
hc32_lock();
/* Enable peripheral clock */
PWC_Fcg3PeriphClockCmd(LP_FUNCTION_CLK_GATE, Enable);
/* Set silence mode */
UsartSetSilenceMode(LP_UART_SILENCE_MODE);
PWC_Fcg3PeriphClockCmd(DBG_FUNCTION_CLK_GATE, Enable);
/* Initialize UART function. */
(void)USART_MultiProcessorInit(LP_UNIT, &stcUartMultiProcessorInit);
/* Register error IRQ handler && configure NVIC. */
stcIrqSigninCfg.enIRQn = LP_UNIT_ERR_INT_IRQn;
stcIrqSigninCfg.enIntSrc = LP_UNIT_ERR_INT_SRC;
stcIrqSigninCfg.pfnCallback = &USART_RxErr_IrqCallback;
InstalIrqHandler(&stcIrqSigninCfg, DDL_IRQ_PRIORITY_DEFAULT);
/* Register RX IRQ handler && configure NVIC. */
stcIrqSigninCfg.enIRQn = LP_UNIT_RX_INT_IRQn;
stcIrqSigninCfg.enIntSrc = LP_UNIT_RX_INT_SRC;
stcIrqSigninCfg.pfnCallback = &USART_Rx_IrqCallback;
InstalIrqHandler(&stcIrqSigninCfg, DDL_IRQ_PRIORITY_00);
/* Register TX IRQ handler && configure NVIC. */
stcIrqSigninCfg.enIRQn = LP_UNIT_TX_INT_IRQn;
stcIrqSigninCfg.enIntSrc = LP_UNIT_TX_INT_SRC;
stcIrqSigninCfg.pfnCallback = &USART_TxEmpty_IrqCallback;
InstalIrqHandler(&stcIrqSigninCfg, DDL_IRQ_PRIORITY_DEFAULT);
/* Register TC IRQ handler && configure NVIC. */
stcIrqSigninCfg.enIRQn = LP_UNIT_TCI_INT_IRQn;
stcIrqSigninCfg.enIntSrc = LP_UNIT_TCI_INT_SRC;
stcIrqSigninCfg.pfnCallback = &USART_TxComplete_IrqCallback;
InstalIrqHandler(&stcIrqSigninCfg, DDL_IRQ_PRIORITY_DEFAULT);
if (Ok != USART_UartInit(DBG_UNIT, &stcUartInit))
{
for (;;);
}
}

View File

@ -0,0 +1,189 @@
/**
*******************************************************************************
* @file arch/arm/src/hc32/hc32_spi.c
* @brief SPI write read flash API for the Device Driver Library.
@verbatim
Change Logs:
Date Author Notes
2020-06-12 Wangmin First version
2020-10-13 Wangmin Modify spelling mistake
@endverbatim
*******************************************************************************
* Copyright (C) 2020, Huada Semiconductor Co., Ltd. All rights reserved.
*
* This software component is licensed by HDSC 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
*
*******************************************************************************
*/
/*******************************************************************************
* Include files
******************************************************************************/
#include "hc32_ddl.h"
#include "hc32_spi.h"
/*******************************************************************************
* Local type definitions ('typedef')
******************************************************************************/
/*******************************************************************************
* Local pre-processor symbols/macros ('#define')
******************************************************************************/
/*******************************************************************************
* Global variable definitions (declared in header file with 'extern')
******************************************************************************/
/*******************************************************************************
* Local function prototypes ('static')
******************************************************************************/
/*******************************************************************************
* Local variable definitions ('static')
******************************************************************************/
/*******************************************************************************
* Function implementation - global ('extern') and local ('static')
******************************************************************************/
/**
* @brief MCU Peripheral registers write unprotected.
* @param None
* @retval None
* @note Comment/uncomment each API depending on APP requires.
*/
static void Peripheral_WE(void)
{
/* Unlock GPIO register: PSPCR, PCCR, PINAER, PCRxy, PFSRxy */
GPIO_Unlock();
/* Unlock PWC register: FCG0 */
PWC_FCG0_Unlock();
/* Unlock PWC, CLK, PVD registers, @ref PWC_REG_Write_Unlock_Code for details */
PWC_Unlock(PWC_UNLOCK_CODE_0 | PWC_UNLOCK_CODE_1 | PWC_UNLOCK_CODE_2);
/* Unlock SRAM register: WTCR */
SRAM_WTCR_Unlock();
/* Unlock SRAM register: CKCR */
//SRAM_CKCR_Unlock();
/* Unlock all EFM registers */
EFM_Unlock();
/* Unlock EFM register: FWMC */
//EFM_FWMC_Unlock();
/* Unlock EFM OTP write protect registers */
//EFM_OTP_WP_Unlock();
/* Unlock all MPU registers */
// MPU_Unlock();
}
/**
* @brief MCU Peripheral registers write protected.
* @param None
* @retval None
* @note Comment/uncomment each API depending on APP requires.
*/
static __attribute__((unused)) void Peripheral_WP(void)
{
/* Lock GPIO register: PSPCR, PCCR, PINAER, PCRxy, PFSRxy */
GPIO_Lock();
/* Lock PWC register: FCG0 */
PWC_FCG0_Lock();
/* Lock PWC, CLK, PVD registers, @ref PWC_REG_Write_Unlock_Code for details */
PWC_Lock(PWC_UNLOCK_CODE_0 | PWC_UNLOCK_CODE_1 | PWC_UNLOCK_CODE_2);
/* Lock SRAM register: WTCR */
SRAM_WTCR_Lock();
/* Lock SRAM register: CKCR */
//SRAM_CKCR_Lock();
/* Lock EFM OTP write protect registers */
//EFM_OTP_WP_Lock();
/* Lock EFM register: FWMC */
//EFM_FWMC_Lock();
/* Lock all EFM registers */
EFM_Lock();
/* Lock all MPU registers */
// MPU_Lock();
}
/**
* @brief Configure SPI peripheral function
*
* @param [in] None
*
* @retval None
*/
static void Spi_Config(void)
{
stc_spi_init_t stcSpiInit;
stc_spi_delay_t stcSpiDelayCfg;
/* Clear initialize structure */
(void)SPI_StructInit(&stcSpiInit);
(void)SPI_DelayStructInit(&stcSpiDelayCfg);
/* Configure peripheral clock */
PWC_Fcg1PeriphClockCmd(SPI_UNIT_CLOCK, Enable);
/* SPI De-initialize */
SPI_DeInit(SPI_UNIT);
/* Configuration SPI structure */
stcSpiInit.u32WireMode = SPI_WIRE_3;
stcSpiInit.u32TransMode = SPI_FULL_DUPLEX;
stcSpiInit.u32MasterSlave = SPI_MASTER;
stcSpiInit.u32SuspMode = SPI_COM_SUSP_FUNC_OFF;
stcSpiInit.u32Modfe = SPI_MODFE_DISABLE;
stcSpiInit.u32Parity = SPI_PARITY_INVALID;
stcSpiInit.u32SpiMode = SPI_MODE_0;
stcSpiInit.u32BaudRatePrescaler = SPI_BR_PCLK1_DIV256;
stcSpiInit.u32DataBits = SPI_DATA_SIZE_8BIT;
stcSpiInit.u32FirstBit = SPI_FIRST_MSB;
(void)SPI_Init(SPI_UNIT, &stcSpiInit);
stcSpiDelayCfg.u32IntervalDelay = SPI_INTERVAL_TIME_8SCK_2PCLK1;
stcSpiDelayCfg.u32ReleaseDelay = SPI_RELEASE_TIME_8SCK;
stcSpiDelayCfg.u32SetupDelay = SPI_SETUP_TIME_1SCK;
(void)SPI_DelayTimeCfg(SPI_UNIT, &stcSpiDelayCfg);
SPI_FunctionCmd(SPI_UNIT, Enable);
}
int hc32_spi_init(void)
{
stc_gpio_init_t stcGpioCfg;
Peripheral_WE();
/* Port configurate */
(void)GPIO_StructInit(&stcGpioCfg);
/* High driving capacity for output pin. */
stcGpioCfg.u16PinDir = PIN_DIR_OUT;
stcGpioCfg.u16PinDrv = PIN_DRV_HIGH;
stcGpioCfg.u16PinState = PIN_STATE_SET;
(void)GPIO_Init(SPI_NSS_PORT, SPI_NSS_PIN, &stcGpioCfg);
(void)GPIO_StructInit(&stcGpioCfg);
stcGpioCfg.u16PinDrv = PIN_DRV_HIGH;
(void)GPIO_Init(SPI_SCK_PORT, SPI_SCK_PIN, &stcGpioCfg);
(void)GPIO_Init(SPI_MOSI_PORT, SPI_MOSI_PIN, &stcGpioCfg);
/* CMOS input for input pin */
stcGpioCfg.u16PinDrv = PIN_DRV_LOW;
stcGpioCfg.u16PinIType = PIN_ITYPE_CMOS;
(void)GPIO_Init(SPI_MISO_PORT, SPI_MISO_PIN, &stcGpioCfg);
/* Configure SPI Port function for master */
GPIO_SetFunc(SPI_SCK_PORT, SPI_SCK_PIN, SPI_SCK_FUNC, PIN_SUBFUNC_DISABLE);
GPIO_SetFunc(SPI_MOSI_PORT, SPI_MOSI_PIN, SPI_MOSI_FUNC, PIN_SUBFUNC_DISABLE);
GPIO_SetFunc(SPI_MISO_PORT, SPI_MISO_PIN, SPI_MISO_FUNC, PIN_SUBFUNC_DISABLE);
/* Configure SPI for SPI flash */
Spi_Config();
Peripheral_WP();
return OK;
}

View File

@ -0,0 +1,77 @@
/**
*******************************************************************************
* @file arch/arm/src/hc32/hc32_spi.h
* @brief SPI write read flash API for the Device Driver Library.
@verbatim
Change Logs:
Date Author Notes
2020-06-12 Wangmin First version
2020-10-13 Wangmin Modify spelling mistake
@endverbatim
*******************************************************************************
* Copyright (C) 2020, Huada Semiconductor Co., Ltd. All rights reserved.
*
* This software component is licensed by HDSC 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
*
*******************************************************************************
*/
/*******************************************************************************
* Include files
******************************************************************************/
#include "hc32_ddl.h"
/*******************************************************************************
* Local type definitions ('typedef')
******************************************************************************/
/*******************************************************************************
* Local pre-processor symbols/macros ('#define')
******************************************************************************/
/* SPI unit and clock definition */
#define SPI_UNIT (M4_SPI1)
#define SPI_UNIT_CLOCK (PWC_FCG1_SPI1)
/* SPI port definition for master */
#define SPI_NSS_PORT (GPIO_PORT_C)
#define SPI_NSS_PIN (GPIO_PIN_07)
#define SPI_SCK_PORT (GPIO_PORT_C)
#define SPI_SCK_PIN (GPIO_PIN_06)
#define SPI_SCK_FUNC (GPIO_FUNC_40_SPI1_SCK)
#define SPI_MOSI_PORT (GPIO_PORT_D)
#define SPI_MOSI_PIN (GPIO_PIN_08)
#define SPI_MOSI_FUNC (GPIO_FUNC_41_SPI1_MOSI)
#define SPI_MISO_PORT (GPIO_PORT_D)
#define SPI_MISO_PIN (GPIO_PIN_09)
#define SPI_MISO_FUNC (GPIO_FUNC_42_SPI1_MISO)
/* NSS pin control */
#define SPI_NSS_HIGH() (GPIO_SetPins(SPI_NSS_PORT, SPI_NSS_PIN))
#define SPI_NSS_LOW() (GPIO_ResetPins(SPI_NSS_PORT, SPI_NSS_PIN))
/*******************************************************************************
* Global variable definitions (declared in header file with 'extern')
******************************************************************************/
/*******************************************************************************
* Local function prototypes ('static')
******************************************************************************/
/*******************************************************************************
* Local variable definitions ('static')
******************************************************************************/
/*******************************************************************************
* Function implementation - global ('extern') and local ('static')
******************************************************************************/
int hc32_spi_init(void);
void hc32_spiflash_test(void);

View File

@ -0,0 +1,350 @@
/**
*******************************************************************************
* @file arch/arm/src/hc32/hc32_spiflash.c
* @brief SPI write read flash API for the Device Driver Library.
@verbatim
Change Logs:
Date Author Notes
2020-06-12 Wangmin First version
2020-10-13 Wangmin Modify spelling mistake
@endverbatim
*******************************************************************************
* Copyright (C) 2020, Huada Semiconductor Co., Ltd. All rights reserved.
*
* This software component is licensed by HDSC 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
*
*******************************************************************************
*/
/*******************************************************************************
* Include files
******************************************************************************/
#include "hc32_ddl.h"
#include "hc32_spi.h"
#include "hc32_uart.h"
/*******************************************************************************
* Local type definitions ('typedef')
******************************************************************************/
/*******************************************************************************
* Local pre-processor symbols/macros ('#define')
******************************************************************************/
/* FLASH parameters */
#define FLASH_PAGE_SIZE (0x100U)
#define FLASH_SECTOR_SIZE (0x1000U)
#define FLASH_MAX_ADDR (0x800000UL)
#define FLASH_DUMMY_BYTE_VALUE (0xffU)
#define FLASH_BUSY_BIT_MASK (0x01U)
/* FLASH instruction */
#define FLASH_INSTR_WRITE_ENABLE (0x06U)
#define FLASH_INSTR_PAGE_PROGRAM (0x02U)
#define FLASH_INSTR_STANDARD_READ (0x03U)
#define FLASH_INSTR_ERASE_4KB_SECTOR (0x20U)
#define FLASH_INSTR_READ_SR1 (0x05U)
#define FLASH_READ_MANUFACTURER_ID (0x90U)
/*******************************************************************************
* Global variable definitions (declared in header file with 'extern')
******************************************************************************/
/*******************************************************************************
* Local function prototypes ('static')
******************************************************************************/
/*******************************************************************************
* Local variable definitions ('static')
******************************************************************************/
/*******************************************************************************
* Function implementation - global ('extern') and local ('static')
******************************************************************************/
/**
* @brief SPI flash write byte function
*
* @param [in] u8Data SPI write data to flash
*
* @retval uint8_t SPI receive data from flash
*/
static uint8_t SpiFlash_WriteReadByte(uint8_t u8Data)
{
uint8_t u8Byte;
/* Wait tx buffer empty */
while (Reset == SPI_GetStatus(SPI_UNIT, SPI_FLAG_TX_BUFFER_EMPTY))
{
}
/* Send data */
SPI_WriteDataReg(SPI_UNIT, (uint32_t)u8Data);
/* Wait rx buffer full */
while (Reset == SPI_GetStatus(SPI_UNIT, SPI_FLAG_RX_BUFFER_FULL))
{
}
/* Receive data */
u8Byte = (uint8_t)SPI_ReadDataReg(SPI_UNIT);
return u8Byte;
}
/**
* @brief SPI flash write enable function
*
* @param [in] None
*
* @retval None
*/
static void SpiFlash_WriteEnable(void)
{
SPI_NSS_LOW();
(void)SpiFlash_WriteReadByte(FLASH_INSTR_WRITE_ENABLE);
SPI_NSS_HIGH();
}
/**
* @brief SPI flash wait for write operation end function
*
* @param [in] None
*
* @retval Ok Flash internal operation finish
* @retval ErrorTimeout Flash internal operation timeout
*/
static en_result_t SpiFlash_WaitForWriteEnd(void)
{
en_result_t enRet = Ok;
uint8_t u8Status;
uint32_t u32Timeout;
stc_clk_freq_t stcClkFreq;
(void)CLK_GetClockFreq(&stcClkFreq);
u32Timeout = stcClkFreq.sysclkFreq / 1000U;
SPI_NSS_LOW();
(void)SpiFlash_WriteReadByte(FLASH_INSTR_READ_SR1);
do
{
u8Status = SpiFlash_WriteReadByte(FLASH_DUMMY_BYTE_VALUE);
u32Timeout--;
} while ((u32Timeout != 0UL) &&
((u8Status & FLASH_BUSY_BIT_MASK) == FLASH_BUSY_BIT_MASK));
if (FLASH_BUSY_BIT_MASK == u8Status)
{
enRet = ErrorTimeout;
}
SPI_NSS_HIGH();
return enRet;
}
/**
* @brief SPI flash page write program function
*
* @param [in] u32Addr Valid flash address
* @param [in] pData Pointer to send data buffer
* @param [in] len Send data length
*
* @retval Error Page write program failed
* @retval Ok Page write program success
*/
static en_result_t SpiFlash_WritePage(uint32_t u32Addr, const uint8_t pData[], uint16_t len)
{
en_result_t enRet;
uint16_t u16Index = 0U;
if ((u32Addr > FLASH_MAX_ADDR) || (NULL == pData) || (len > FLASH_PAGE_SIZE))
{
enRet = Error;
}
else
{
SpiFlash_WriteEnable();
/* Send data to flash */
SPI_NSS_LOW();
(void)SpiFlash_WriteReadByte(FLASH_INSTR_PAGE_PROGRAM);
(void)SpiFlash_WriteReadByte((uint8_t)((u32Addr & 0xFF0000UL) >> 16U));
(void)SpiFlash_WriteReadByte((uint8_t)((u32Addr & 0xFF00U) >> 8U));
(void)SpiFlash_WriteReadByte((uint8_t)(u32Addr & 0xFFU));
while (0U != (len--))
{
(void)SpiFlash_WriteReadByte(pData[u16Index]);
u16Index++;
}
SPI_NSS_HIGH();
/* Wait for flash idle */
enRet = SpiFlash_WaitForWriteEnd();
}
return enRet;
}
/**
* @brief SPI flash read data function
*
* @param [in] u32Addr Valid flash address
* @param [out] pData Pointer to receive data buffer
*
* @param [in] len Read data length
*
* @retval Error Read data program failed
* @retval Ok Read data program success
*/
static en_result_t SpiFlash_ReadData(uint32_t u32Addr, uint8_t pData[], uint16_t len)
{
en_result_t enRet = Ok;
uint16_t u16Index = 0U;
if ((u32Addr > FLASH_MAX_ADDR) || (NULL == pData))
{
enRet = Error;
}
else
{
SpiFlash_WriteEnable();
/* Send data to flash */
SPI_NSS_LOW();
(void)SpiFlash_WriteReadByte(FLASH_INSTR_STANDARD_READ);
(void)SpiFlash_WriteReadByte((uint8_t)((u32Addr & 0xFF0000UL) >> 16U));
(void)SpiFlash_WriteReadByte((uint8_t)((u32Addr & 0xFF00U) >> 8U));
(void)SpiFlash_WriteReadByte((uint8_t)(u32Addr & 0xFFU));
while (0U != (len--))
{
pData[u16Index] = SpiFlash_WriteReadByte(FLASH_DUMMY_BYTE_VALUE);
u16Index++;
}
SPI_NSS_HIGH();
}
return enRet;
}
/**
* @brief SPI flash read ID for test
*
* @param [in] None
*
* @retval uint8_t Flash ID
*/
static uint8_t SpiFlash_ReadID(void)
{
uint8_t u8IdRead;
SPI_NSS_LOW();
(void)SpiFlash_WriteReadByte(FLASH_READ_MANUFACTURER_ID);
(void)SpiFlash_WriteReadByte((uint8_t)0x00U);
(void)SpiFlash_WriteReadByte((uint8_t)0x00U);
(void)SpiFlash_WriteReadByte((uint8_t)0x00U);
u8IdRead = SpiFlash_WriteReadByte(FLASH_DUMMY_BYTE_VALUE);
SPI_NSS_HIGH();
return u8IdRead;
}
/**
* @brief SPI flash erase 4Kb sector function
*
* @param [in] u32Addr Valid flash address
*
* @retval Error Sector erase failed
* @retval Ok Sector erase success
*/
static en_result_t SpiFlash_Erase4KbSector(uint32_t u32Addr)
{
en_result_t enRet;
if (u32Addr >= FLASH_MAX_ADDR)
{
enRet = Error;
}
else
{
SpiFlash_WriteEnable();
/* Send instruction to flash */
SPI_NSS_LOW();
(void)SpiFlash_WriteReadByte(FLASH_INSTR_ERASE_4KB_SECTOR);
(void)SpiFlash_WriteReadByte((uint8_t)((u32Addr & 0xFF0000UL) >> 16U));
(void)SpiFlash_WriteReadByte((uint8_t)((u32Addr & 0xFF00U) >> 8U));
(void)SpiFlash_WriteReadByte((uint8_t)(u32Addr & 0xFFU));
//SPI_GetStatus(const M4_SPI_TypeDef *SPIx, uint32_t u32Flag) //todo
SPI_NSS_HIGH();
/* Wait for flash idle */
enRet = SpiFlash_WaitForWriteEnd();
}
return enRet;
}
/**
* @brief Main function of spi_master_base project
* @param None
* @retval int32_t return value, if needed
*/
void hc32_spiflash_test(void)
{
uint32_t flashAddr = 0UL;
uint16_t bufferLen;
char txBuffer[] = "SPI read and write flash example: Welcome to use HDSC micro chip";
char rxBuffer[128];
uint8_t flash_id = 0;
hc32_spi_init();
/* Get tx buffer length */
bufferLen = (uint16_t)sizeof(txBuffer);
flash_id = SpiFlash_ReadID();
hc32_print("SPI Flash id: %#x\n", flash_id);
(void)memset(rxBuffer, 0L, sizeof(rxBuffer));
/* Erase sector */
(void)SpiFlash_Erase4KbSector(flashAddr);
/* Write data to flash */
(void)SpiFlash_WritePage(flashAddr, (uint8_t*)&txBuffer[0], bufferLen);
/* Read data from flash */
(void)SpiFlash_ReadData(flashAddr, (uint8_t*)&rxBuffer[0], bufferLen);
/* Compare txBuffer and rxBuffer */
if (memcmp(txBuffer, rxBuffer, (uint32_t)bufferLen) != 0)
{
hc32_print("spi failed!!!\n");
}
else
{
hc32_print("spi ok!!!\n");
}
/* Flash address offset */
flashAddr += FLASH_SECTOR_SIZE;
if (flashAddr >= FLASH_MAX_ADDR)
{
flashAddr = 0U;
}
}
int hc32_spidev_initialized = 1;
void hc32_spidev_initialize(void)
{
hc32_spi_init();
hc32_spidev_initialized = 0;
}
/**
* @}
*/
/**
* @}
*/
/*******************************************************************************
* EOF (not truncated)
******************************************************************************/

View File

@ -27,7 +27,6 @@
#include <nuttx/config.h>
#include <nuttx/serial/serial.h>
#include "chip.h"
#define CONSOLE_UART 6
@ -43,9 +42,35 @@
* Pre-processor Definitions
****************************************************************************/
/* Make sure that we have not enabled more U[S]ARTs than are supported by the
* device.
typedef enum en_uart_state
{
UART_STATE_IDLE = 0U, /*!< No data */
UART_STATE_RXEND = 1U, /*!< UART RX End */
} uart_state_t;
/**
* @brief Ring buffer structure definition
*/
typedef struct
{
uint16_t u16Capacity;
volatile uint16_t u16UsedSize;
uint16_t u16InIdx;
uint16_t u16OutIdx;
uint8_t au8Buf[50];
} uart_ring_buffer_t;
/* UART multiple processor ID definition */
#define UART_MASTER_STATION_ID (0x20U)
#define UART_SLAVE_STATION_ID (0x21U)
/* Ring buffer size */
#define IS_RING_BUFFER_EMPTY(x) (0U == ((x)->u16UsedSize))
/* Multi-processor silence mode */
#define DBG_UART_NORMAL_MODE (0U)
#define DBG_UART_SILENCE_MODE (1U)
/****************************************************************************
* Public Types
@ -80,7 +105,9 @@ extern "C"
FAR uart_dev_t *hc32_serial_get_uart(int uart_num);
void hc32_print(const char *fmt, ...);
int hc32_print(const char *fmt, ...);
void hc32_console_handle(char *buf);
#undef EXTERN
#if defined(__cplusplus)

View File

@ -0,0 +1,266 @@
/****************************************************************************
* arch/arm/src/armv7-m/arm_vectors.c
*
* Copyright (C) 2012 Michael Smith. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions 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 NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER 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.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include "chip.h"
#include "arm_internal.h"
#include "hc32f4a0_interrupts.h"
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
#define IDLE_STACK ((unsigned)&_ebss+CONFIG_IDLETHREAD_STACKSIZE)
#ifndef ARMV7M_PERIPHERAL_INTERRUPTS
# error ARMV7M_PERIPHERAL_INTERRUPTS must be defined to the number of I/O interrupts to be supported
#endif
/****************************************************************************
* Public Functions
****************************************************************************/
/* Chip-specific entrypoint */
extern void __start(void);
/* Common exception entrypoint */
extern void exception_common(void);
/****************************************************************************
* Public data
****************************************************************************/
/* The v7m vector table consists of an array of function pointers, with the
* first slot (vector zero) used to hold the initial stack pointer.
*
* As all exceptions (interrupts) are routed via exception_common, we just
* need to fill this array with pointers to it.
*
* Note that the [ ... ] designated initializer is a GCC extension.
*/
#if 0
unsigned _vectors[] locate_data(".vectors") =
{
/* Initial stack */
IDLE_STACK,
/* Reset exception handler */
(unsigned)&__start,
/* Vectors 2 - n point directly at the generic handler */
[2 ... (15 + ARMV7M_PERIPHERAL_INTERRUPTS)] = (unsigned)&exception_common
};
#else
unsigned _vectors[] locate_data(".vectors") =
{
/* Initial stack */
IDLE_STACK,
/* Reset exception handler */
(unsigned)&__start,
(unsigned)&NMI_Handler,
(unsigned)&HardFault_Handler,
(unsigned)&MemManage_Handler,
(unsigned)&BusFault_Handler,
(unsigned)&UsageFault_Handler,
(unsigned)&exception_common,
(unsigned)&exception_common,
(unsigned)&exception_common,
(unsigned)&exception_common,
(unsigned)&SVC_Handler, /* SVC */
(unsigned)&DebugMon_Handler, /* DebugMon */
(unsigned)&exception_common,
(unsigned)&PendSV_Handler,
(unsigned)&SysTick_Handler, /* SysTick */
(unsigned)&IRQ000_Handler,
(unsigned)&IRQ001_Handler,
(unsigned)&IRQ002_Handler,
(unsigned)&IRQ003_Handler,
(unsigned)&IRQ004_Handler,
(unsigned)&IRQ005_Handler,
(unsigned)&IRQ006_Handler,
(unsigned)&IRQ007_Handler,
(unsigned)&IRQ008_Handler,
(unsigned)&IRQ009_Handler,
(unsigned)&IRQ010_Handler,
(unsigned)&IRQ011_Handler,
(unsigned)&IRQ012_Handler,
(unsigned)&IRQ013_Handler,
(unsigned)&IRQ014_Handler,
(unsigned)&IRQ015_Handler,
(unsigned)&IRQ016_Handler,
(unsigned)&IRQ017_Handler,
(unsigned)&IRQ018_Handler,
(unsigned)&IRQ019_Handler,
(unsigned)&IRQ020_Handler,
(unsigned)&IRQ021_Handler,
(unsigned)&IRQ022_Handler,
(unsigned)&IRQ023_Handler,
(unsigned)&IRQ024_Handler,
(unsigned)&IRQ025_Handler,
(unsigned)&IRQ026_Handler,
(unsigned)&IRQ027_Handler,
(unsigned)&IRQ028_Handler,
(unsigned)&IRQ029_Handler,
(unsigned)&IRQ030_Handler,
(unsigned)&IRQ031_Handler,
(unsigned)&IRQ032_Handler,
(unsigned)&IRQ033_Handler,
(unsigned)&IRQ034_Handler,
(unsigned)&IRQ035_Handler,
(unsigned)&IRQ036_Handler,
(unsigned)&IRQ037_Handler,
(unsigned)&IRQ038_Handler,
(unsigned)&IRQ039_Handler,
(unsigned)&IRQ040_Handler,
(unsigned)&IRQ041_Handler,
(unsigned)&IRQ042_Handler,
(unsigned)&IRQ043_Handler,
(unsigned)&IRQ044_Handler,
(unsigned)&IRQ045_Handler,
(unsigned)&IRQ046_Handler,
(unsigned)&IRQ047_Handler,
(unsigned)&IRQ048_Handler,
(unsigned)&IRQ049_Handler,
(unsigned)&IRQ050_Handler,
(unsigned)&IRQ051_Handler,
(unsigned)&IRQ052_Handler,
(unsigned)&IRQ053_Handler,
(unsigned)&IRQ054_Handler,
(unsigned)&IRQ055_Handler,
(unsigned)&IRQ056_Handler,
(unsigned)&IRQ057_Handler,
(unsigned)&IRQ058_Handler,
(unsigned)&IRQ059_Handler,
(unsigned)&IRQ060_Handler,
(unsigned)&IRQ061_Handler,
(unsigned)&IRQ062_Handler,
(unsigned)&IRQ063_Handler,
(unsigned)&IRQ064_Handler,
(unsigned)&IRQ065_Handler,
(unsigned)&IRQ066_Handler,
(unsigned)&IRQ067_Handler,
(unsigned)&IRQ068_Handler,
(unsigned)&IRQ069_Handler,
(unsigned)&IRQ070_Handler,
(unsigned)&IRQ071_Handler,
(unsigned)&IRQ072_Handler,
(unsigned)&IRQ073_Handler,
(unsigned)&IRQ074_Handler,
(unsigned)&IRQ075_Handler,
(unsigned)&IRQ076_Handler,
(unsigned)&IRQ077_Handler,
(unsigned)&IRQ078_Handler,
(unsigned)&IRQ079_Handler,
(unsigned)&IRQ080_Handler,
(unsigned)&IRQ081_Handler,
(unsigned)&IRQ082_Handler,
(unsigned)&IRQ083_Handler,
(unsigned)&IRQ084_Handler,
(unsigned)&IRQ085_Handler,
(unsigned)&IRQ086_Handler,
(unsigned)&IRQ087_Handler,
(unsigned)&IRQ088_Handler,
(unsigned)&IRQ089_Handler,
(unsigned)&IRQ090_Handler,
(unsigned)&IRQ091_Handler,
(unsigned)&IRQ092_Handler,
(unsigned)&IRQ093_Handler,
(unsigned)&IRQ094_Handler,
(unsigned)&IRQ095_Handler,
(unsigned)&IRQ096_Handler,
(unsigned)&IRQ097_Handler,
(unsigned)&IRQ098_Handler,
(unsigned)&IRQ099_Handler,
(unsigned)&IRQ100_Handler,
(unsigned)&IRQ101_Handler,
(unsigned)&IRQ102_Handler,
(unsigned)&IRQ103_Handler,
(unsigned)&IRQ104_Handler,
(unsigned)&IRQ105_Handler,
(unsigned)&IRQ106_Handler,
(unsigned)&IRQ107_Handler,
(unsigned)&IRQ108_Handler,
(unsigned)&IRQ109_Handler,
(unsigned)&IRQ110_Handler,
(unsigned)&IRQ111_Handler,
(unsigned)&IRQ112_Handler,
(unsigned)&IRQ113_Handler,
(unsigned)&IRQ114_Handler,
(unsigned)&IRQ115_Handler,
(unsigned)&IRQ116_Handler,
(unsigned)&IRQ117_Handler,
(unsigned)&IRQ118_Handler,
(unsigned)&IRQ119_Handler,
(unsigned)&IRQ120_Handler,
(unsigned)&IRQ121_Handler,
(unsigned)&IRQ122_Handler,
(unsigned)&IRQ123_Handler,
(unsigned)&IRQ124_Handler,
(unsigned)&IRQ125_Handler,
(unsigned)&IRQ126_Handler,
(unsigned)&IRQ127_Handler,
(unsigned)&IRQ128_Handler,
(unsigned)&IRQ129_Handler,
(unsigned)&IRQ130_Handler,
(unsigned)&IRQ131_Handler,
(unsigned)&IRQ132_Handler,
(unsigned)&IRQ133_Handler,
(unsigned)&IRQ134_Handler,
(unsigned)&IRQ135_Handler,
(unsigned)&IRQ136_Handler,
(unsigned)&IRQ137_Handler,
(unsigned)&IRQ138_Handler,
(unsigned)&IRQ139_Handler,
(unsigned)&IRQ140_Handler,
(unsigned)&IRQ141_Handler,
(unsigned)&IRQ142_Handler,
(unsigned)&IRQ143_Handler
// [2 ... (15 + ARMV7M_PERIPHERAL_INTERRUPTS)] = (unsigned)&exception_common
};
#endif

View File

@ -137,6 +137,8 @@ typedef struct
#define GPIO_PORT_SHIFT 16
#define GPIO_PINSET(_port, _pin) ((uint32_t)(_port << GPIO_PORT_SHIFT) | _pin)
#define GPIO_PIN(_pinset) ((_pinset >> GPIO_PIN_SHIFT) & GPIO_PIN_MASK)
#define GPIO_PORT(_pinset) ((_pinset >> GPIO_PORT_SHIFT) & GPIO_PORT_MASK)
/**
* @}

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,446 @@
/**
*******************************************************************************
* @file hc32f4a0_spi.h
* @brief This file contains all the functions prototypes of the SPI driver
* library.
@verbatim
Change Logs:
Date Author Notes
2020-06-12 Wangmin First version
@endverbatim
*******************************************************************************
* Copyright (C) 2020, Huada Semiconductor Co., Ltd. All rights reserved.
*
* This software component is licensed by HDSC 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
*
*******************************************************************************
*/
#ifndef __HC32F4A0_SPI_H__
#define __HC32F4A0_SPI_H__
/* C binding of definitions if building with C++ compiler */
#ifdef __cplusplus
extern "C"
{
#endif
/*******************************************************************************
* Include files
******************************************************************************/
#include "hc32_common.h"
#include "ddl_config.h"
/**
* @addtogroup HC32F4A0_DDL_Driver
* @{
*/
/**
* @addtogroup DDL_SPI
* @{
*/
#if (DDL_SPI_ENABLE == DDL_ON)
/*******************************************************************************
* Global type definitions ('typedef')
******************************************************************************/
/**
* @defgroup SPI_Global_Types SPI Global Types
* @{
*/
/**
* @brief Structure definition of SPI initialization.
*/
typedef struct
{
uint32_t u32WireMode; /*!< SPI wire mode, 3 wire mode or 4 wire mode.
This parameter can be a value of @ref SPI_Wire_Mode_Define */
uint32_t u32TransMode; /*!< SPI transfer mode, send only or full duplex.
This parameter can be a value of @ref SPI_Transfer_Mode_Define */
uint32_t u32MasterSlave; /*!< SPI master/slave mode.
This parameter can be a value of @ref SPI_Master_Slave_Mode_Define */
uint32_t u32SuspMode; /*!< SPI communication suspend function.
This parameter can be a value of @ref SPI_Communication_Suspend_Function_Define */
uint32_t u32Modfe; /*!< SPI mode fault detect command.
This parameter can be a value of @ref SPI_Mode_Fault_Dectet_Command_Define */
uint32_t u32Parity; /*!< SPI parity check selection.
This parameter can be a value of @ref SPI_Parity_Check_Define */
uint32_t u32SpiMode; /*!< SPI mode.
This parameter can be a value of @ref SPI_Mode_Define */
uint32_t u32BaudRatePrescaler; /*!< SPI baud rate prescaler.
This parameter can be a value of @ref SPI_Baud_Rate_Prescaler_Define */
uint32_t u32DataBits; /*!< SPI data bits, 4 bits ~ 32 bits.
This parameter can be a value of @ref SPI_Data_Size_Define */
uint32_t u32FirstBit; /*!< MSB first or LSB first.
This parameter can be a value of @ref SPI_First_Bit_Define */
uint32_t u32FrameLevel; /*!< SPI frame level, SPI_FRAME_1 ~ SPI_FRAME_4.
This parameter can be a value of @ref SPI_Frame_Level_Define */
} stc_spi_init_t;
/**
* @brief Structure definition of SPI delay time configuration.
*/
typedef struct
{
uint32_t u32IntervalDelay; /*!< SPI interval time delay (Next access delay time)
This parameter can be a value of @ref SPI_Interval_Delay_Time_define */
uint32_t u32ReleaseDelay; /*!< SPI release time delay (SCK invalid delay time)
This parameter can be a value of @ref SPI_Release_Delay_Time_define */
uint32_t u32SetupDelay; /*!< SPI Setup time delay (SCK valid delay time) define
This parameter can be a value of @ref SPI_Setup_Delay_Time_define */
} stc_spi_delay_t;
/**
* @}
*/
/*******************************************************************************
* Global pre-processor symbols/macros ('#define')
******************************************************************************/
/**
* @defgroup SPI_Global_Macros SPI Global Macros
* @{
*/
/**
* @defgroup SPI_Wire_Mode_Define SPI wire mode define
* @{
*/
#define SPI_WIRE_4 (0UL)
#define SPI_WIRE_3 (SPI_CR1_SPIMDS)
/**
* @}
*/
/**
* @defgroup SPI_Transfer_Mode_Define SPI transfer mode define
* @{
*/
#define SPI_FULL_DUPLEX (0UL) /*!< Full duplex. */
#define SPI_SEND_ONLY (SPI_CR1_TXMDS) /*!< Send only. */
/**
* @}
*/
/**
* @defgroup SPI_Master_Slave_Mode_Define SPI master slave mode define
* @{
*/
#define SPI_SLAVE (0UL)
#define SPI_MASTER (SPI_CR1_MSTR)
/**
* @}
*/
/**
* @defgroup SPI_Loopback_Selection_Define SPI loopback selection define
* @note Loopback mode is mainly used for parity self-diagnosis in 4-wire full-duplex mode.
* @{
*/
#define SPI_SPLPBK_INVALID (0UL)
#define SPI_SPLPBK_MOSI_INVERT (SPI_CR1_SPLPBK) /*!< MISO data is the inverse of the data output by MOSI. */
#define SPI_SPLPBK_MOSI (SPI_CR1_SPLPBK2) /*!< MISO data is the data output by MOSI. */
/**
* @}
*/
/**
* @defgroup SPI_Communication_Suspend_Function_Define SPI communication suspend function define
* @{
*/
#define SPI_COM_SUSP_FUNC_OFF (0UL)
#define SPI_COM_SUSP_FUNC_ON (SPI_CR1_CSUSPE)
/**
* @}
*/
/**
* @defgroup SPI_Interrupt_Type_Define SPI interrupt type define
* @{
*/
#define SPI_INT_ERROR (SPI_CR1_EIE) /*!< Including overload, underload and parity error. */
#define SPI_INT_TX_BUFFER_EMPTY (SPI_CR1_TXIE)
#define SPI_INT_RX_BUFFER_FULL (SPI_CR1_RXIE)
#define SPI_INT_IDLE (SPI_CR1_IDIE)
/**
* @}
*/
/**
* @defgroup SPI_Mode_Fault_Dectet_Command_Define SPI mode fault dectect command define
* @{
*/
#define SPI_MODFE_DISABLE (0UL) /*!< Disable mode fault detection. */
#define SPI_MODFE_ENABLE (SPI_CR1_MODFE) /*!< Enable mode fault detection. */
/**
* @}
*/
/**
* @defgroup SPI_Parity_Check_Error_Self_Diagnosis_Define SPI parity check error self diagnosis define
* @{
*/
#define SPI_PATE_DISABLE (0UL) /*!< Disable self diagnosis of parity check. */
#define SPI_PATE_ENABLE (SPI_CR1_PATE) /*!< Enable self diagnosis of parity check. */
/**
* @}
*/
/**
* @defgroup SPI_Parity_Check_Define SPI parity check mode define
* @{
*/
#define SPI_PARITY_INVALID (0UL) /*!< Parity check invalid. */
#define SPI_PARITY_EVEN (SPI_CR1_PAE) /*!< Parity check selection even parity. */
#define SPI_PARITY_ODD (SPI_CR1_PAE | SPI_CR1_PAOE) /*!< Parity check selection odd parity. */
/**
* @}
*/
/**
* @defgroup SPI_Interval_Delay_Time_define SPI interval time delay (Next access delay time) define
* @{
*/
#define SPI_INTERVAL_TIME_1SCK_2PCLK1 (0UL)
#define SPI_INTERVAL_TIME_2SCK_2PCLK1 (SPI_CFG1_MIDI_0)
#define SPI_INTERVAL_TIME_3SCK_2PCLK1 (SPI_CFG1_MIDI_1)
#define SPI_INTERVAL_TIME_4SCK_2PCLK1 (SPI_CFG1_MIDI_1 | SPI_CFG1_MIDI_0)
#define SPI_INTERVAL_TIME_5SCK_2PCLK1 (SPI_CFG1_MIDI_2)
#define SPI_INTERVAL_TIME_6SCK_2PCLK1 (SPI_CFG1_MIDI_2 | SPI_CFG1_MIDI_0)
#define SPI_INTERVAL_TIME_7SCK_2PCLK1 (SPI_CFG1_MIDI_2 | SPI_CFG1_MIDI_1)
#define SPI_INTERVAL_TIME_8SCK_2PCLK1 (SPI_CFG1_MIDI_2 | SPI_CFG1_MIDI_1 | SPI_CFG1_MIDI_0)
/**
* @}
*/
/**
* @defgroup SPI_Release_Delay_Time_define SPI release time delay (SCK invalid delay time) define
* @{
*/
#define SPI_RELEASE_TIME_1SCK (0UL)
#define SPI_RELEASE_TIME_2SCK (SPI_CFG1_MSSDL_0)
#define SPI_RELEASE_TIME_3SCK (SPI_CFG1_MSSDL_1)
#define SPI_RELEASE_TIME_4SCK (SPI_CFG1_MSSDL_1 | SPI_CFG1_MSSDL_0)
#define SPI_RELEASE_TIME_5SCK (SPI_CFG1_MSSDL_2)
#define SPI_RELEASE_TIME_6SCK (SPI_CFG1_MSSDL_2 | SPI_CFG1_MSSDL_0)
#define SPI_RELEASE_TIME_7SCK (SPI_CFG1_MSSDL_2 | SPI_CFG1_MSSDL_1)
#define SPI_RELEASE_TIME_8SCK (SPI_CFG1_MSSDL_2 | SPI_CFG1_MSSDL_1 | SPI_CFG1_MSSDL_0)
/**
* @}
*/
/**
* @defgroup SPI_Setup_Delay_Time_define SPI Setup time delay (SCK valid delay time) define
* @{
*/
#define SPI_SETUP_TIME_1SCK (0UL)
#define SPI_SETUP_TIME_2SCK (SPI_CFG1_MSSI_0)
#define SPI_SETUP_TIME_3SCK (SPI_CFG1_MSSI_1)
#define SPI_SETUP_TIME_4SCK (SPI_CFG1_MSSI_1 | SPI_CFG1_MSSI_0)
#define SPI_SETUP_TIME_5SCK (SPI_CFG1_MSSI_2)
#define SPI_SETUP_TIME_6SCK (SPI_CFG1_MSSI_2 | SPI_CFG1_MSSI_0)
#define SPI_SETUP_TIME_7SCK (SPI_CFG1_MSSI_2 | SPI_CFG1_MSSI_1)
#define SPI_SETUP_TIME_8SCK (SPI_CFG1_MSSI_2 | SPI_CFG1_MSSI_1 | SPI_CFG1_MSSI_0)
/**
* @}
*/
/**
* @defgroup SPI_SS_Pin_Define SPI SSx define
* @{
*/
#define SPI_PIN_SS0 (SPI_CFG1_SS0PV)
#define SPI_PIN_SS1 (SPI_CFG1_SS1PV)
#define SPI_PIN_SS2 (SPI_CFG1_SS2PV)
#define SPI_PIN_SS3 (SPI_CFG1_SS3PV)
/**
* @}
*/
/**
* @defgroup SPI_SS_Active_Level_Define SPI SSx Active Level define
* @{
*/
#define SPI_SS_ACTIVE_LOW (0UL) /*!< SS pin active low. */
#define SPI_SS_ACTIVE_HIGH (1UL) /*!< SS pin active high. */
/**
* @}
*/
/**
* @defgroup SPI_Read_Target_Buffer_Define SPI read data register target buffer define
* @{
*/
#define SPI_RD_TARGET_RD_BUF (0UL) /*!< Read RX buffer. */
#define SPI_RD_TARGET_WR_BUF (SPI_CFG1_SPRDTD) /*!< Read TX buffer. */
/**
* @}
*/
/**
* @defgroup SPI_Frame_Level_Define SPI data frame level define, The Data in the
* SPI_DR register will be send to TX_BUFF after
* enough data frame write to the SPI_DR
* @{
*/
#define SPI_FRAME_1 (0UL) /*!< Data 1 frame */
#define SPI_FRAME_2 (SPI_CFG1_FTHLV_0) /*!< Data 2 frame.*/
#define SPI_FRAME_3 (SPI_CFG1_FTHLV_1) /*!< Data 3 frame.*/
#define SPI_FRAME_4 (SPI_CFG1_FTHLV_0 | SPI_CFG1_FTHLV_1) /*!< Data 4 frame.*/
/**
* @}
*/
/**
* @defgroup SPI_Mode_Define SPI Mode define
* @{
*/
/* SCK pin output low in idle state; MOSI/MISO pin data valid in odd edge , MOSI/MISO pin data change in even edge */
#define SPI_MODE_0 (0UL)
/* SCK pin output low in idle state; MOSI/MISO pin data valid in even edge , MOSI/MISO pin data change in odd edge */
#define SPI_MODE_1 (SPI_CFG2_CPHA)
/* SCK pin output high in idle state; MOSI/MISO pin data valid in odd edge , MOSI/MISO pin data change in even edge */
#define SPI_MODE_2 (SPI_CFG2_CPOL)
/* SCK pin output high in idle state; MOSI/MISO pin data valid in even edge , MOSI/MISO pin data change in odd edge */
#define SPI_MODE_3 (SPI_CFG2_CPOL | SPI_CFG2_CPHA)
/**
* @}
*/
/**
* @defgroup SPI_Baud_Rate_Prescaler_Define SPI baudrate prescaler define
* @{
*/
#define SPI_BR_PCLK1_DIV2 (0UL) /*!< SPI baud rate is the pclk1 divided by 2. */
#define SPI_BR_PCLK1_DIV4 (SPI_CFG2_MBR_0) /*!< SPI baud rate is the pclk1 clock divided by 4. */
#define SPI_BR_PCLK1_DIV8 (SPI_CFG2_MBR_1) /*!< SPI baud rate is the pclk1 clock divided by 8. */
#define SPI_BR_PCLK1_DIV16 (SPI_CFG2_MBR_1 | SPI_CFG2_MBR_0) /*!< SPI baud rate is the pclk1 clock divided by 16. */
#define SPI_BR_PCLK1_DIV32 (SPI_CFG2_MBR_2) /*!< SPI baud rate is the pclk1 clock divided by 32. */
#define SPI_BR_PCLK1_DIV64 (SPI_CFG2_MBR_2 | SPI_CFG2_MBR_0) /*!< SPI baud rate is the pclk1 clock divided by 64. */
#define SPI_BR_PCLK1_DIV128 (SPI_CFG2_MBR_2 | SPI_CFG2_MBR_1) /*!< SPI baud rate is the pclk1 clock divided by 128. */
#define SPI_BR_PCLK1_DIV256 (SPI_CFG2_MBR_2 | SPI_CFG2_MBR_1 | SPI_CFG2_MBR_0) /*!< SPI baud rate is the pclk1 divided by 256. */
/**
* @}
*/
/**
* @defgroup SPI_Data_Size_Define SPI data size define
* @{
*/
#define SPI_DATA_SIZE_4BIT (0UL)
#define SPI_DATA_SIZE_5BIT (SPI_CFG2_DSIZE_0)
#define SPI_DATA_SIZE_6BIT (SPI_CFG2_DSIZE_1)
#define SPI_DATA_SIZE_7BIT (SPI_CFG2_DSIZE_0 | SPI_CFG2_DSIZE_1)
#define SPI_DATA_SIZE_8BIT (SPI_CFG2_DSIZE_2)
#define SPI_DATA_SIZE_9BIT (SPI_CFG2_DSIZE_2 | SPI_CFG2_DSIZE_0)
#define SPI_DATA_SIZE_10BIT (SPI_CFG2_DSIZE_2 | SPI_CFG2_DSIZE_1)
#define SPI_DATA_SIZE_11BIT (SPI_CFG2_DSIZE_2 | SPI_CFG2_DSIZE_1 | SPI_CFG2_DSIZE_0)
#define SPI_DATA_SIZE_12BIT (SPI_CFG2_DSIZE_3)
#define SPI_DATA_SIZE_13BIT (SPI_CFG2_DSIZE_3 | SPI_CFG2_DSIZE_0)
#define SPI_DATA_SIZE_14BIT (SPI_CFG2_DSIZE_3 | SPI_CFG2_DSIZE_1)
#define SPI_DATA_SIZE_15BIT (SPI_CFG2_DSIZE_3 | SPI_CFG2_DSIZE_1 | SPI_CFG2_DSIZE_0)
#define SPI_DATA_SIZE_16BIT (SPI_CFG2_DSIZE_3 | SPI_CFG2_DSIZE_2)
#define SPI_DATA_SIZE_20BIT (SPI_CFG2_DSIZE_3 | SPI_CFG2_DSIZE_2 | SPI_CFG2_DSIZE_0)
#define SPI_DATA_SIZE_24BIT (SPI_CFG2_DSIZE_3 | SPI_CFG2_DSIZE_2 | SPI_CFG2_DSIZE_1)
#define SPI_DATA_SIZE_32BIT (SPI_CFG2_DSIZE_3 | SPI_CFG2_DSIZE_2 | SPI_CFG2_DSIZE_1 | SPI_CFG2_DSIZE_0)
/**
* @}
*/
/**
* @defgroup SPI_First_Bit_Define SPI first bit define
* @{
*/
#define SPI_FIRST_MSB (0UL)
#define SPI_FIRST_LSB (SPI_CFG2_LSBF)
/**
* @}
*/
/**
* @defgroup SPI_State_Flag_Define SPI state flag define
* @{
*/
#define SPI_FLAG_OVERLOAD (SPI_SR_OVRERF)
#define SPI_FLAG_IDLE (SPI_SR_IDLNF)
#define SPI_FLAG_MODE_FAULT (SPI_SR_MODFERF)
#define SPI_FLAG_PARITY_ERROR (SPI_SR_PERF)
#define SPI_FLAG_UNDERLOAD (SPI_SR_UDRERF)
#define SPI_FLAG_TX_BUFFER_EMPTY (SPI_SR_TDEF) /*!< This flag is set when the data in the data register \
is copied into the shift register, but the transmission \
of the data bit may not have been completed. */
#define SPI_FLAG_RX_BUFFER_FULL (SPI_SR_RDFF) /*!< When this flag is set, it indicates that a data was received. */
/**
* @}
*/
/**
* @}
*/
/*******************************************************************************
* Global variable definitions ('extern')
******************************************************************************/
/*******************************************************************************
Global function prototypes (definition in C source)
******************************************************************************/
/**
* @addtogroup SPI_Global_Functions
* @{
*/
en_result_t SPI_StructInit(stc_spi_init_t *pstcInit);
en_result_t SPI_DelayStructInit(stc_spi_delay_t *pstcDelayCfg);
en_result_t SPI_Init(M4_SPI_TypeDef *SPIx, const stc_spi_init_t *pstcInit);
void SPI_DeInit(M4_SPI_TypeDef *SPIx);
void SPI_IntCmd(M4_SPI_TypeDef *SPIx, uint32_t u32IntType, en_functional_state_t enNewState);
void SPI_FunctionCmd(M4_SPI_TypeDef *SPIx, en_functional_state_t enNewState);
void SPI_WriteDataReg(M4_SPI_TypeDef *SPIx, uint32_t u32Data);
uint32_t SPI_ReadDataReg(const M4_SPI_TypeDef *SPIx);
en_flag_status_t SPI_GetStatus(const M4_SPI_TypeDef *SPIx, uint32_t u32Flag);
void SPI_ClearFlag(M4_SPI_TypeDef *SPIx, uint32_t u32Flag);
void SPI_LoopbackModeCfg(M4_SPI_TypeDef *SPIx, uint32_t u32Mode);
void SPI_PateCmd(M4_SPI_TypeDef *SPIx, en_functional_state_t enNewState);
en_result_t SPI_DelayTimeCfg(M4_SPI_TypeDef *SPIx, const stc_spi_delay_t *pstcDelayCfg);
void SPI_SSValidLevelCfg(M4_SPI_TypeDef *SPIx, uint32_t u32SSPin, en_functional_state_t enNewState);
void SPI_SSPinSel(M4_SPI_TypeDef *SPIx, uint32_t u32SSPin);
void SPI_ReadBufCfg(M4_SPI_TypeDef *SPIx, uint32_t u32ReadBuf);
en_result_t SPI_Transmit(M4_SPI_TypeDef *SPIx, const void *pvTxBuf, uint32_t u32TxLength);
en_result_t SPI_Receive(M4_SPI_TypeDef *SPIx, void *pvRxBuf, uint32_t u32RxLength);
en_result_t SPI_TransmitReceive(M4_SPI_TypeDef *SPIx, const void *pvTxBuf, void *pvRxBuf, uint32_t u32Length);
/**
* @}
*/
#endif /* DDL_SPI_ENABLE */
/**
* @}
*/
/**
* @}
*/
#ifdef __cplusplus
}
#endif
#endif /* __HC32F4A0_SPI_H__ */
/*******************************************************************************
* EOF (not truncated)
******************************************************************************/

View File

@ -1,575 +0,0 @@
/**
*******************************************************************************
* @file w25qxx.c
* @brief This midware file provides firmware functions to W25QXX group spi flash.
@verbatim
Change Logs:
Date Author Notes
2020-06-12 Wangmin First version
2020-08-31 Wangmin Modify for MISRAC2012
@endverbatim
*******************************************************************************
* Copyright (C) 2020, Huada Semiconductor Co., Ltd. All rights reserved.
*
* This software component is licensed by HDSC 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
*
*******************************************************************************
*/
/*******************************************************************************
* Include files
******************************************************************************/
#include "w25qxx.h"
#include "ev_hc32f4a0_lqfp176_w25qxx.h"
/**
* @addtogroup BSP
* @{
*/
/**
* @addtogroup Components
* @{
*/
/** @defgroup W25QXX Flash Driver for W25QXX
* @{
*/
#if (BSP_W25QXX_ENABLE == BSP_ON)
/*******************************************************************************
* Local type definitions ('typedef')
******************************************************************************/
/*******************************************************************************
* Local pre-processor symbols/macros ('#define')
******************************************************************************/
/**
* @defgroup W25QXX_Local_Macros W25QXX Local Macros
* @{
*/
#define W25Q_BIT_0 (1UL << 0U)
#define W25Q_BIT_1 (1UL << 1U)
#define W25Q_BIT_2 (1UL << 2U)
#define W25Q_BIT_3 (1UL << 3U)
#define W25Q_BIT_4 (1UL << 4U)
#define W25Q_BIT_5 (1UL << 5U)
#define W25Q_BIT_6 (1UL << 6U)
#define W25Q_BIT_7 (1UL << 7U)
#define W25Q_BIT_8 (1UL << 8U)
#define W25Q_BIT_9 (1UL << 9U)
#define W25Q_BIT_10 (1UL << 10U)
#define W25Q_BIT_11 (1UL << 11U)
#define W25Q_BIT_12 (1UL << 12U)
#define W25Q_BIT_13 (1UL << 13U)
#define W25Q_BIT_14 (1UL << 14U)
#define W25Q_BIT_15 (1UL << 15U)
#define W25Q_ST_BUSY ((uint16_t)W25Q_BIT_0)
#define W25Q_ST_WEL ((uint16_t)W25Q_BIT_1) /*<! Write enable latch. */
#define LOAD_CMD(a, cmd, addr) do { \
(a)[0U] = (cmd); \
(a)[1U] = (uint8_t)((addr) >> 16U); \
(a)[2U] = (uint8_t)((addr) >> 8U); \
(a)[3U] = (uint8_t)(addr); \
} while (0U)
/**
* @}
*/
/*******************************************************************************
* Global variable definitions (declared in header file with 'extern')
******************************************************************************/
/*******************************************************************************
* Local function prototypes ('static')
******************************************************************************/
/**
* @defgroup W25QXX_Local_Functions W25QXX Local Functions
* @{
*/
static void W25QXX_WriteCmd(uint8_t u8Cmd, const uint8_t *pu8CmdData, uint32_t u32CmdDataLength);
static void W25QXX_ReadCmd(uint8_t u8Cmd, uint8_t *pu8CmdData, uint32_t u32CmdDataLength,
uint8_t *pu8Info, uint8_t u8InfoLength);
static void W25QXX_Wt(uint8_t u8Cmd, uint32_t u32Address, const uint8_t *pu8Data, uint32_t u32DataLength);
static void W25QXX_Rd(uint8_t u8Cmd, uint32_t u32Address, uint8_t *pu8Data, uint32_t u32DataLength);
static void W25QXX_WaitBusy(void);
static void W25QXX_WriteEnable(void);
static void W25QXX_WriteDisable(void);
static void W25QXX_WritePage(uint32_t u32Address, const uint8_t *pu8Data, uint32_t u32DataLength);
static void W25QXX_Write_NoCheck(const uint8_t *pBuffer, uint32_t WriteAddr, uint16_t NumByteToWrite);
static void W25QXX_WriteCmd(uint8_t u8Cmd, const uint8_t *pu8CmdData, uint32_t u32CmdDataLength);
static void W25QXX_ReadCmd(uint8_t u8Cmd, uint8_t *pu8CmdData, uint32_t u32CmdDataLength,
uint8_t *pu8Info, uint8_t u8InfoLength);
/**
* @}
*/
/*******************************************************************************
* Local variable definitions ('static')
******************************************************************************/
static uint8_t W25QXX_BUFFER[4096U];
/*******************************************************************************
* Function implementation - global ('extern') and local ('static')
******************************************************************************/
/**
* @defgroup W25QXX_Global_Functions W25QXX Global Functions
* @{
*/
/**
* @brief Initializes W25QXX.
* @param [out] pstcW25qxx Pointer to a stc_w25qxx_t structure which contains the information of the SPI flash.
* @retval None
*/
void W25QXX_Init(stc_w25qxx_t *pstcW25qxx)
{
BSP_W25Q_SPI_Init();
if (pstcW25qxx != NULL)
{
/* Read Flash ID */
pstcW25qxx->u16ManId = W25QXX_ReadManDeviceId();
switch (pstcW25qxx->u16ManId)
{
case W25Q64:
pstcW25qxx->u32PageCount = 32768UL; /* W25Q64 contains 32768 pages. */
pstcW25qxx->u32SectorCount = 2048U; /* W25Q64 contains 2048 sectors. */
pstcW25qxx->u32BlockCount32k = 0U; /* DO NOT support 32K block. */
pstcW25qxx->u32BlockCount64k = 128U;
pstcW25qxx->u32CapacityInBytes = pstcW25qxx->u32PageCount * W25Q_SIZE_PAGE;
pstcW25qxx->u32CapacityInKB = pstcW25qxx->u32CapacityInBytes * W25Q_SIZE_1K;
break;
default:
break;
}
}
}
/**
* @brief Read manufacturer device ID.
* @param None
* @retval 16 bit manufacturer device ID.
*/
uint16_t W25QXX_ReadManDeviceId(void)
{
uint8_t au8TempId[2U];
uint8_t au8Dummy[3U] = {0U};
uint16_t u16ManID;
W25QXX_ReadCmd(W25Q_MANUFACTURER_DEVICE_ID, au8Dummy, 3U, au8TempId, 2U);
u16ManID = (uint16_t)au8TempId[0U] << 8U;
u16ManID |= au8TempId[1U];
return u16ManID;
}
/**
* @brief Read unique ID.
* @param [out] pu8UniqueId Pointer to a buffer the 64 bit unique ID to be stored.
* @retval None
*/
void W25QXX_ReadUniqueId(uint8_t *pu8UniqueId)
{
uint8_t au8Dummy[4U] = {0U};
W25QXX_ReadCmd(W25Q_READ_UNIQUE_ID, au8Dummy, 4U, pu8UniqueId, 8U);
}
/**
* @brief W25QXX read status register.
* @param None
* @retval 16 bit W25QXX status.
*/
uint16_t W25QXX_ReadStatus(void)
{
uint8_t u8TempStatus;
uint16_t u16RetStatus;
W25QXX_ReadCmd(W25Q_READ_STATUS_REG_2, NULL, 0U, &u8TempStatus, 1U);
u16RetStatus = u8TempStatus;
W25QXX_ReadCmd(W25Q_READ_STATUS_REG_1, NULL, 0U, &u8TempStatus, 1U);
u16RetStatus <<= 8U;
u16RetStatus |= u8TempStatus;
return u16RetStatus;
}
/**
* @brief W25QXX write status register
* @param [in] u16Status Specified status.
* @retval None
*/
void W25QXX_WriteStatus(uint16_t u16Status)
{
uint8_t au8Data[2U];
au8Data[0U] = (uint8_t)u16Status;
au8Data[1U] = (uint8_t)(u16Status >> 8U);
W25QXX_WriteCmd(W25Q_WRITE_STATUS_REG, au8Data, 2U);
}
/**
* @brief W25QXX power down.
* @param None
* @retval None
*/
void W25QXX_PowerDown(void)
{
W25QXX_WriteCmd(W25Q_POWER_DOWN, NULL, 0U);
W25QXX_DELAY_MS(1U);
}
/**
* @brief W25QXX release power down.
* @param None
* @retval None
*/
void W25QXX_ReleasePowerDown(void)
{
W25QXX_WriteCmd(W25Q_RELEASE_POWER_DOWN, NULL, 0U);
W25QXX_DELAY_MS(1U);
}
/**
* @brief W25QXX chip ease.
* @param None
* @retval None
*/
void W25QXX_EraseChip(void)
{
W25QXX_WriteEnable();
W25QXX_WaitBusy();
W25QXX_WriteCmd(W25Q_CHIP_ERASE, NULL, 0U);
W25QXX_WaitBusy();
}
/**
* @brief W25QXX sector ease.
* @param [in] u32SectorAddress The address of the specified sector.
* @retval None
*/
void W25QXX_EraseSector(uint32_t u32SectorAddress)
{
u32SectorAddress *= W25Q_SIZE_SECTOR;
W25QXX_WriteEnable();
W25QXX_WaitBusy();
W25QXX_Wt(W25Q_SECTOR_ERASE, u32SectorAddress, NULL, 0U);
W25QXX_WaitBusy();
W25QXX_WriteDisable();
}
/**
* @brief W25QXX block ease.
* @param [in] u32BlockAddress The address of the specified block.
* @retval None
*/
void W25QXX_EraseBlock(uint32_t u32BlockAddress)
{
W25QXX_Wt(W25Q_BLOCK_ERASE_64K, u32BlockAddress, NULL, 0U);
}
/**
* @brief W25QXX flash write
* @param [in] pBuffer Data buffer to be written
* @param [in] WriteAddr Address to be written
* @param [in] NumByteToWrite Number to be written, (MAX. 65535)
* @retval None
*/
static void W25QXX_Write_NoCheck(const uint8_t *pBuffer, uint32_t WriteAddr, uint16_t NumByteToWrite)
{
uint32_t pageremain;
uint32_t u32BufAdrTmp = (uint32_t)pBuffer;
pageremain = 256U - WriteAddr % 256U;
if (NumByteToWrite <= pageremain)
{
pageremain = NumByteToWrite;
}
for(;;)
{
W25QXX_WritePage(WriteAddr, (uint8_t *)u32BufAdrTmp, pageremain);
if (NumByteToWrite == (uint16_t)pageremain)
{
break;
}
else //NumByteToWrite>pageremain
{
u32BufAdrTmp += pageremain;
WriteAddr += pageremain;
NumByteToWrite -= (uint16_t)pageremain;
if (NumByteToWrite > 256U)
{
pageremain = 256U;
}
else
{
pageremain = (uint32_t)NumByteToWrite;
}
}
}
}
/**
* @brief W25QXX write data.
* @param [in] u32Address The start address of the data to be written.
* @param [in] pu8WriteBuf The pointer to the buffer contains the data to be written.
* @param [in] u32NumByteToWrite Buffer size in bytes.
* @retval None
*/
void W25QXX_WriteData(uint32_t u32Address, const uint8_t *pu8WriteBuf, uint32_t u32NumByteToWrite)
{
uint32_t secpos;
uint16_t secoff;
uint16_t secremain;
uint16_t i;
uint8_t *pW25QXX_BUF;
pW25QXX_BUF = W25QXX_BUFFER;
uint32_t u32WriteBufAddr = (uint32_t)&pu8WriteBuf;
secpos = u32Address / 4096U;
secoff = (uint16_t)(u32Address % 4096U);
secremain = 4096U - secoff;
if (u32NumByteToWrite <= secremain)
{
secremain = (uint16_t)u32NumByteToWrite;
}
for(;;)
{
W25QXX_ReadData(secpos * 4096U, pW25QXX_BUF, 4096U); // read one sector content
for (i = 0U; i < secremain; i++) // check if blank sector
{
if (pW25QXX_BUF[secoff + i] != (uint8_t)0xFFU)
{
break;
}
}
if (i < secremain)
{
W25QXX_EraseSector(secpos); // not blank, need erase
for (i = 0U; i < secremain; i++) // backup first
{
pW25QXX_BUF[i + secoff] = pu8WriteBuf[i];
}
W25QXX_Write_NoCheck(pW25QXX_BUF, secpos * 4096U, 4096U); // write back after erase
}
else
{
W25QXX_Write_NoCheck((const uint8_t *)u32WriteBufAddr, u32Address, secremain);
}
if (u32NumByteToWrite == secremain)
{
break;
}
else
{
secpos++; // next sector
secoff = 0U;
u32WriteBufAddr += secremain;
u32Address += secremain;
u32NumByteToWrite -= secremain;
if (u32NumByteToWrite > 4096U)
{
secremain = 4096U;
}
else
{
secremain = (uint16_t)u32NumByteToWrite;
}
}
}
}
/**
* @brief W25QXX read data.
* @param [in] u32Address The start address of the data to be read.
* @param [in] pu8ReadBuf The pointer to the buffer contains the data to be stored.
* @param [in] u32NumByteToRead Buffer size in bytes.
* @retval None
*/
void W25QXX_ReadData(uint32_t u32Address, uint8_t *pu8ReadBuf, uint32_t u32NumByteToRead)
{
W25QXX_Rd(W25Q_READ_DATA, u32Address, pu8ReadBuf, u32NumByteToRead);
}
/**
* @}
*/
/**
* @addtogroup W25QXX_Local_Functions W25QXX Local Functions
* @{
*/
/**
* @brief W25QXX write command.
* @param [in] u8Cmd Command of W25QXX.
* @param [in] pu8CmdData Pointer to a buffer that contains the data following the command.
* @param [in] u32CmdDataLength The length of the command data in bytes.
* @retval None
*/
static void W25QXX_WriteCmd(uint8_t u8Cmd, const uint8_t *pu8CmdData, uint32_t u32CmdDataLength)
{
W25Q_CS_ACTIVE();
(void)BSP_W25Q_SPI_Transmit(&u8Cmd, 1U);
(void)BSP_W25Q_SPI_Transmit(pu8CmdData, u32CmdDataLength);
W25Q_CS_INACTIVE();
}
/**
* @brief W25QXX read command.
* @param [in] u8Cmd Command of W25QXX.
* @param [in] pu8CmdData Pointer to a buffer that contains the data following the command.
* @param [in] u32CmdDataLength The length of the command data in bytes.
* @param [in] pu8Info The information of the command.
* @param [in] u8InfoLength The length of the information.
* @retval None
*/
static void W25QXX_ReadCmd(uint8_t u8Cmd, uint8_t *pu8CmdData, uint32_t u32CmdDataLength,
uint8_t *pu8Info, uint8_t u8InfoLength)
{
W25Q_CS_ACTIVE();
(void)BSP_W25Q_SPI_Transmit(&u8Cmd, 1U);
(void)BSP_W25Q_SPI_Transmit(pu8CmdData, u32CmdDataLength);
(void)BSP_W25Q_SPI_Receive(pu8Info, (uint32_t)u8InfoLength);
W25Q_CS_INACTIVE();
}
/**
* @brief W25QXX write data.
* @param [in] u8Cmd Command of W25QXX.
* @param [in] u32Address The start address of the data to be written.
* @param [in] pu8Data The data to be written.
* @param [in] u32DataLength The length of the data in bytes.
* @retval None
*/
static void W25QXX_Wt(uint8_t u8Cmd, uint32_t u32Address, const uint8_t *pu8Data, uint32_t u32DataLength)
{
uint8_t au8Cmd[4U];
LOAD_CMD(au8Cmd, u8Cmd, u32Address);
W25Q_CS_ACTIVE();
(void)BSP_W25Q_SPI_Transmit(au8Cmd, 4U);
(void)BSP_W25Q_SPI_Transmit(pu8Data, u32DataLength);
W25Q_CS_INACTIVE();
}
/**
* @brief W25QXX read data.
* @param [in] u8Cmd Command of W25QXX.
* @param [in] u32Address The start address of the data to be written.
* @param [in] pu8Data The data to be stored.
* @param [in] u32DataLength The length of the data in bytes.
* @retval None
*/
static void W25QXX_Rd(uint8_t u8Cmd, uint32_t u32Address, uint8_t *pu8Data, uint32_t u32DataLength)
{
uint8_t au8Cmd[4U];
LOAD_CMD(au8Cmd, u8Cmd, u32Address);
W25Q_CS_ACTIVE();
(void)BSP_W25Q_SPI_Transmit(au8Cmd, 4U);
(void)BSP_W25Q_SPI_Receive(pu8Data, u32DataLength);
W25Q_CS_INACTIVE();
}
/**
* @brief W25QXX Write enable.
* @param None
* @retval None
*/
static void W25QXX_WriteEnable(void)
{
W25QXX_WriteCmd(W25Q_WRITE_ENABLE, NULL, 0U);
}
/**
* @brief W25QXX Write disable.
* @param None
* @retval None
*/
static void W25QXX_WriteDisable(void)
{
W25QXX_WriteCmd(W25Q_WRITE_DISABLE, NULL, 0U);
}
/**
* @brief Wait while W25QXX is busy.
* @param None
* @retval None
*/
static void W25QXX_WaitBusy(void)
{
while ((W25QXX_ReadStatus() & W25Q_ST_BUSY) == W25Q_ST_BUSY)
{
;
}
}
/**
* @brief W25QXX page program.
* @param [in] u32Address Start address of the page.
* @param [in] pu8Data Pointer to a buffer that contains the data to be written.
* @param [in] u32DataLength Size of the buffer in bytes.
* @retval None
*/
static void W25QXX_WritePage(uint32_t u32Address, const uint8_t *pu8Data, uint32_t u32DataLength)
{
W25QXX_WriteEnable();
W25QXX_Wt(W25Q_PAGE_PROGRAM, u32Address, pu8Data, u32DataLength);
W25QXX_WaitBusy();
}
/**
* @}
*/
#endif /* BSP_W25QXX_ENABLE */
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/*******************************************************************************
* EOF (not truncated)
******************************************************************************/

View File

@ -1,197 +0,0 @@
/**
*******************************************************************************
* @file w25qxx.h
* @brief This file provides firmware functions to W25QXX group spi flash.
@verbatim
Change Logs:
Date Author Notes
2020-06-12 Wangmin First version
@endverbatim
*******************************************************************************
* Copyright (C) 2020, Huada Semiconductor Co., Ltd. All rights reserved.
*
* This software component is licensed by HDSC 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
*
*******************************************************************************
*/
#ifndef __W25QXX_H__
#define __W25QXX_H__
/* C binding of definitions if building with C++ compiler */
#ifdef __cplusplus
extern "C"
{
#endif
/*******************************************************************************
* Include files
******************************************************************************/
#include "hc32_common.h"
/**
* @addtogroup BSP
* @{
*/
/**
* @addtogroup Components
* @{
*/
/** @addtogroup W25QXX
* @{
*/
#if (BSP_W25QXX_ENABLE == BSP_ON)
/*******************************************************************************
* Global type definitions ('typedef')
******************************************************************************/
/**
* @defgroup W25QXX_Global_Types W25QXX Global Types
* @{
*/
/**
* @brief Structure definition of W25QXX information.
*/
typedef struct
{
uint16_t u16ManId; /*!< Manufacturer device ID. */
uint8_t au8UniqueId[8U]; /*!< 64 bit unique ID number. */
uint32_t u32PageCount;
uint32_t u32SectorCount;
uint32_t u32BlockCount32k;
uint32_t u32BlockCount64k;
uint32_t u32CapacityInBytes;
uint32_t u32CapacityInKB;
} stc_w25qxx_t;
/**
* @}
*/
/*******************************************************************************
* Global pre-processor symbols/macros ('#define')
******************************************************************************/
/**
* @defgroup W25QXX_Global_Macros W25QXX Global Macros
* @{
*/
/**
* @defgroup W25QXX_ID W25QXX ID
* @{
*/
#define W25Q80 (0xEF13U)
#define W25Q16 (0xEF14U)
#define W25Q32 (0xEF15U)
#define W25Q64 (0xEF16U)
#define W25Q128 (0xEF17U)
/**
* @}
*/
/**
* @defgroup W25QXX_Command W25QXX Command
* @{
*/
#define W25Q_WRITE_ENABLE ((uint8_t)0x06U)
#define W25Q_VOLATILE_SR_WRITE_ENABLE ((uint8_t)0x50U)
#define W25Q_WRITE_DISABLE ((uint8_t)0x04U)
#define W25Q_READ_STATUS_REG_1 ((uint8_t)0x05U)
#define W25Q_READ_STATUS_REG_2 ((uint8_t)0x35U)
#define W25Q_WRITE_STATUS_REG ((uint8_t)0x01U)
#define W25Q_PAGE_PROGRAM ((uint8_t)0x02U)
#define W25Q_SECTOR_ERASE ((uint8_t)0x20U)
#define W25Q_BLOCK_ERASE_32K ((uint8_t)0x52U)
#define W25Q_BLOCK_ERASE_64K ((uint8_t)0xD8U)
#define W25Q_CHIP_ERASE ((uint8_t)0xC7U)
#define W25Q_ERASE_PROGRAM_SUSPEND ((uint8_t)0x75U)
#define W25Q_ERASE_PROGRAM_RESUME ((uint8_t)0x7AU)
#define W25Q_POWER_DOWN ((uint8_t)0xB9U)
#define W25Q_READ_DATA ((uint8_t)0x03U)
#define W25Q_FAST_READ ((uint8_t)0x0BU)
#define W25Q_DEVICE_ID ((uint8_t)0xABU)
#define W25Q_RELEASE_POWER_DOWN (W25Q_DEVICE_ID)
#define W25Q_MANUFACTURER_DEVICE_ID ((uint8_t)0x90U)
#define W25Q_JEDEC_ID ((uint8_t)0x9FU)
#define W25Q_READ_UNIQUE_ID ((uint8_t)0x4BU)
#define W25Q_READ_SFDP_REG ((uint8_t)0x5AU)
#define W25Q_REASE_SECURITY_REG ((uint8_t)0x44U)
#define W25Q_PROGRAM_SECURITY_REG ((uint8_t)0x42U)
#define W25Q_READ_SECURITY_REG ((uint8_t)0x48U)
#define W25Q_ENABLE_QPI ((uint8_t)0x38U)
#define W25Q_ENABLE_RESET ((uint8_t)0x66U)
#define W25Q_RESET ((uint8_t)0x99U)
/**
* @}
*/
#define W25Q_SIZE_1K (1024U) /*!< 1KB */
#define W25Q_SIZE_PAGE (256U) /*!< 256B/page */
#define W25Q_SIZE_SECTOR (W25Q_SIZE_1K * 4U) /*!< 4KB/sector */
#define W25Q_SIZE_BLOCK (W25Q_SIZE_1K * 64U) /*!< 64KB/block */
/**
* @}
*/
/*******************************************************************************
* Global variable definitions ('extern')
******************************************************************************/
/*******************************************************************************
Global function prototypes (definition in C source)
******************************************************************************/
/**
* @addtogroup W25QXX_Global_Functions W25QXX Global Functions
* @{
*/
void W25QXX_Init(stc_w25qxx_t *pstcW25qxx);
uint16_t W25QXX_ReadManDeviceId(void);
void W25QXX_ReadUniqueId(uint8_t *pu8UniqueId);
uint16_t W25QXX_ReadStatus(void);
void W25QXX_WriteStatus(uint16_t u16Status);
void W25QXX_PowerDown(void);
void W25QXX_ReleasePowerDown(void);
void W25QXX_EraseChip(void);
void W25QXX_EraseSector(uint32_t u32SectorAddress);
void W25QXX_EraseBlock(uint32_t u32BlockAddress);
void W25QXX_WriteData(uint32_t u32Address, const uint8_t *pu8WriteBuf, uint32_t u32NumByteToWrite);
void W25QXX_ReadData(uint32_t u32Address, uint8_t *pu8ReadBuf, uint32_t u32NumByteToRead);
/**
* @}
*/
#endif /* BSP_W25QXX_ENABLE */
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
#ifdef __cplusplus
}
#endif
#endif /* __W25QXX_H__ */
/*******************************************************************************
* EOF (not truncated)
******************************************************************************/