Merge branch 'prepare_for_master' of https://git.trustie.net/xuos/xiuos into prepare_for_master

This commit is contained in:
wgzAIIT 2022-12-09 12:04:06 +08:00
commit 342d925c0f
114 changed files with 11042 additions and 1653 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)
******************************************************************************/

View File

@ -0,0 +1,36 @@
menu "TableStorage"
config TABLE_STORAGE
bool "Using Table storage system"
default n
if TABLE_STORAGE
config TABLE_STORAGE_BASIC
bool "Enable TableStorage Basic"
default y
config TABLE_STORAGE_QUERY
bool "[System-level] Enable TableStorage Buffer"
default n
config TABLE_STORAGE_CACHE
bool "[System-level] Enable TableStorage Prefetcher"
default n
config TABLE_STORAGE_PREFETCH
bool "[Table-level] Enable TableStorage Query Cache"
default n
config TABLE_STORAGE_SECOND_INDEX
bool "[Table-level] Enable TableStorage Second Index"
default n
config TABLE_STORAGE_TRANSACTION
bool "(Other) Enable TableStorage Transaction"
default n
endif
endmenu

View File

@ -0,0 +1,153 @@
## README
TableStorage是一款面向泛在操作系统的轻量级表存储原型系统。TableStorage专注于泛在操作系统场景下结构化数据的存储与传统的多层堆叠式软件栈数据库 + 文件系统不同TableStorage避免过度分层从存储全栈角度进行跨层数据库的存储引擎 + 文件系统)的设计,主要包含以下三个属性
- 低冗余:去除文件抽象并直接将“表”存储到设备中, 避免功能冗余和不必要的软件开销
- 兼容性提供一组通用的API 以支持表级的存取操作,与传统数据库中的读写操作兼容
- 可集成:支持组件的深度集成,具体来说, 可以集成事务和执行引擎以满足复杂的事务和查询处理需求
### 开发板
- K210最小系统板Max bit
- SD卡配置
| 引脚 | 作用 | RW007板子 |
| :----------------: | :-------: | :-------: |
| io 27(印丝标注SCK) | SPI1_SCK | SCK |
| io 26(印丝标注SO) | SPI1_MISO | MISO |
| io 28(印丝标注SI) | SPI1_MOSI | MOSI |
| io 29 | CS/BOOT1 | CS |
### 编译说明
- 环境搭建
- 参考https://gitlink.org.cn/xuos/xiuos/tree/prepare_for_master/Ubiquitous%2FXiZi_IIoT%2Fboard%2Fkd233下的**开发环境搭建**小节搭建好XiUOS的开发环境
- 参考https://gitlink.org.cn/xuos/xiuos/tree/prepare_for_master/Ubiquitous%2FRT-Thread_Fusion_XiUOS%2Faiit_board%2Fk210搭建好XiUOS-RTThread的开发环境
- 配置XiUOS-RTThread基本环境
- SD卡的配置按照上表SD卡引脚说明配置
<img src="pic/image-20221123215723700.png" alt="image-20221123215723700" style="zoom: 33%;" />
- 其他推荐配置
<img src="pic/image-20221123215509060.png" alt="image-20221123215509060" style="zoom: 50%;" />
- (可选)如果编译时,出现定时器错误,则可以选择使用软件定时器
<img src="pic/image-20221123215939427.png" alt="image-20221123215939427" style="zoom: 33%;" />
- 配置TableStorage
```shell
scons --menuconfig
```
- 若不开启TableStorage组件则自动在SD卡上使用FATFS
- 若开启TableStorage组件则在SD卡上使用TableStorage默认打开了Enable TableStorage Basic模块当前版本仅支持Basic模块
<img src="pic/image-20221123213344406.png" alt="image-20221123213344406" style="zoom: 33%;" />
- 执行 scons 编译若编译正确无误在当前文件夹下生成rtthread.elf、rtthread.bin。其中rtthread.bin需要烧写到设备中进行运行
- 烧录及运行结果图
```shell
sudo kflash -t rtthread.bin -p /dev/ttyUSB0
```
- 烧录并运行无误,则
<img src="pic/image-20221123215143184.png" alt="image-20221123215143184" style="zoom: 33%;" />
### 调试
- 修改k210/rtconfig.py中的BUILD选项来配置debug模式并重新编译
- 安装openocd下载ubuntu版本64位
- 下载地址:[Releases · kendryte/openocd-kendryte (github.com)](https://github.com/kendryte/openocd-kendryte/releases),推荐下载地址为http://101.36.126.201:8011/kendryte-openocd-0.2.3-ubuntu64.tar.gz
- 安装
```shell
sudo apt install libusb-dev libftdi-dev libhidapi-dev
sudo mv kendryte-openocd-0.2.3-ubuntu64.tar.gz /opt
cd /opt
sudo tar -zxvf kendryte-openocd-0.2.3-ubuntu64.tar.gz
```
- 修改配置文件
sudo vim /opt/kendryte-openocd/tcl/k210.cfg并复制以下内容
```shell
# SiPEED USB-JTAG/TTL
interface ftdi
ftdi_device_desc "Dual RS232"
ftdi_vid_pid 0x0403 0x6010
ftdi_layout_init 0x0508 0x0f1b
ftdi_layout_signal nTRST -data 0x0200 -noe 0x0100
ftdi_layout_signal nSRST -data 0x0800 -noe 0x0400
jtag_rclk 3000
# server port
gdb_port 9999
telnet_port 4444
# add cpu target
set _CHIPNAME riscv
jtag newtap $_CHIPNAME cpu -irlen 5 -expected-id 0x04e4796b
set _TARGETNAME $_CHIPNAME.cpu
target create $_TARGETNAME riscv -chain-position $_TARGETNAME
# command
init
if {[ info exists pulse_srst]} {
ftdi_set_signal nSRST 0
ftdi_set_signal nSRST 1
ftdi_set_signal nSRST z
}
halt
```
- 调试器和Max bit开发板的硬件连线
<img src="pic/image-20221123220234259.png" alt="image-20221123220234259" style="zoom: 33%;" />
- 启动调试器
```shell
sudo /opt/kendryte-openocd/bin/openocd -f /opt/kendryte-openocd/tcl/k210.cfg
```
<img src="pic/image-20221123221828637.png" alt="image-20221123221828637" style="zoom: 33%;" />
- 在Ubiquitous/RT-Thread_Fusion_XiUOS/aiit_board/k210目录下连接调试器
```shell
/opt/xpack-riscv-none-embed-gcc-10.2.0-1.2/bin/riscv-none-embed-gdb rtthread.elf --eval-command="target remote 127.0.0.1:9999"
```
- gdb终端调试
<img src="pic/image-20221123222125802.png" alt="image-20221123222125802" style="zoom: 33%;" />
<img src="pic/image-20221123223127817.png" alt="image-20221123223127817" style="zoom:33%;" />
- vscode调试
<img src="pic/image-20221123225705614.png" alt="image-20221123225705614" style="zoom:33%;" />

View File

@ -0,0 +1,26 @@
from building import *
# get current directory
cwd = GetCurrentDir()
# the set of source files associated with this SConscript file.
src = Glob('src/common/*.cc')
src += Glob('src/execution/*.cc')
src += Glob('src/storage/*.cc')
# compile optional modules
if GetDepend(['TABLE_STORAGE_CACHE']):
src += ['src/modules/prefetcher.cc']
if GetDepend(['TABLE_STORAGE_CACHE']):
src += ['src/modules/queryCache.cc']
if GetDepend(['TABLE_STORAGE_CACHE']):
src += ['src/modules/buffer.cc']
if GetDepend(['TABLE_STORAGE_CACHE']):
src += ['src/modules/secondIndex.cc']
# include path
path = [cwd + '/include']
group = DefineGroup('TableStorage', src, depend = ['TABLE_STORAGE'], CPPPATH = path)
Return('group')

View File

@ -0,0 +1,35 @@
/**
* @file BufferItem.h
* @brief BufferItem
* @version 0.1
* @author SYS Lab
* @date 2022.11.01
*/
#ifndef BUFFERITEM_H
#define BUFFERITEM_H
#include <stdint.h>
#include "Common.h"
namespace LightTable {
class BufferItem {
public:
BufferItem(uint64_t tableID);
virtual ~BufferItem();
// virtual void flush() const = 0;
uint64_t getTableID() { return tableID; }
protected:
uint64_t tableID;
DISALLOW_COPY_AND_ASSIGN(BufferItem);
};
} // namespace LightTable
#endif // BUFFERITEM_H

View File

@ -0,0 +1,144 @@
/**
* @file Common.h
* @brief parameter configuration
* @version 0.1
* @author SYS Lab
* @date 2022.11.01
*/
#ifndef COMMON_H
#define COMMON_H
#include <rtconfig.h>
#include <time.h>
#include <chrono>
#include <queue>
namespace LightTable {
#define YCSB_TEST
extern int cacheReadNum;
extern int cacheWriteNum;
extern std::chrono::steady_clock::time_point start_time;
extern std::chrono::steady_clock::time_point end_time;
extern double diff_sdcard_read;
extern double diff_sdcard_write;
#define SYSTEM_MAX_CORES 0
#define SYSTEM_MAX_IO_QUEUES 8
#ifndef YCSB_TEST
#define NETWORK_MESSAGE_DATA_MAX_SIZE 4088
#define NETWORK_TRANSMIT_MAX_SIZE 4096
#else
#define NETWORK_MESSAGE_DATA_MAX_SIZE 51192
#define NETWORK_TRANSMIT_MAX_SIZE 51200
#endif
#define SDCARD_TEST_WRITE_BLOCKID 200
#define SDCARD_TEST_READ_BLOCKID 1000
#define SDCARD_TEST_NUM 10000
#define HASH_BUCKET_SIZE 50
#define CACHE_SIZE 500
#define SEGMENT_TYPE_SMALL_BITMAP_SIZE 32768
#define SEGMENT_TYPE_MEDIUM_BITMAP_SIZE 4096
#ifndef YCSB_TEST
#define SEGMENT_TYPE_BIG_BITMAP_SIZE 512
#else
#define SEGMENT_TYPE_BIG_BITMAP_SIZE 512
#endif
#define SEGMENT_TYPE_SMALL_START 64
#define SEGMENT_TYPE_MEDIUM_START 2097216
#define SEGMENT_TYPE_BIG_START 6291528
#define SEGMENT_TYPE_SMALL_CELL_SIZE 4096
#define SEGMENT_TYPE_MEDIUM_CELL_SIZE 65536
#ifndef YCSB_TEST
#define SEGMENT_TYPE_BIG_CELL_SIZE 2097152
#else
#define SEGMENT_TYPE_BIG_CELL_SIZE 65536000
#endif
#define PREFETCH_BLOCK_SERIALIZED_LENGTH 33
#define MAX_BRANCH_COUNT 4
#define PRELOAD_BLOCK_COUNT 10
#define PRELOAD_CHECK_INTERVAL_US 50
#define BLOCK_SIZE 512
#ifndef YCSB_TEST
#define BUFFER_SIZE 200
#else
#define BUFFER_SIZE 300000
#endif
#define CACHED_PAGE_COUNT 100
#define ROOTTABLE_TUPLE_SIZE sizeof(RootTable::TableTuple)
#define TABLE_ID_SIZE sizeof(uint64_t)
#define SYSTEM_TABLE_COUNT 1
#define ROOTTABLE_TABLE_ID 1
#define ROOTTABLE_SEGMENT_ID 1
#define ROOTTABLE_FIRST_BLOCK_ID 14680164
#define TABLE1_META_BLOCKID 1000
#define TABLE1_META_LOG_BLOCKID 10000
#define TABLE1_INDEX_BLOCKID 2000
#define TABLE1_INDEX_LOG_BLOCKID 20000
#define TABLE1_DATA_LOG_BLOCKID 30000
#define META_ENTRY_NUM 8
#define META_ENTRY_SIZE 64
#define BUFFER_MAX 4096
#define COMMON_TABLE_START_ID 101
#define YCSB_TABLE_ID 100
#define TABLE_NAME_LENGTH 32
#define PRIMARY_KEY_LENGTH 128
#define FILE_PATH_LENGTH 1024
#define FILE_NAME_LENGTH 128
#define USER_NAME_LENGTH 32
#define COLUMN_NAME_LENGTH 128
#define COLUMN_TYPE_NAME_LENGTH 32
#define PREFETCH_BLOCK_SERIALIZED_LENGTH 33
#define ROWMAP_SERIALIZED_LENGTH 42
#define SCHEMA_ENTRY_SERIALIZED_LENGTH 181
#define MAX_META_LENGTH 2048
#define MAX_PATH_LENGTH 128
const char METAPATH[MAX_PATH_LENGTH] = "../../data";
struct timespec diff(struct timespec start, struct timespec end);
class Queue {
public:
#ifdef IO_PROFILING
static struct timespec accumulate_io_times();
static struct timespec accumulate_io_submit_times();
#endif
#ifdef IO_PROFILING
static std::queue<struct timespec> io_times;
static std::queue<struct timespec> io_submit_times;
#endif
};
// A macro to disallow the copy constructor and operator= functions
#ifndef DISALLOW_COPY_AND_ASSIGN
#define DISALLOW_COPY_AND_ASSIGN(TypeName) \
TypeName(const TypeName &) = delete; \
TypeName &operator=(const TypeName &) = delete;
#endif
} // namespace LightTable
#endif // COMMON_H

View File

@ -0,0 +1,35 @@
/**
* @file CommonTable.h
* @brief CommonTable
* @version 0.1
* @author SYS Lab
* @date 2022.11.01
*/
#ifndef COMMONTABLE_H
#define COMMONTABLE_H
#include "Table.h"
namespace LightTable {
class CommonTable : public Table {
public:
CommonTable(uint64_t tableID, const char *tableName, uint64_t firstBlockID,
uint64_t segmentID, SegmentType segmentType,
std::vector<Schema::SchemaEntry> schemaEntrys,
bool usePrimaryKeyIndex = false);
CommonTable(uint64_t tableID, const char *tableName, uint64_t firstBlockID,
uint64_t segmentID, SegmentType segmentType,
bool usePrimaryKeyIndex = false);
friend class MetaHandle;
protected:
DISALLOW_COPY_AND_ASSIGN(CommonTable);
};
} // namespace LightTable
#endif // COMMONTABLE_H

View File

@ -0,0 +1,61 @@
/**
* @file Driver.h
* @brief driver
* @version 0.1
* @author SYS Lab
* @date 2022.11.01
*/
#ifndef DRIVER_H
#define DRIVER_H
#include <stdint.h>
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
#include <time.h>
#include <atomic>
#include <iostream>
#include <thread>
#include "Common.h"
#include "Error.h"
// #include <mutex>
// #include <pthread.h>
// #include <condition_variable>
#ifdef __cplusplus
extern "C" {
#endif
uint32_t MakeTableStorage(const char *device_name);
#ifdef __cplusplus
}
#endif
namespace LightTable {
class Driver {
public:
static uint32_t driver_init(const char *device_name);
static void driver_cleanup(const char *device_name);
static uint32_t driver_read(uint8_t *buf, uint64_t blockID);
static uint32_t driver_write(uint8_t *buf, uint64_t blockID);
static uint32_t read(uint8_t *buf, uint64_t blockID);
static uint32_t write(uint8_t *buf, uint64_t blockID);
Driver(){};
#ifdef TABLE_STORAGE_CACHE
static BlockCache *blkCache;
#endif
};
} // namespace LightTable
#endif // DRIVER_H

View File

@ -0,0 +1,62 @@
/**
* @file Error.h
* @brief error number
* @version 0.1
* @author SYS Lab
* @date 2022.11.01
*/
#ifndef ERROR_H
#define ERROR_H
namespace LightTable {
enum ErrorCode {
SUCCESS = 0,
ERROR_TABLE = 1,
SEGMENT_TYPE_ERROR = 2,
SEGMENT_STATUS_ERROR = 3,
SEGMENT_IS_EXHAUSTED = 4,
BUCKET_ITEM_NOT_FOUND = 5,
ADD_BUCKET_ITEM_ERROR = 6,
PREFETCH_BLOCK_NOT_FOUND = 7,
GET_AVAILABLE_BLOCK_ERROR = 8,
BLOCK_OCCUPIED = 9,
ADD_ROW_MAP_ENTRY_ERROR = 10,
ROW_MAP_ENTRY_NOT_FOUND = 11,
ADD_SCHEMA_ENTRY_ERROR = 12,
SCHEMA_ENTRY_NOT_FOUND = 13,
COLUMN_ITEM_NOT_FOUND = 14,
COLUMN_ID_NOT_CONTINUOUS = 15,
DELETE_PARIMARY_KEY_COLUMN = 16,
TABLE_NOT_FOUND = 17,
TABLE_TUPLE_NOT_FOUND = 18,
ADD_TABLE_TUPLE_ERROR = 19,
BUFFER_EMPTY = 20,
TYPE_INVALID = 21,
ROWLOCATION_INVALID = 22,
CREATE_SOCKET_ERROR = 23,
INET_PTON_ERROR = 24,
BIND_SOCKET_ERROR = 25,
LISTEN_SOCKET_ERROR = 26,
ACCEPT_SOCKET_ERROR = 27,
CONNECT_SOCKET_ERROR = 28,
SEND_MESSAGE_ERROR = 29,
EVENT_TYPE_NOT_DEFINED = 30,
SCHEMA_NOT_EXIST = 31,
OPEN_META_FILE_ERROR = 32,
INVALID_META_FILE = 33,
INVALID_MEMORY_BLOCK_ID = 34,
UPDATE_TUPLE_ERROR = 35,
INVALID_PAGE_ID = 36,
ADD_QUERY_CACHE_ERROR = 37,
TRIE_LEAF_EXIST = 38,
TRIE_LEAF_NOT_EXIST = 39,
TRIE_LEAF_NOT_FOUND = 40,
INVALID_SCAN_RANGE = 41,
INVALID_PRELOAD_TASK = 42,
};
} // namespace LightTable
#endif // ERROR_H

View File

@ -0,0 +1,59 @@
/**
* @file HashBucket.h
* @brief HashBucket
* @version 0.1
* @author SYS Lab
* @date 2022.11.01
*/
#ifndef HASHBUCKET_H
#define HASHBUCKET_H
#include <stdint.h>
// #include <pthread.h>
#include <algorithm>
#include <map>
#include <iostream>
#include <utility>
// #include <mutex>
#include "Common.h"
#include "Error.h"
namespace LightTable {
typedef struct rowLocation {
uint64_t blockID;
uint64_t rowOffset;
} RowLocation;
class HashBucket {
public:
HashBucket();
uint32_t addBucketItem(uint64_t key, RowLocation rowLocation);
uint32_t deleteBucketItem(uint64_t key);
uint32_t updateRowLocation(uint64_t key, RowLocation rowLocation);
uint32_t getRowLocation(uint64_t key, RowLocation &rowLocation);
uint64_t getBucketSize();
uint32_t setBucketSize(uint64_t bucketSize);
uint32_t getAllBucketItems(std::map<uint64_t, RowLocation> &bucketItems);
private:
std::map<uint64_t, RowLocation> bucketItems;
uint64_t bucketSize;
// pthread_mutex_t mtx;
DISALLOW_COPY_AND_ASSIGN(HashBucket);
};
} // namespace LightTable
#endif // HASHBUCKET_H

View File

@ -0,0 +1,63 @@
/**
* @file HashTable.h
* @brief HashTable
* @version 0.1
* @author SYS Lab
* @date 2022.11.01
*/
#ifndef HASHTABLE_H
#define HASHTABLE_H
#include <stdint.h>
#include <algorithm>
#include <vector>
#include <iostream>
#include <string>
#include "Common.h"
#include "HashBucket.h"
namespace LightTable {
class HashTable {
public:
HashTable();
~HashTable();
uint64_t getMapKey(const char *primaryKey);
uint32_t hashToBucket(uint64_t key);
uint32_t getRowLocation(uint32_t bucketID, uint64_t key,
RowLocation &rowLocation);
uint32_t addItem(uint32_t bucketID, uint64_t key, RowLocation rowLocation);
uint32_t deleteItem(uint32_t bucketID, uint64_t key);
uint32_t updateItem(uint32_t bucketID, uint64_t key, RowLocation rowLocation);
uint64_t getItemCount();
uint32_t getAllBuckets(std::vector<HashBucket *> &buckets);
uint32_t refreshRowLocations(uint64_t blockID, uint64_t deleteOffset,
uint64_t rowSize,
std::map<uint64_t, RowLocation> &locationItems);
uint32_t clear();
private:
std::vector<HashBucket *> buckets;
DISALLOW_COPY_AND_ASSIGN(HashTable);
public:
friend class MetaHandle;
};
} // namespace LightTable
#endif // HASHTABLE_H

View File

@ -0,0 +1,101 @@
/**
* @file PrefetchBlockManager.h
* @brief PrefetchBlockManager
* @version 0.1
* @author SYS Lab
* @date 2022.11.01
*/
#ifndef PREFETCHBLOCKMANAGER_H
#define PREFETCHBLOCKMANAGER_H
#include <stdint.h>
#include <time.h>
#include <stdlib.h>
// #include <pthread.h>
#include <map>
#include <iostream>
#include <algorithm>
#include <chrono>
#include <utility>
// #include <mutex>
#include "Error.h"
#include "Common.h"
#include "SegmentManager.h"
namespace LightTable
{
enum PrefetchBlockStatus
{
PREFETCH_BLOCK_STATUS_IDLE = 0,
PREFETCH_BLOCK_STATUS_BUSY,
};
class PrefetchBlockManager
{
public:
typedef struct prefetchBlockManagerEntry
{
uint64_t blockID;
uint64_t currentOffset;
bool isOccupied;
bool isCached;
uint64_t pageID;
}PrefetchBlockManagerEntry;
PrefetchBlockManager(uint64_t firstBlockID, uint64_t segmentID,
SegmentType segmentType);
~PrefetchBlockManager();
uint64_t blockAllocate(uint64_t rowSize);
uint64_t getNextBlock();
uint32_t setBlockState(uint64_t blockID, bool isOccupied);
uint32_t setOffset(uint64_t blockID, uint64_t currentOffset);
uint32_t getOffset(uint64_t blockID, uint64_t &currentOffset);
uint32_t advanceOffset(uint64_t blockID, uint64_t rowSize);
uint32_t isOccupied(uint64_t blockID, bool &status);
uint32_t getPrefetchBlockEntry(uint64_t blockID,
PrefetchBlockManagerEntry &entry);
uint32_t getAllPrefetchBlockEntrys(std::map<uint64_t,
PrefetchBlockManagerEntry> &entrys);
uint32_t lockBlock(uint64_t blockID);
uint32_t unlockBlock(uint64_t blockID);
uint32_t setIsCached(uint64_t blockID, bool isCached, uint64_t pageID);
bool isCached(uint64_t blockID, uint64_t &pageID);
private:
std::map<uint64_t, PrefetchBlockManagerEntry> prefetchBlocks;
const uint64_t segmentID;
const SegmentType segmentType;
const uint64_t firstBlockID;
uint64_t blockCount;
uint64_t currentID;
DISALLOW_COPY_AND_ASSIGN(PrefetchBlockManager);
public:
friend class QueryCache;
friend class MetaHandle;
};
} // namespace LightTable
#endif // PREFETCHBLOCKMANAGER_H

View File

@ -0,0 +1,57 @@
/**
* @file RWLock.h
* @brief RWLock
* @version 0.1
* @author SYS Lab
* @date 2022.11.01
*/
#ifndef RWLOCK_H
#define RWLOCK_H
#include <stdint.h>
#include <stdio.h>
#include <atomic>
namespace LightTable {
using version_lock_t = uint8_t;
#define LOAD_ORDER std::memory_order_acquire
#define STORE_ORDER std::memory_order_release
static_assert(sizeof(version_lock_t) == 1, "Lock must be 1 byte.");
static constexpr version_lock_t CLIENT_BIT = 0b10000000;
static constexpr version_lock_t NO_CLIENT_BIT = 0b01111111;
static constexpr version_lock_t USED_BIT = 0b01000000;
static constexpr version_lock_t UNLOCKED_BIT = 0b11111110;
#define IS_LOCKED(lock) ((lock)&1)
class RWLock {
std::atomic<version_lock_t> version_lock;
public:
bool lock(const bool blocking = true) {
version_lock_t lock_value = version_lock.load(LOAD_ORDER);
// Compare and swap until we are the thread to set the lock bit
lock_value &= UNLOCKED_BIT;
while (!version_lock.compare_exchange_weak(lock_value, lock_value + 1)) {
lock_value &= UNLOCKED_BIT;
if (!blocking) {
return false;
}
}
return true;
}
void unlock() {
const version_lock_t current_version = version_lock.load(LOAD_ORDER);
version_lock_t new_version = (current_version + 1) % USED_BIT;
new_version |= USED_BIT;
new_version |= (current_version & CLIENT_BIT);
version_lock.store(new_version, STORE_ORDER);
}
};
} // namespace LightTable
#endif // HASHTABLE_H

View File

@ -0,0 +1,75 @@
/**
* @file RootTable.h
* @brief RootTable
* @version 0.1
* @author SYS Lab
* @date 2022.11.01
*/
#ifndef ROOTTABLE_H
#define ROOTTABLE_H
#include <stddef.h>
#include <time.h>
#include <algorithm>
#include <iostream>
#include <map>
#include "Common.h"
#include "SystemTable.h"
namespace LightTable {
class Buffer;
class RootTable : public SystemTable {
public:
typedef struct tableTuple {
uint64_t tableID;
char tableName[TABLE_NAME_LENGTH];
uint64_t firstBlockID;
uint64_t segmentID;
SegmentType segmentType;
char user[USER_NAME_LENGTH];
struct tm time;
} TableTuple;
RootTable(std::vector<Schema::SchemaEntry> schemaEntrys,
bool usePrimaryKeyIndex)
: SystemTable(ROOTTABLE_TABLE_ID, "RootTable", ROOTTABLE_FIRST_BLOCK_ID,
ROOTTABLE_SEGMENT_ID, SEGMENT_TYPE_BIG, schemaEntrys,
usePrimaryKeyIndex) {}
RootTable(bool usePrimaryKeyIndex = false);
uint32_t tableNameToTableID(const char *tableName, uint64_t &tableID);
uint32_t deleteTableInfo(uint64_t tableID);
uint32_t appendTableInfo(TableTuple tableTuple);
uint32_t getTableInfo(uint64_t tableID, TableTuple &tableTupleResult);
uint32_t modifyTableInfo(uint64_t tableID, TableTuple tableTuple);
uint32_t getTableTuple(uint64_t tableID, TableTuple &tableTuple);
uint32_t serializeRow(const TableTuple tableTuple, uint8_t *buf);
uint32_t deserializeRow(const uint8_t *buf, TableTuple *tableTuple);
uint64_t getTableCount();
private:
std::map<uint64_t, TableTuple> tableTupleMap;
DISALLOW_COPY_AND_ASSIGN(RootTable);
public:
friend class MetaHandle;
};
} // namespace LightTable
#endif // ROOTTABLE_H

View File

@ -0,0 +1,57 @@
/**
* @file RowMap.h
* @brief
* @version 0.1
* @author SYS Lab
* @date 2022.11.01
*/
#ifndef ROWMAP_H
#define ROWMAP_H
#include <stdint.h>
#include <algorithm>
#include <iostream>
#include <map>
#include <string>
#include "Common.h"
#include "Error.h"
namespace LightTable {
class RowMap {
public:
typedef struct rowMapEntry {
uint64_t key;
uint64_t blockID;
uint64_t rowOffset;
} RowMapEntry;
RowMap();
uint32_t appendEntry(uint64_t key, uint64_t blockID, uint64_t rowOffset);
uint32_t deleteEntry(uint64_t key);
uint32_t alterEntry(uint64_t key, uint64_t blockID, uint64_t rowOffset);
uint32_t queryEntry(uint64_t key, RowMapEntry &rowMapEntry);
uint32_t queryAllEntry(std::map<uint64_t, RowMapEntry> &allRowMapEntrys);
uint64_t getRowCount();
private:
std::map<uint64_t, RowMapEntry> rowMapEntrys;
DISALLOW_COPY_AND_ASSIGN(RowMap);
public:
friend class MetaHandle;
};
} // namespace LightTable
#endif // ROWMAP_H

View File

@ -0,0 +1,92 @@
/**
* @file Schema.h
* @brief table schema
* @version 0.1
* @author SYS Lab
* @date 2022.11.01
*/
#ifndef SCHEMA_H
#define SCHEMA_H
#include <stdint.h>
#include <string.h>
#include <algorithm>
#include <iostream>
#include <map>
#include <string>
#include "Common.h"
#include "Error.h"
namespace LightTable {
class Schema {
public:
typedef struct schemaEntry {
uint64_t columnID;
char columnName[COLUMN_NAME_LENGTH];
char type[COLUMN_TYPE_NAME_LENGTH];
uint32_t length;
bool isPrimaryKey;
bool isEmpty;
schemaEntry &operator=(schemaEntry &another) {
this->columnID = another.columnID;
memcpy(this->columnName, another.columnName, COLUMN_NAME_LENGTH);
memcpy(this->type, another.type, COLUMN_TYPE_NAME_LENGTH);
this->length = another.length;
this->isPrimaryKey = another.isPrimaryKey;
this->isEmpty = another.isEmpty;
return *this;
}
} SchemaEntry;
Schema();
Schema(std::vector<SchemaEntry> schemaEntrys);
uint32_t appendEntry(SchemaEntry &schemaEntry);
uint32_t deleteEntry(uint64_t columnID);
uint32_t alterEntry(uint64_t columnID, SchemaEntry schemaEntry);
uint32_t getColumnID(const char *columnName, uint64_t &columnID);
uint32_t queryEntry(uint64_t columnID, Schema::SchemaEntry &schemaEntry);
uint32_t queryAllEntry(std::map<uint64_t, SchemaEntry> &allSchemaEntrys);
uint64_t getEntrySize();
void setEntrySize(uint64_t entrySize);
uint32_t getPrimaryKeyLength();
uint64_t getColumnCount();
void setColumnCount(uint64_t columnCount);
Schema::SchemaEntry &getPrimaryKeySchema();
uint32_t drop();
private:
std::map<uint64_t, SchemaEntry> schemaEntrys;
SchemaEntry primaryKeySchema;
uint64_t columnCount;
uint64_t entrySize;
DISALLOW_COPY_AND_ASSIGN(Schema);
public:
friend class MetaHandle;
};
} // namespace LightTable
#endif // SCHEMA_H

View File

@ -0,0 +1,59 @@
/**
* @file SegmentManager.h
* @brief SegmentManager
* @version 0.1
* @author SYS Lab
* @date 2022.11.01
*/
#ifndef SEGMENTMANAGER_H
#define SEGMENTMANAGER_H
#include <stdint.h>
#include "Common.h"
#include "Error.h"
#include "Driver.h"
#include "Common.h"
namespace LightTable {
enum SegmentType {
SEGMENT_TYPE_SMALL = 101,
SEGMENT_TYPE_MEDIUM,
SEGMENT_TYPE_BIG,
};
enum SegmentStatus {
SEGMENT_STATUS_IDLE = 0,
SEGMENT_STATUS_BUSY,
};
class SegmentManager {
public:
SegmentManager();
~SegmentManager();
uint32_t setBitmap(SegmentType segmentType, uint64_t segmentID,
SegmentStatus segmentStatus);
uint32_t getIdleSegment(SegmentType segmentType, uint64_t &segmentID,
uint64_t &firstBlockID);
private:
uint32_t setBit(uint64_t segmentID, uint8_t *buf, uint64_t segmentStart,
SegmentStatus segmentStatus);
uint32_t findFirstIdle(uint8_t *buf, uint64_t segmentNum,
uint64_t &segmentID);
uint8_t *bigBitmap;
uint8_t *mediumBitmap;
uint8_t *smallBitmap;
DISALLOW_COPY_AND_ASSIGN(SegmentManager);
};
} // namespace LightTable
#endif // SEGMENTMANAGER_H

View File

@ -0,0 +1,33 @@
/**
* @file SystemTable.h
* @brief SystemTable
* @version 0.1
* @author SYS Lab
* @date 2022.11.01
*/
#ifndef SYSTEMTABLE_H
#define SYSTEMTABLE_H
#include "Table.h"
namespace LightTable {
class SystemTable : public Table {
public:
SystemTable(uint64_t tableID, const char *tableName, uint64_t firstBlockID,
uint64_t segmentID, SegmentType segmentType,
std::vector<Schema::SchemaEntry> schemaEntrys,
bool usePrimaryKeyIndex);
SystemTable(uint64_t tableID, const char *tableName, uint64_t firstBlockID,
uint64_t segmentID, SegmentType segmentType,
bool usePrimaryKeyIndex);
protected:
DISALLOW_COPY_AND_ASSIGN(SystemTable);
};
} // namespace LightTable
#endif // SYSTEMTABLE_H

View File

@ -0,0 +1,147 @@
/**
* @file Table.h
* @brief Table
* @version 0.1
* @author SYS Lab
* @date 2022.11.01
*/
#ifndef TABLE_H
#define TABLE_H
#include <stdint.h>
#include <string.h>
#include <stddef.h>
#include <algorithm>
#include <ctime>
#include <iostream>
#include <queue>
#include <string>
#include <vector>
#include "Common.h"
#include "HashTable.h"
#include "RowMap.h"
#include "Schema.h"
#include "Driver.h"
#include "UndoLogEntry.h"
#include "SegmentManager.h"
#include "PrefetchBlockManager.h"
namespace LightTable {
#ifdef TABLE_STORAGE_SECOND_INDEX
// TODO: second index
#endif
class Buffer;
class Table {
typedef struct currentLocation {
uint64_t blockID;
int32_t emptySlotNum;
} currentLocation;
typedef struct metaLogEntry {
uint64_t tableID;
uint64_t tupleNum;
std::time_t t;
} metaLogEntry;
public:
Table(uint64_t tableID, const char *tableName, uint64_t firstBlockID,
uint64_t segmentID, SegmentType segmentType,
std::vector<Schema::SchemaEntry> schemaEntrys,
bool usePrimaryKeyIndex = false);
Table(uint64_t tableID, const char *tableName, uint64_t firstBlockID,
uint64_t segmentID, SegmentType segmentType,
bool usePrimaryKeyIndex = false);
uint32_t drop();
uint32_t truncate();
uint32_t insertRow(const uint8_t *rowData);
uint32_t insertRow_logging(const uint8_t *rowData);
uint32_t deleteRow(const char *primaryKey);
uint32_t updateRow(const char *primaryKey, const uint8_t *rowData);
uint32_t updateColumnItem(const char *primaryKey, const char *columnName,
const uint8_t *columnData);
uint32_t updateColumnItem_logging(const char *primaryKey,
const char *columnName,
const uint8_t *columnData);
uint32_t selectRow(const char *primaryKey, uint8_t *rowData);
uint32_t selectColumnItem(const char *primaryKey, const char *columnName,
uint8_t *columnData);
uint64_t getRowCount();
uint64_t getTableID();
char *getTableName();
uint32_t setTableID(uint64_t tableID);
uint32_t setTableName(const char *tableName);
Schema &getSchema();
HashTable &getHashTable();
protected:
uint32_t getColumnID(const char *columnName, uint64_t &columnID);
uint32_t parsePrimaryKey(const uint8_t *rowData, char *primaryKeyData);
uint32_t locateRow(const char *primaryKey, RowLocation &rowLocation);
uint32_t getRowFromBlock(const char *primaryKey, uint8_t *rowData,
const uint8_t *blockData,
const RowLocation rowLocation);
uint32_t selectRow(const char *primaryKey, uint8_t *rowData,
RowLocation &rowLocation);
uint32_t deleteRowData(uint64_t key, RowLocation rowLocation);
uint32_t getColumnOffset(const char *columnName, uint64_t &columnID,
uint32_t &columnLength, uint64_t &offset);
uint64_t tableID;
char tableName[TABLE_NAME_LENGTH];
Schema schema;
RowMap rowMap;
HashTable hashTable;
bool usePrimaryKeyIndex;
uint64_t tupleNum;
std::time_t t;
currentLocation indexLocation;
currentLocation metaLogLocation;
currentLocation indexLogLocation;
currentLocation dataLogLocation;
uint8_t indexData[BLOCK_SIZE];
uint8_t metaData[BLOCK_SIZE];
uint8_t metaLog[BLOCK_SIZE];
uint8_t indexLog[BLOCK_SIZE];
uint8_t dataLog[BLOCK_SIZE];
PrefetchBlockManager prefetchBlockManager;
DISALLOW_COPY_AND_ASSIGN(Table);
public:
friend class DaemonProcess;
friend class MetaHandle;
friend class QueryCache;
};
} // namespace LightTable
#endif // TABLE_H

View File

@ -0,0 +1,145 @@
/**
* @file TableStorage.h
* @brief TableStorage
* @version 0.1
* @author SYS Lab
* @date 2022.11.01
*/
#ifndef DAEMONPROCESS_H
#define DAEMONPROCESS_H
#include <stdint.h>
#include <stdio.h>
#include <time.h>
#include <errno.h>
#include <stdlib.h>
#include <string.h>
#include <unistd.h>
#include <algorithm>
#include <map>
#include <iomanip>
#include <iostream>
#include <thread>
// #include <sys/types.h>
// #include <sys/socket.h>
// #include <arpa/inet.h>
// #include <netinet/in.h>
// #include <netinet/tcp.h>
#include "RootTable.h"
#include "SegmentManager.h"
#include "Common.h"
#include "CommonTable.h"
#include "Error.h"
#include "Driver.h"
#include "Table.h"
#define TABLE_DEBUG_ENABLE
#define PROJECT_NAME "TanleStorage"
#ifndef TABLE_PRINT
#define TABLE_PRINT(...) printf(__VA_ARGS__)
#endif
#define TABLE_LOG_PREFIX1() \
TABLE_PRINT("[\e[1;34m%s\033[0m] \e[1;31m%s\033[0m", PROJECT_NAME, \
__FUNCTION__)
#define TABLE_LOG_PREFIX2() TABLE_PRINT(" ")
#define TABLE_LOG_PREFIX() \
TABLE_LOG_PREFIX1(); \
TABLE_LOG_PREFIX2()
#ifdef TABLE_DEBUG_ENABLE
#define TABLE_DEBUG(...) \
TABLE_LOG_PREFIX(); \
TABLE_PRINT("(\e[1;32m%s:%d\033[0m) ", __FILE__, __LINE__); \
TABLE_PRINT(__VA_ARGS__)
#else
#define TABLE_DEBUG(...)
#endif
namespace LightTable {
enum EventType {
CREATE_TABLE_EVENT = 10001,
INSERT_ROW_EVENT,
DELETE_ROW_EVENT,
SELECT_ROW_EVENT,
#ifdef YCSB_TEST
SCAN_EVENT,
#endif
UPDATE_ROW_EVENT,
#ifdef YCSB_TEST
UPDATE_COLUMNS_EVENT,
#endif
DROP_TABLE_EVENT,
RESPOND_CLIENT_REQUEST,
STOP_SERVICE_EVENT,
#ifdef YCSB_TEST
UNKNOWN_EVENT,
#endif
};
typedef struct message {
uint32_t size;
EventType eventType;
uint8_t data[NETWORK_MESSAGE_DATA_MAX_SIZE];
} Message;
class TableStorage {
public:
static TableStorage *getInstance(const char *ipAddress,
const uint32_t portNum,
const char *path = METAPATH) {
static TableStorage *daemonProcess;
// To determine whether the first call.
if (daemonProcess == NULL) {
daemonProcess = new TableStorage(ipAddress, portNum, path);
}
return daemonProcess;
}
uint32_t createTable(const char *tableName, SegmentType segmentType,
std::vector<Schema::SchemaEntry> &schema);
uint32_t dropTable(const char *tableName);
uint32_t insertTuple(const char *tableName, const uint8_t *row);
uint32_t deleteTuple(const char *tableName, const char *primaryKey);
uint32_t updateTuple(const char *tableName, const char *primaryKey,
const char *columnName, const uint8_t *value);
uint32_t selectTuple(const char *tableName, const char *primaryKey,
uint8_t *row);
uint32_t initTableStorage();
uint32_t closeTableStorage();
private:
TableStorage(const char *ipAddress, const uint32_t portNum, const char *path);
~TableStorage();
RootTable *rootTable;
std::map<uint64_t, Table *> tableMap;
SegmentManager *segmentManager;
const char *LightTableIPAddress;
const uint32_t LightTablePortNum;
// int32_t socketfd;
// MetaHandle metaHandle;
// Buffer *buf;
// QueryCache *queryCache;
// BlockPreload *blockPreload;
friend class Benchmark;
};
} // namespace LightTable
#endif // DAEMONPROCESS_H

View File

@ -0,0 +1,81 @@
/**
* @file ThreadSafeQueue.h
* @brief ThreadSafeQueue
* @version 0.1
* @author SYS Lab
* @date 2022.11.01
*/
#include <pthread.h>
#include <iostream>
#include "Common.h"
using namespace std;
namespace LightTable {
template <class object>
class ThreadSafeQueue {
private:
pthread_mutex_t m_lock;
int m_front;
int m_rear;
object m_data[BUFFER_SIZE];
public:
ThreadSafeQueue() : m_front(0), m_rear(0) {
pthread_mutex_init(&m_lock, NULL);
}
bool EnQueue(object data) {
pthread_mutex_lock(&m_lock);
if (isFull()) {
// cout<<"The queue is full!"<<endl;
pthread_mutex_unlock(&m_lock);
return false;
}
m_data[m_rear] = data;
m_rear = (m_rear + 1) % BUFFER_SIZE;
pthread_mutex_unlock(&m_lock);
return true;
}
bool DeQueue(object& data) {
pthread_mutex_lock(&m_lock);
if (isEmpty()) {
pthread_mutex_unlock(&m_lock);
return false;
}
data = m_data[m_front];
m_front = (m_front + 1) % BUFFER_SIZE;
pthread_mutex_unlock(&m_lock);
return true;
}
bool top(object& data) {
pthread_mutex_lock(&m_lock);
if (isEmpty()) {
pthread_mutex_unlock(&m_lock);
return false;
}
data = m_data[m_front];
pthread_mutex_unlock(&m_lock);
return true;
}
bool isFull() {
if ((m_rear + 1) % BUFFER_SIZE == m_front) return true;
return false;
}
bool isEmpty() {
if (m_rear == m_front) return true;
return false;
}
~ThreadSafeQueue() { pthread_mutex_destroy(&m_lock); }
};
} // namespace LightTable

View File

@ -0,0 +1,49 @@
/**
* @file UndoLogEntry.h
* @brief UndoLogEntry
* @version 0.1
* @author SYS Lab
* @date 2022.11.01
*/
#ifndef UNDOLOGENTRY_H
#define UNDOLOGENTRY_H
#include <stdint.h>
#include "BufferItem.h"
#include "Common.h"
#include "Error.h"
namespace LightTable {
class UndoLogEntry : public BufferItem {
public:
UndoLogEntry(uint64_t tableID, const char *primaryKey, uint64_t keySize,
char *tuple, uint64_t tupleSize, uint64_t blockID,
uint64_t offset);
static bool getIsExpired(UndoLogEntry *logEntry);
void expireUndoLog();
uint32_t getTuple(uint64_t tableID, const char *primaryKey, char *tuple,
uint64_t &blockID, uint64_t &offset);
char *getPrimaryKey();
~UndoLogEntry();
private:
char *tuple;
char *primaryKey;
uint64_t blockID;
uint64_t offset;
uint64_t tupleSize;
uint64_t keySize;
bool isExpired;
DISALLOW_COPY_AND_ASSIGN(UndoLogEntry);
};
} // namespace LightTable
#endif // UNDOLOGENTRY_H

View File

@ -0,0 +1,41 @@
/**
* @file integer.h
* @brief integer
* @version 0.1
* @author SYS Lab
* @date 2022.11.01
*/
#ifndef _FF_INTEGER
#define _FF_INTEGER
#ifdef _WIN32 /* FatFs development platform */
#include <tchar.h>
#include <windows.h>
typedef unsigned __int64 QWORD;
#else /* Embedded platform */
/* These types MUST be 16-bit or 32-bit */
typedef int INT;
typedef unsigned int UINT;
/* This type MUST be 8-bit */
typedef unsigned char BYTE;
/* These types MUST be 16-bit */
typedef short SHORT;
typedef unsigned short WORD;
typedef unsigned short WCHAR;
/* These types MUST be 32-bit */
typedef long LONG;
typedef unsigned long DWORD;
/* This type MUST be 64-bit (Remove this for C89 compatibility) */
typedef unsigned long long QWORD;
#endif
#endif

Binary file not shown.

After

Width:  |  Height:  |  Size: 72 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 132 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 56 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 92 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 149 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 30 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 77 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 177 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 227 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 144 KiB

View File

@ -0,0 +1,80 @@
/**
* @file Common.cc
* @brief Common
* @version 0.1
* @author SYS Lab
* @date 2022.11.01
*/
#include "Common.h"
namespace LightTable {
int cacheReadNum = 0;
int cacheWriteNum = 0;
std::chrono::steady_clock::time_point start_time =
std::chrono::steady_clock::now();
std::chrono::steady_clock::time_point end_time =
std::chrono::steady_clock::now();
double diff_sdcard_read = 0.0;
double diff_sdcard_write = 0.0;
struct timespec diff(struct timespec start, struct timespec end) {
struct timespec temp;
if ((end.tv_nsec - start.tv_nsec) < 0) {
temp.tv_sec = end.tv_sec - start.tv_sec - 1;
temp.tv_nsec = 1000000000 + end.tv_nsec - start.tv_nsec;
} else {
temp.tv_sec = end.tv_sec - start.tv_sec;
temp.tv_nsec = end.tv_nsec - start.tv_nsec;
}
return temp;
}
#ifdef IO_PROFILING
std::queue<struct timespec> Queue::io_times;
std::queue<struct timespec> Queue::io_submit_times;
#endif
#ifdef IO_PROFILING
struct timespec Queue::accumulate_io_times() {
struct timespec sum;
sum.tv_sec = 0;
sum.tv_nsec = 0;
while (!io_times.empty()) {
sum.tv_sec += io_times.front().tv_sec;
if (1000000000 <= sum.tv_nsec + io_times.front().tv_nsec) {
sum.tv_sec++;
sum.tv_nsec = sum.tv_nsec + io_times.front().tv_nsec - 1000000000;
} else {
sum.tv_nsec += io_times.front().tv_nsec;
}
io_times.pop();
}
return sum;
}
struct timespec Queue::accumulate_io_submit_times() {
struct timespec sum;
sum.tv_sec = 0;
sum.tv_nsec = 0;
while (!io_submit_times.empty()) {
sum.tv_sec += io_submit_times.front().tv_sec;
if (1000000000 <= sum.tv_nsec + io_submit_times.front().tv_nsec) {
sum.tv_sec++;
sum.tv_nsec = sum.tv_nsec + io_submit_times.front().tv_nsec - 1000000000;
} else {
sum.tv_nsec += io_submit_times.front().tv_nsec;
}
io_submit_times.pop();
}
return sum;
}
#endif
} // namespace LightTable

View File

@ -0,0 +1,92 @@
/**
* @file Driver.cc
* @brief Driver
* @version 0.1
* @author SYS Lab
* @date 2022.11.01
*/
#include "Driver.h"
extern "C" {
#include "ff.h"
#include "ffconf.h"
#include <diskio.h>
#include <rtdef.h>
}
/* Definitions of physical drive number for each drive */
#define DEV_RAM 0 /* Example: Map Ramdisk to physical drive 0 */
#define DEV_MMC 1 /* Example: Map MMC/SD card to physical drive 1 */
#define DEV_USB 2 /* Example: Map USB MSD to physical drive 2 */
static rt_device_t disk[FF_VOLUMES] = {0};
namespace LightTable {
uint32_t Driver::write(uint8_t *buf, uint64_t blockID) {
rt_size_t result;
rt_device_t device = disk[0];
#ifdef TABLE_STORAGE_CACHE
// TODO: cache
#endif
if (rt_device_write(device, blockID, buf, 1) == 1)
return RES_OK;
else
return RES_ERROR;
}
uint32_t Driver::read(uint8_t *buf, uint64_t blockID) {
rt_size_t result;
rt_device_t device = disk[0];
#ifdef TABLE_STORAGE_CACHE
// TODO: cache
#endif
if (rt_device_read(device, blockID, buf, 1) == 1) {
return RES_OK;
}
return RES_OK;
}
void Driver::driver_cleanup(const char *device_name) {
/* clean device */
return;
}
uint32_t Driver::driver_init(const char *device_name) {
/* init device */
/* note: initialization of the device is done at the MakeTableStorage*/
return 0;
}
} // namespace LightTable
uint32_t MakeTableStorage(const char *device_name) {
rt_device_t dev_id;
/* open specific device */
if (device_name == NULL) {
/* which is a non-device filesystem mount */
dev_id = NULL;
} else if ((dev_id = rt_device_find(device_name)) == NULL) {
/* no this device */
rt_set_errno(-ENODEV);
return -1;
}
/* open device, but do not check the status of device */
if (dev_id != NULL) {
if (rt_device_open(dev_id, RT_DEVICE_OFLAG_RDWR) != RT_EOK) {
return -1;
}
}
disk[0] = dev_id;
return 0;
}

View File

@ -0,0 +1,22 @@
ifndef LIGHTTABLE_DIR
LIGHTTABLE_DIR = ../..
endif
SRC_FILES := $(wildcard *.cc)
INCLUDE_DIR = -I$(LIGHTTABLE_DIR)/src -I. -I$(LIGHTTABLE_DIR)/spdk/include
SOURCE_FOR_CC = $(foreach source_file_1, $(SOURCES),$(filter %.cc, $(source_file_1)))
CXXFLAGS += -Werror -fno-omit-frame-pointer -Wall -Wextra -Wno-unused-parameter \
-Wno-missing-field-initializers -Wmissing-declarations -fno-strict-aliasing \
$(INCLUDE_DIR) -Wformat -Wformat-security -D_GNU_SOURCE \
-fPIC -fno-stack-protector -fno-common -DNDEBUG -U_FORTIFY_SOURCE \
-D_FORTIFY_SOURCE=2 -std=c++11
CXXFLAGS += -DYCSB_TEST
CXXFLAGS += -Wl,-z,relro,-z,now -Wl,-z,noexecstack -lpthread -Wl,-z,relro,-z,now \
-Wl,-z,noexecstack \
-Wl,--whole-archive -Wl,--no-whole-archive
include $(KERNEL_ROOT)/compiler.mk

View File

@ -0,0 +1,17 @@
/**
* @file BufferItem.cc
* @brief BufferItem
* @version 0.1
* @author SYS Lab
* @date 2022.11.01
*/
#include "BufferItem.h"
namespace LightTable {
BufferItem::BufferItem(uint64_t tableID) : tableID(tableID) {}
BufferItem::~BufferItem() {}
} // namespace LightTable

View File

@ -0,0 +1,23 @@
ifndef LIGHTTABLE_DIR
LIGHTTABLE_DIR = ../..
endif
SRC_FILES := $(wildcard *.cc)
INCLUDE_DIR = -I$(LIGHTTABLE_DIR)/src -I.
SOURCE_FOR_CC = $(foreach source_file_1, $(SOURCES),$(filter %.cc, $(source_file_1)))
CXXFLAGS += -Werror -fno-omit-frame-pointer -Wall -Wextra -Wno-unused-parameter \
-Wno-missing-field-initializers -Wmissing-declarations -fno-strict-aliasing \
$(INCLUDE_DIR) -Wformat -Wformat-security -D_GNU_SOURCE \
-fPIC -fno-stack-protector -fno-common -DNDEBUG -U_FORTIFY_SOURCE \
-D_FORTIFY_SOURCE=2 -std=c++11
CXXFLAGS += -DYCSB_TEST
CXXFLAGS += -Wl,-z,relro,-z,now -Wl,-z,noexecstack -lpthread -Wl,-z,relro,-z,now \
-Wl,-z,noexecstack \
-Wl,--whole-archive -Wl,--no-whole-archive
include $(KERNEL_ROOT)/compiler.mk

View File

@ -0,0 +1,184 @@
/**
* @file TableStorage.cc
* @brief TableStorage
* @version 0.1
* @author SYS Lab
* @date 2022.11.01
*/
#include "TableStorage.h"
// #include "ThreadPool.h"
// #include "Buffer.h"
// static struct timespec time1, time2, time3;
// static uint32_t coreNum = 0;
namespace LightTable {
TableStorage::TableStorage(const char *ipAddress, const uint32_t portNum,
const char *path)
: // metaHandle(path),
LightTableIPAddress(ipAddress),
LightTablePortNum(portNum) {
segmentManager = new SegmentManager();
rootTable = new RootTable();
std::cout << "INIT TableStorage SUCCESS" << "\n";
// threadPool = ThreadPool::getInstance(SYSTEM_MAX_CORES);
// buf = Buffer::getInstance();
// queryCache = QueryCache::getInstance(&tableMap);
// blockPreload = BlockPreload::getInstance();
// blockPreload->setParameters(queryCache);
// buf->setParameters(&metaHandle, rootTable);
}
uint32_t TableStorage::createTable(const char *tableName,
SegmentType segmentType,
std::vector<Schema::SchemaEntry> &schema) {
uint64_t segmentID = 0;
uint64_t firstBlockID = 0;
uint64_t tableID =
tableMap.size() + COMMON_TABLE_START_ID - SYSTEM_TABLE_COUNT;
uint32_t err =
segmentManager->getIdleSegment(segmentType, segmentID, firstBlockID);
if (err != SUCCESS) {
return err;
}
CommonTable *commonTable = new CommonTable(tableID, tableName, firstBlockID,
segmentID, segmentType, schema);
std::pair<std::map<uint64_t, Table *>::iterator, bool> ret;
ret = tableMap.insert(std::pair<uint64_t, Table *>(tableID, commonTable));
if (false == ret.second) {
return ERROR_TABLE;
}
time_t timeNow = time(NULL);
struct tm *now = localtime(&timeNow);
RootTable::TableTuple tuple;
tuple.tableID = tableID;
memcpy(tuple.tableName, tableName, TABLE_NAME_LENGTH);
tuple.firstBlockID = firstBlockID;
tuple.segmentType = segmentType;
tuple.segmentID = segmentID;
memcpy(tuple.user, "user", 5);
tuple.time = *now;
err = rootTable->appendTableInfo(tuple);
if (err == SUCCESS) std::cout << "create table: " << tableName << std::endl;
return err;
}
uint32_t TableStorage::dropTable(const char *tableName) {
uint64_t tableID = 0;
uint32_t result = rootTable->tableNameToTableID(tableName, tableID);
if (SUCCESS != result) return result;
std::map<uint64_t, Table *>::iterator iter = tableMap.find(tableID);
Table *commonTable = iter->second;
commonTable->drop();
tableMap.erase(tableID);
result = rootTable->deleteTableInfo(tableID);
if (result == SUCCESS) std::cout << "drop table: " << tableName << std::endl;
return result;
}
uint32_t TableStorage::insertTuple(const char *tableName, const uint8_t *row) {
uint64_t tableID = 0;
uint32_t result = 0;
#ifndef SDCARD_TEST
result = rootTable->tableNameToTableID(tableName, tableID);
if (SUCCESS != result) {
return result;
}
#else
tableID = YCSB_TABLE_ID;
#endif
std::map<uint64_t, Table *>::iterator iter = tableMap.find(tableID);
Table *commonTable = iter->second;
#ifndef TABLE_STORAGE_LOGGING
result = commonTable->insertRow(row);
#else
result = commonTable->insertRow_logging(row);
#endif
return result;
}
uint32_t TableStorage::deleteTuple(const char *tableName,
const char *primaryKey) {
uint64_t tableID = 0;
uint32_t result = rootTable->tableNameToTableID(tableName, tableID);
if (SUCCESS != result) return result;
std::map<uint64_t, Table *>::iterator iter = tableMap.find(tableID);
Table *commonTable = iter->second;
result = commonTable->deleteRow(primaryKey);
if (result == SUCCESS)
std::cout << "delete a tuple in " << tableName << " success!" << std::endl;
return result;
}
uint32_t TableStorage::updateTuple(const char *tableName,
const char *primaryKey,
const char *columnName,
const uint8_t *value) {
uint64_t tableID = 0;
uint32_t result = rootTable->tableNameToTableID(tableName, tableID);
if (SUCCESS != result) return result;
std::map<uint64_t, Table *>::iterator iter = tableMap.find(tableID);
Table *commonTable = iter->second;
#ifndef TABLE_STORAGE_LOGGING
result = commonTable->updateColumnItem(primaryKey, columnName, value);
#else
result = commonTable->updateColumnItem_logging(primaryKey, columnName, value);
#endif
return result;
}
uint32_t TableStorage::selectTuple(const char *tableName,
const char *primaryKey, uint8_t *row) {
uint64_t tableID = 0;
uint32_t result = 0;
#ifndef SDCARD_TEST
result = rootTable->tableNameToTableID(tableName, tableID);
if (SUCCESS != result) return result;
#else
tableID = YCSB_TABLE_ID;
#endif
std::map<uint64_t, Table *>::iterator iter = tableMap.find(tableID);
Table *commonTable = iter->second;
result = commonTable->selectRow(primaryKey, row);
return result;
}
uint32_t TableStorage::initTableStorage() {
return SUCCESS;
}
uint32_t TableStorage::closeTableStorage() {
return SUCCESS;
}
TableStorage::~TableStorage() {
for (auto ite = tableMap.begin(); ite != tableMap.end(); ++ite)
delete (ite->second);
tableMap.clear();
delete (rootTable);
delete (segmentManager);
std::cout << "close TableStorage success!\n";
}
} // namespace LightTable

View File

@ -0,0 +1,54 @@
/**
* @file UndoLogEntry.cc
* @brief UndoLogEntry
* @version 0.1
* @author SYS Lab
* @date 2022.11.01
*/
#include "UndoLogEntry.h"
#include <string.h>
namespace LightTable {
UndoLogEntry::UndoLogEntry(uint64_t tableID, const char *primaryKey,
uint64_t keySize, char *tuple, uint64_t tupleSize,
uint64_t blockID, uint64_t offset)
: BufferItem(tableID),
blockID(blockID),
offset(offset),
tupleSize(tupleSize),
keySize(keySize),
isExpired(false) {
memcpy(this->tuple, tuple, tupleSize);
memcpy(this->primaryKey, primaryKey, keySize);
}
UndoLogEntry::~UndoLogEntry() {
delete[] primaryKey;
delete[] tuple;
}
uint32_t UndoLogEntry::getTuple(uint64_t tableID, const char *primaryKey,
char *tuple, uint64_t &blockID,
uint64_t &offset) {
if (this->tableID != tableID || strcmp(this->primaryKey, primaryKey) != 0) {
return ERROR_TABLE;
}
memcpy(tuple, this->tuple, tupleSize);
blockID = this->blockID;
offset = this->offset;
return SUCCESS;
}
void UndoLogEntry::expireUndoLog() { isExpired = true; }
char *UndoLogEntry::getPrimaryKey() { return this->primaryKey; }
bool UndoLogEntry::getIsExpired(UndoLogEntry *logEntry) {
return logEntry->isExpired;
}
} // namespace LightTable

View File

@ -0,0 +1,31 @@
/**
* @file CommonTable.cc
* @brief CommonTable
* @version 0.1
* @author SYS Lab
* @date 2022.11.01
*/
#include "CommonTable.h"
namespace LightTable {
CommonTable::CommonTable(uint64_t tableID, const char *tableName,
uint64_t firstBlockID, uint64_t segmentID,
SegmentType segmentType,
std::vector<Schema::SchemaEntry> schemaEntrys,
bool usePrimaryKeyIndex)
: Table(tableID, tableName, firstBlockID, segmentID, segmentType,
schemaEntrys, usePrimaryKeyIndex)
{}
CommonTable::CommonTable(uint64_t tableID, const char *tableName,
uint64_t firstBlockID, uint64_t segmentID,
SegmentType segmentType, bool usePrimaryKeyIndex)
: Table(tableID, tableName, firstBlockID, segmentID, segmentType,
usePrimaryKeyIndex)
{}
} // namespace LightTable

View File

@ -0,0 +1,77 @@
/**
* @file HashBucket.cc
* @brief HashBucket
* @version 0.1
* @author SYS Lab
* @date 2022.11.01
*/
#include "HashBucket.h"
namespace LightTable {
HashBucket::HashBucket() : bucketSize(0) {}
uint32_t HashBucket::addBucketItem(uint64_t key, RowLocation rowLocation) {
std::pair<std::map<uint64_t, RowLocation>::iterator, bool> ret;
// std::unique_lock<std::mutex> lck(mtx);
// pthread_mutex_lock(&mtx);
ret = bucketItems.insert(std::pair<uint64_t, RowLocation>(key, rowLocation));
// lck.unlock();
// pthread_mutex_unlock(&mtx);
if (ret.second == false) {
return ADD_BUCKET_ITEM_ERROR;
}
bucketSize++;
return SUCCESS;
}
uint32_t HashBucket::deleteBucketItem(uint64_t key) {
if (bucketItems.erase(key) == 1) {
bucketSize--;
return SUCCESS;
}
return BUCKET_ITEM_NOT_FOUND;
}
uint32_t HashBucket::updateRowLocation(uint64_t key, RowLocation rowLocation) {
std::map<uint64_t, RowLocation>::iterator iter;
iter = bucketItems.find(key);
if (iter != bucketItems.end()) {
(iter->second).blockID = rowLocation.blockID;
(iter->second).rowOffset = rowLocation.rowOffset;
return SUCCESS;
}
return BUCKET_ITEM_NOT_FOUND;
}
uint32_t HashBucket::getRowLocation(uint64_t key, RowLocation &rowLocation) {
std::map<uint64_t, RowLocation>::iterator iter;
iter = bucketItems.find(key);
if (iter != bucketItems.end()) {
rowLocation.blockID = (iter->second).blockID;
rowLocation.rowOffset = (iter->second).rowOffset;
return SUCCESS;
}
rowLocation.blockID = 0;
rowLocation.rowOffset = 0;
return BUCKET_ITEM_NOT_FOUND;
}
uint64_t HashBucket::getBucketSize() { return bucketSize; }
uint32_t HashBucket::setBucketSize(uint64_t bucketSize) {
this->bucketSize = bucketSize;
return SUCCESS;
}
uint32_t HashBucket::getAllBucketItems(
std::map<uint64_t, RowLocation> &bucketItems) {
bucketItems = this->bucketItems;
return SUCCESS;
}
} // namespace LightTable

View File

@ -0,0 +1,113 @@
/**
* @file HashTable.cc
* @brief HashTable
* @version 0.1
* @author SYS Lab
* @date 2022.11.01
*/
#include "HashTable.h"
namespace LightTable {
HashTable::HashTable() {
buckets.reserve(HASH_BUCKET_SIZE);
for (uint32_t i = 0; i < HASH_BUCKET_SIZE; i++) {
HashBucket *tempBucket = new HashBucket();
buckets.push_back(tempBucket);
}
}
HashTable::~HashTable() {
std::vector<HashBucket *>::iterator iter = buckets.begin();
while (iter != buckets.end()) {
iter = buckets.erase(iter);
}
}
uint64_t HashTable::getMapKey(const char *primaryKey) {
const std::string str = primaryKey;
uint64_t BitsInUnsignedInt = (uint64_t)(4 * 8);
uint64_t ThreeQuarters = (uint64_t)((BitsInUnsignedInt * 3) / 4);
uint64_t OneEighth = (uint64_t)(BitsInUnsignedInt / 8);
uint64_t HighBits = (uint64_t)(0xFFFFFFFF) << (BitsInUnsignedInt - OneEighth);
uint64_t hash = 0;
uint64_t test = 0;
for (uint32_t i = 0; i < str.length(); i++) {
hash = (hash << OneEighth) + str[i];
if ((test = hash & HighBits) != 0) {
hash = ((hash ^ (test >> ThreeQuarters)) & (~HighBits));
}
}
return hash;
}
uint32_t HashTable::hashToBucket(uint64_t key) {
return key % HASH_BUCKET_SIZE;
}
uint32_t HashTable::getRowLocation(uint32_t bucketID, uint64_t key,
RowLocation &rowLocation) {
return buckets[bucketID]->getRowLocation(key, rowLocation);
}
uint32_t HashTable::addItem(uint32_t bucketID, uint64_t key,
RowLocation rowLocation) {
return buckets[bucketID]->addBucketItem(key, rowLocation);
}
uint32_t HashTable::deleteItem(uint32_t bucketID, uint64_t key) {
return buckets[bucketID]->deleteBucketItem(key);
}
uint32_t HashTable::updateItem(uint32_t bucketID, uint64_t key,
RowLocation rowLocation) {
return buckets[bucketID]->updateRowLocation(key, rowLocation);
}
uint64_t HashTable::getItemCount() {
if (buckets.size() == 0) {
return buckets.size();
}
uint64_t itemCount = 0;
for (uint32_t i = 0; i < HASH_BUCKET_SIZE; i++) {
itemCount += buckets[i]->getBucketSize();
}
return itemCount;
}
uint32_t HashTable::getAllBuckets(std::vector<HashBucket *> &buckets) {
buckets = this->buckets;
return SUCCESS;
}
uint32_t HashTable::refreshRowLocations(
uint64_t blockID, uint64_t deleteOffset, uint64_t rowSize,
std::map<uint64_t, RowLocation> &locationItems) {
for (uint32_t i = 0; i < HASH_BUCKET_SIZE; i++) {
std::map<uint64_t, RowLocation> bucketItems;
buckets[i]->getAllBucketItems(bucketItems);
std::map<uint64_t, RowLocation>::iterator iter = bucketItems.begin();
while (iter != bucketItems.end()) {
if ((iter->second).blockID == blockID &&
(iter->second).rowOffset > deleteOffset) {
(iter->second).rowOffset -= rowSize;
locationItems.insert(
std::pair<uint64_t, RowLocation>(iter->first, iter->second));
}
}
}
return SUCCESS;
}
uint32_t HashTable::clear() {
std::vector<HashBucket *>::iterator iter = buckets.begin();
while (iter != buckets.end()) {
iter = buckets.erase(iter);
}
return SUCCESS;
}
} // namespace LightTable

View File

@ -0,0 +1,23 @@
ifndef LIGHTTABLE_DIR
LIGHTTABLE_DIR = ../..
endif
SRC_FILES := $(wildcard *.cc)
INCLUDE_DIR = -I$(LIGHTTABLE_DIR)/src -I. -I$(LIGHTTABLE_DIR)/spdk/include -I/opt/gnu-mcu-eclipse/riscv-none-gcc/8.2.0-2.1-20190425-1021/riscv-none-embed/include/c++/8.2.0
SOURCE_FOR_CC = $(foreach source_file_1, $(SOURCES),$(filter %.cc, $(source_file_1)))
CXXFLAGS += -fno-omit-frame-pointer \
-Wno-missing-field-initializers -Wmissing-declarations -fno-strict-aliasing \
$(INCLUDE_DIR) -Wformat -Wformat-security -D_GNU_SOURCE \
-fPIC -fno-stack-protector -fno-common -DNDEBUG -U_FORTIFY_SOURCE \
-D_FORTIFY_SOURCE=2 -std=c++11
CXXFLAGS += -DYCSB_TEST
CXXFLAGS += -Wl,-z,relro,-z,now -Wl,-z,noexecstack -lpthread -Wl,-z,relro,-z,now \
-Wl,-z,noexecstack \
-Wl,--whole-archive -Wl,--no-whole-archive -lrt
include $(KERNEL_ROOT)/compiler.mk

View File

@ -0,0 +1,267 @@
/**
* @file PrefetchBlockManager.cc
* @brief PrefetchBlockManager
* @version 0.1
* @author SYS Lab
* @date 2022.11.01
*/
#include "PrefetchBlockManager.h"
namespace LightTable
{
PrefetchBlockManager::PrefetchBlockManager(uint64_t firstBlockID,
uint64_t segmentID,
SegmentType segmentType)
: segmentID(segmentID), segmentType(segmentType), firstBlockID(firstBlockID), currentID(0)
{
uint32_t num = 0;
switch (segmentType)
{
case SEGMENT_TYPE_SMALL:
num = SEGMENT_TYPE_SMALL_CELL_SIZE / BLOCK_SIZE;
break;
case SEGMENT_TYPE_MEDIUM:
num = SEGMENT_TYPE_MEDIUM_CELL_SIZE / BLOCK_SIZE;
break;
case SEGMENT_TYPE_BIG:
num = SEGMENT_TYPE_BIG_CELL_SIZE / BLOCK_SIZE;
break;
default:
break;
}
blockCount = num;
#ifndef YCSB_TEST
while (num--)
{
PrefetchBlockManagerEntry *entry = new PrefetchBlockManagerEntry();
entry->blockID = firstBlockID + num;
entry->currentOffset = 0;
entry->isOccupied = PREFETCH_BLOCK_STATUS_IDLE;
prefetchBlocks.insert(std::pair<uint64_t, PrefetchBlockManagerEntry>(entry->blockID, *entry));
}
#endif
}
PrefetchBlockManager::~PrefetchBlockManager()
{
prefetchBlocks.clear();
}
uint64_t
PrefetchBlockManager::getNextBlock()
{
uint32_t count = blockCount - currentID;
if (count <= 0)
{
return 0;
}
currentID++;
return currentID + firstBlockID - 1;
}
uint64_t
PrefetchBlockManager::blockAllocate(uint64_t rowSize)
{
if (blockCount == 0)
{
return 0;
}
// struct timespec time;
// clock_gettime(CLOCK_REALTIME, &time);
srand((unsigned)time(NULL));
std::map<uint64_t, PrefetchBlockManagerEntry>::iterator iter;
uint32_t count = blockCount - currentID;
while (count--)
{
uint64_t blockID = currentID + firstBlockID;
iter = prefetchBlocks.find(blockID);
if (!iter->second.isOccupied)
{
if (rowSize < (BLOCK_SIZE - iter->second.currentOffset))
{
iter->second.isOccupied = PREFETCH_BLOCK_STATUS_BUSY;
return blockID;
}
}
currentID++;
}
return 0;
}
uint32_t
PrefetchBlockManager::setBlockState(uint64_t blockID, bool isOccupied)
{
std::map<uint64_t, PrefetchBlockManagerEntry>::iterator iter;
iter = prefetchBlocks.find(blockID);
if (iter != prefetchBlocks.end())
{
iter->second.isOccupied = isOccupied;
return SUCCESS;
}
else
{
return PREFETCH_BLOCK_NOT_FOUND;
}
}
uint32_t
PrefetchBlockManager::setOffset(uint64_t blockID, uint64_t currentOffset)
{
std::map<uint64_t, PrefetchBlockManagerEntry>::iterator iter;
iter = prefetchBlocks.find(blockID);
if (iter != prefetchBlocks.end())
{
iter->second.currentOffset = currentOffset;
return SUCCESS;
}
else
{
return PREFETCH_BLOCK_NOT_FOUND;
}
}
uint32_t
PrefetchBlockManager::getOffset(uint64_t blockID, uint64_t &currentOffset)
{
std::map<uint64_t, PrefetchBlockManagerEntry>::iterator iter;
iter = prefetchBlocks.find(blockID);
if (iter != prefetchBlocks.end())
{
currentOffset = iter->second.currentOffset;
return SUCCESS;
}
else
{
return PREFETCH_BLOCK_NOT_FOUND;
}
}
uint32_t
PrefetchBlockManager::advanceOffset(uint64_t blockID, uint64_t rowSize)
{
std::map<uint64_t, PrefetchBlockManagerEntry>::iterator iter;
iter = prefetchBlocks.find(blockID);
if (iter != prefetchBlocks.end())
{
iter->second.currentOffset += rowSize;
return SUCCESS;
}
else
{
return PREFETCH_BLOCK_NOT_FOUND;
}
}
uint32_t
PrefetchBlockManager::isOccupied(uint64_t blockID, bool &status)
{
std::map<uint64_t, PrefetchBlockManagerEntry>::iterator iter;
iter = prefetchBlocks.find(blockID);
if (iter != prefetchBlocks.end())
{
status = iter->second.isOccupied;
return SUCCESS;
}
else
{
return PREFETCH_BLOCK_NOT_FOUND;
}
}
uint32_t
PrefetchBlockManager::getPrefetchBlockEntry(uint64_t blockID,
PrefetchBlockManagerEntry &entry)
{
entry = prefetchBlocks[blockID];
return SUCCESS;
}
uint32_t
PrefetchBlockManager::getAllPrefetchBlockEntrys(std::map<uint64_t,
PrefetchBlockManagerEntry> &entrys)
{
entrys = prefetchBlocks;
return SUCCESS;
}
uint32_t
PrefetchBlockManager::lockBlock(uint64_t blockID)
{
std::map<uint64_t, PrefetchBlockManagerEntry>::iterator iter;
iter = prefetchBlocks.find(blockID);
if (iter != prefetchBlocks.end())
{
if (iter->second.isOccupied == PREFETCH_BLOCK_STATUS_BUSY)
{
return BLOCK_OCCUPIED;
}
iter->second.isOccupied = PREFETCH_BLOCK_STATUS_BUSY;
return SUCCESS;
}
return PREFETCH_BLOCK_NOT_FOUND;
}
uint32_t
PrefetchBlockManager::unlockBlock(uint64_t blockID)
{
std::map<uint64_t, PrefetchBlockManagerEntry>::iterator iter;
iter = prefetchBlocks.find(blockID);
if (iter != prefetchBlocks.end())
{
if (iter->second.isOccupied == PREFETCH_BLOCK_STATUS_BUSY)
{
iter->second.isOccupied = PREFETCH_BLOCK_STATUS_IDLE;
}
return SUCCESS;
}
return PREFETCH_BLOCK_NOT_FOUND;
}
bool
PrefetchBlockManager::isCached(uint64_t blockID, uint64_t &pageID)
{
std::map<uint64_t, PrefetchBlockManagerEntry>::iterator iter;
iter = prefetchBlocks.find(blockID);
if (iter != prefetchBlocks.end() && iter->second.isCached)
{
pageID = iter->second.pageID;
return true;
}
return false;
}
uint32_t
PrefetchBlockManager::setIsCached(uint64_t blockID, bool isCached, uint64_t pageID)
{
std::map<uint64_t, PrefetchBlockManagerEntry>::iterator iter;
iter = prefetchBlocks.find(blockID);
if (iter != prefetchBlocks.end())
{
iter->second.isCached = isCached;
if (isCached)
{
iter->second.pageID = pageID;
}
return SUCCESS;
}
return PREFETCH_BLOCK_NOT_FOUND;
}
} // namespace LightTable

View File

@ -0,0 +1,244 @@
/**
* @file RootTable.cc
* @brief RootTable
* @version 0.1
* @author SYS Lab
* @date 2022.11.01
*/
#include "RootTable.h"
namespace LightTable {
RootTable::RootTable(bool usePrimaryKeyIndex)
: SystemTable(ROOTTABLE_TABLE_ID, "RootTable", ROOTTABLE_FIRST_BLOCK_ID,
ROOTTABLE_SEGMENT_ID, SEGMENT_TYPE_SMALL,
usePrimaryKeyIndex) {
Schema::SchemaEntry entry1 = {1, "tableID", "uint64_t", 8, true, false};
schema.appendEntry(entry1);
Schema::SchemaEntry entry2 = {2, "tableName", "string", TABLE_NAME_LENGTH,
false, false};
schema.appendEntry(entry2);
Schema::SchemaEntry entry3 = {3, "firstBlockID", "uint64_t", 8, false, false};
schema.appendEntry(entry3);
Schema::SchemaEntry entry4 = {4, "segmentID", "uint64_t", 8, false, false};
schema.appendEntry(entry4);
Schema::SchemaEntry entry5 = {5, "segmentType", "uint32_t", 4, false, false};
schema.appendEntry(entry5);
Schema::SchemaEntry entry6 = {6, "user", "string", USER_NAME_LENGTH,
false, true};
schema.appendEntry(entry6);
Schema::SchemaEntry entry7 = {7, "time", "time", 60, false, false};
schema.appendEntry(entry7);
}
uint32_t RootTable::tableNameToTableID(const char *tableName,
uint64_t &tableID) {
std::map<uint64_t, TableTuple>::iterator iter = tableTupleMap.begin();
while (iter != tableTupleMap.end()) {
if (0 == strncmp(tableName, iter->second.tableName, TABLE_NAME_LENGTH)) {
tableID = iter->second.tableID;
return SUCCESS;
}
iter++;
}
return TABLE_NOT_FOUND;
}
uint32_t RootTable::deleteTableInfo(uint64_t tableID) {
uint32_t ret = SUCCESS;
RowLocation rowLocation;
uint32_t bucketID = hashTable.hashToBucket(tableID);
ret = hashTable.getRowLocation(bucketID, tableID, rowLocation);
uint64_t deleteBlockID = rowLocation.blockID;
uint64_t deleteRowOffset = rowLocation.rowOffset;
char *hashTableMetaData = new char[ROWMAP_SERIALIZED_LENGTH];
uint32_t size = 0;
while (prefetchBlockManager.lockBlock(rowLocation.blockID) != SUCCESS)
;
uint64_t currentOffset = 0;
ret = prefetchBlockManager.getOffset(rowLocation.blockID, currentOffset);
if (ret != SUCCESS) {
return ret;
}
if (rowLocation.rowOffset + schema.getEntrySize() != currentOffset) {
// RowBufferItem::Tuple item;
// uint8_t str[ROOTTABLE_TUPLE_SIZE];
// memcpy(str, &tableTupleMap[tableID], sizeof(tableTupleMap[tableID]));
// item.blockID = rowLocation.blockID;
// item.rowOffset = rowLocation.rowOffset;
// item.isDelete = true;
// RowBufferItem *rowBufferItem = new RowBufferItem(item);
// buf->append(rowBufferItem);
std::map<uint64_t, RowLocation> locationItems;
hashTable.refreshRowLocations(deleteBlockID, deleteRowOffset,
schema.getEntrySize(), locationItems);
// std::map<uint64_t, RowLocation>::iterator iter = locationItems.begin();
// while (iter != locationItems.end()) {
// MetaHandle::serialize(std::pair<uint64_t, RowLocation>(iter->first,
// iter->second), tableID, hashTableMetaData, size);
// MetaBufferItem *nextMeta= new MetaBufferItem(tableID, hashTableMetaData,
// size); buf->append(nextMeta);
// }
}
hashTable.deleteItem(bucketID, tableID);
rowLocation.blockID = 0;
// MetaHandle::serialize(std::pair<uint64_t, RowLocation>(tableID,
// rowLocation),
// ROOTTABLE_TABLE_ID, hashTableMetaData, size);
// MetaBufferItem *hashTableMeta= new MetaBufferItem(ROOTTABLE_TABLE_ID,
// hashTableMetaData, size);
// buf->append(hashTableMeta);
uint64_t newOffset = currentOffset - schema.getEntrySize();
prefetchBlockManager.setOffset(deleteBlockID, newOffset);
PrefetchBlockManager::PrefetchBlockManagerEntry blockEntry;
prefetchBlockManager.unlockBlock(deleteBlockID);
prefetchBlockManager.getPrefetchBlockEntry(deleteBlockID, blockEntry);
// char *pbmData = new char[PREFETCH_BLOCK_SERIALIZED_LENGTH];
// MetaHandle::serialize(blockEntry, ROOTTABLE_TABLE_ID, pbmData, size);
// MetaBufferItem *pbmMeta = new MetaBufferItem(ROOTTABLE_TABLE_ID, pbmData,
// size); buf->append(pbmMeta);
if (tableTupleMap.erase(tableID) == 1) {
return SUCCESS;
}
return ERROR_TABLE;
}
uint32_t RootTable::appendTableInfo(TableTuple tableTuple) {
uint32_t err = SUCCESS;
tableTupleMap.insert(
std::pair<uint64_t, TableTuple>(tableTuple.tableID, tableTuple));
uint64_t blockID = 0;
uint64_t blockOffset = 0;
blockID = prefetchBlockManager.blockAllocate(schema.getEntrySize());
err = prefetchBlockManager.getOffset(blockID, blockOffset);
if (err != SUCCESS) {
// TODO allocate new seg
return GET_AVAILABLE_BLOCK_ERROR;
}
// RowBufferItem::Tuple item;
// uint8_t str[ROOTTABLE_TUPLE_SIZE];
// memcpy(str, &tableTuple, sizeof(tableTuple));
// item.row = str;
// item.blockID = blockID;
// item.rowOffset = blockOffset;
// item.isDelete = false;
// RowBufferItem *rowBufferItem = new RowBufferItem(item);
// buf->append(rowBufferItem);
uint32_t bucketID = hashTable.hashToBucket(tableTuple.tableID);
RowLocation rowLocation = {blockID, blockOffset};
err = hashTable.addItem(bucketID, tableTuple.tableID, rowLocation);
if (err != SUCCESS) {
return err;
}
// uint32_t size = 0;
// char *hashTableMetaData = new char[ROWMAP_SERIALIZED_LENGTH];
// MetaHandle::serialize(std::pair<uint64_t, RowLocation>(tableTuple.tableID,
// rowLocation), tableID, hashTableMetaData, size);
// MetaBufferItem *hashTableMeta = new MetaBufferItem(tableID,
// hashTableMetaData,
// size);
// buf->append(hashTableMeta);
err = prefetchBlockManager.advanceOffset(blockID, schema.getEntrySize());
prefetchBlockManager.setBlockState(blockID, PREFETCH_BLOCK_STATUS_IDLE);
// PrefetchBlockManager::PrefetchBlockManagerEntry blockEntry;
// prefetchBlockManager.getPrefetchBlockEntry(blockID, blockEntry);
// char *pbmData = new char[PREFETCH_BLOCK_SERIALIZED_LENGTH];
// MetaHandle::serialize(blockEntry, tableID, pbmData, size);
// MetaBufferItem *pbmMeta = new MetaBufferItem(tableID, pbmData, size);
// buf->append(pbmMeta);
return SUCCESS;
}
uint32_t RootTable::getTableInfo(uint64_t tableID,
TableTuple &tableTupleResult) {
std::map<uint64_t, TableTuple>::iterator iter;
iter = tableTupleMap.find(tableID);
if (iter != tableTupleMap.end()) {
tableTupleResult = iter->second;
return SUCCESS;
}
tableTupleResult.tableID = 0;
return TABLE_TUPLE_NOT_FOUND;
}
uint32_t RootTable::modifyTableInfo(uint64_t tableID, TableTuple tableTuple) {
uint32_t ret = SUCCESS;
std::map<uint64_t, TableTuple>::iterator iter;
iter = tableTupleMap.find(tableID);
if (iter != tableTupleMap.end()) {
iter->second = tableTuple;
uint32_t bucketID = hashTable.hashToBucket(tableID);
RowLocation rowLocation;
ret = hashTable.getRowLocation(bucketID, tableID, rowLocation);
if (ret != SUCCESS) {
return ret;
}
// RowBufferItem::Tuple item;
// uint8_t str[ROOTTABLE_TUPLE_SIZE];
// memcpy(str, &tableTuple, sizeof(tableTuple));
// item.row = str;
// item.blockID = rowLocation.blockID;
// item.rowOffset = rowLocation.rowOffset;
// item.isDelete = false;
// RowBufferItem *rowBufferItem = new RowBufferItem(item);
// buf->append(rowBufferItem);
return SUCCESS;
}
return TABLE_TUPLE_NOT_FOUND;
}
uint32_t RootTable::getTableTuple(uint64_t tableID, TableTuple &tableTuple) {
std::map<uint64_t, TableTuple>::iterator iter;
iter = tableTupleMap.find(tableID);
if (iter != tableTupleMap.end()) {
tableTuple = iter->second;
return SUCCESS;
}
return TABLE_TUPLE_NOT_FOUND;
}
uint32_t RootTable::serializeRow(const TableTuple tableTuple, uint8_t *buf) {
memcpy(buf, &tableTuple, ROOTTABLE_TUPLE_SIZE);
return SUCCESS;
}
uint32_t RootTable::deserializeRow(const uint8_t *buf,
TableTuple *tableTupleResult) {
if (buf != NULL) {
memcpy(tableTupleResult, buf, ROOTTABLE_TUPLE_SIZE);
if (tableTupleResult->tableID != 0) {
return SUCCESS;
}
}
return BUFFER_EMPTY;
}
uint64_t RootTable::getTableCount() { return tableTupleMap.size(); }
} // namespace LightTable

View File

@ -0,0 +1,77 @@
/**
* @file RowMap.cc
* @brief RowMap
* @version 0.1
* @author SYS Lab
* @date 2022.11.01
*/
#include "RowMap.h"
namespace LightTable {
RowMap::RowMap() {}
uint32_t RowMap::appendEntry(uint64_t key, uint64_t blockID,
uint64_t rowOffset) {
std::pair<std::map<uint64_t, RowMapEntry>::iterator, bool> ret;
RowMapEntry rowMapEntry = {key, blockID, rowOffset};
ret = rowMapEntrys.insert(std::pair<uint64_t, RowMapEntry>(key, rowMapEntry));
if (ret.second == false) {
return ADD_ROW_MAP_ENTRY_ERROR;
}
return SUCCESS;
}
uint32_t RowMap::deleteEntry(uint64_t key) {
if (rowMapEntrys.erase(key) == 1) {
return SUCCESS;
}
return ROW_MAP_ENTRY_NOT_FOUND;
}
uint32_t RowMap::alterEntry(uint64_t key, uint64_t blockID,
uint64_t rowOffset) {
std::map<uint64_t, RowMapEntry>::iterator iter;
iter = rowMapEntrys.find(key);
if (iter != rowMapEntrys.end()) {
(iter->second).key = key;
(iter->second).blockID = blockID;
(iter->second).rowOffset = rowOffset;
return SUCCESS;
}
return ROW_MAP_ENTRY_NOT_FOUND;
}
uint32_t RowMap::queryEntry(uint64_t key, RowMapEntry &rowMapEntry) {
std::map<uint64_t, RowMapEntry>::iterator iter;
iter = rowMapEntrys.find(key);
if (iter != rowMapEntrys.end()) {
rowMapEntry = iter->second;
return SUCCESS;
}
rowMapEntry.key = key;
rowMapEntry.blockID = 0;
rowMapEntry.rowOffset = 0;
return ROW_MAP_ENTRY_NOT_FOUND;
}
uint32_t RowMap::queryAllEntry(
std::map<uint64_t, RowMapEntry> &allRowMapEntrys) {
if (rowMapEntrys.empty() == false) {
allRowMapEntrys = rowMapEntrys;
return SUCCESS;
}
return ROW_MAP_ENTRY_NOT_FOUND;
}
uint64_t RowMap::getRowCount() { return rowMapEntrys.size(); }
} // namespace LightTable

View File

@ -0,0 +1,166 @@
/**
* @file Schema.cc
* @brief table schema
* @version 0.1
* @author SYS Lab
* @date 2022.11.01
*/
#include "Schema.h"
namespace LightTable {
Schema::Schema() {
primaryKeySchema.columnID = 1;
primaryKeySchema.isPrimaryKey = true;
columnCount = 0;
entrySize = 0;
}
Schema::Schema(std::vector<SchemaEntry> schemaEntrys) {
columnCount = 0;
entrySize = 0;
primaryKeySchema.columnID = 1;
primaryKeySchema.isPrimaryKey = true;
std::vector<SchemaEntry>::iterator iter = schemaEntrys.begin();
while (iter != schemaEntrys.end()) {
appendEntry(*iter);
iter++;
}
}
uint32_t Schema::appendEntry(SchemaEntry &schemaEntry) {
if (schemaEntry.columnID != columnCount + 1) {
return COLUMN_ID_NOT_CONTINUOUS;
}
std::pair<std::map<uint64_t, SchemaEntry>::iterator, bool> ret;
ret = schemaEntrys.insert(std::pair<uint64_t, Schema::SchemaEntry>(
schemaEntry.columnID, schemaEntry));
if (ret.second == false) {
return ADD_SCHEMA_ENTRY_ERROR;
}
if (schemaEntry.isPrimaryKey) {
primaryKeySchema = schemaEntry;
}
columnCount++;
entrySize = entrySize + schemaEntry.length;
return SUCCESS;
}
uint32_t Schema::deleteEntry(uint64_t columnID) {
if (columnID == primaryKeySchema.columnID) {
return DELETE_PARIMARY_KEY_COLUMN;
}
uint64_t newColumnID = columnID;
SchemaEntry schemaEntry;
std::map<uint64_t, SchemaEntry>::iterator iter;
iter = schemaEntrys.find(columnID);
if (iter != schemaEntrys.end()) {
schemaEntry = iter->second;
schemaEntrys.erase(iter);
entrySize = entrySize - schemaEntry.length;
columnCount--;
if (columnCount > 0) {
iter = schemaEntrys.find(newColumnID + 1);
while (iter != schemaEntrys.end()) {
schemaEntry = iter->second;
schemaEntry.columnID = newColumnID;
schemaEntrys.insert(
std::pair<uint64_t, Schema::SchemaEntry>(newColumnID, schemaEntry));
schemaEntrys.erase(iter);
newColumnID++;
iter = schemaEntrys.find(newColumnID + 1);
}
}
return SUCCESS;
}
return SCHEMA_ENTRY_NOT_FOUND;
}
uint32_t Schema::alterEntry(uint64_t columnID, SchemaEntry schemaEntry) {
if (schemaEntry.columnID != columnID) {
return COLUMN_ID_NOT_CONTINUOUS;
}
std::map<uint64_t, SchemaEntry>::iterator iter;
iter = schemaEntrys.find(columnID);
entrySize = entrySize - (iter->second).length;
if (iter != schemaEntrys.end()) {
iter->second = schemaEntry;
primaryKeySchema = schemaEntry;
entrySize = entrySize + (iter->second).length;
return SUCCESS;
}
return SCHEMA_ENTRY_NOT_FOUND;
}
uint32_t Schema::getColumnID(const char *columnName, uint64_t &columnID) {
std::map<uint64_t, SchemaEntry>::iterator iter = schemaEntrys.begin();
while (iter != schemaEntrys.end()) {
if (strncmp(iter->second.columnName, columnName, iter->second.length) ==
0) {
columnID = (iter->second).columnID;
return SUCCESS;
}
iter++;
}
return COLUMN_ITEM_NOT_FOUND;
}
uint32_t Schema::queryEntry(uint64_t columnID,
Schema::SchemaEntry &schemaEntry) {
std::map<uint64_t, SchemaEntry>::iterator iter;
iter = schemaEntrys.find(columnID);
if (iter != schemaEntrys.end()) {
schemaEntry = iter->second;
return SUCCESS;
}
schemaEntry.columnID = 0;
return SCHEMA_ENTRY_NOT_FOUND;
}
uint32_t Schema::queryAllEntry(
std::map<uint64_t, SchemaEntry> &allSchemaEntrys) {
allSchemaEntrys = schemaEntrys;
if (schemaEntrys.empty() == false) {
return SUCCESS;
}
return SCHEMA_ENTRY_NOT_FOUND;
}
uint64_t Schema::getEntrySize() { return entrySize; }
void Schema::setEntrySize(uint64_t entrySize) { this->entrySize = entrySize; }
uint64_t Schema::getColumnCount() { return columnCount; }
void Schema::setColumnCount(uint64_t columnCount) {
this->columnCount = columnCount;
}
uint32_t Schema::getPrimaryKeyLength() { return primaryKeySchema.length; }
Schema::SchemaEntry &Schema::getPrimaryKeySchema() { return primaryKeySchema; }
uint32_t Schema::drop() {
schemaEntrys.clear();
primaryKeySchema.length = 0;
columnCount = 0;
entrySize = 0;
return SUCCESS;
}
} // namespace LightTable

View File

@ -0,0 +1,180 @@
/**
* @file SegmentManager.cc
* @brief SegmentManager
* @version 0.1
* @author SYS Lab
* @date 2022.11.01
*/
#include "SegmentManager.h"
namespace LightTable {
SegmentManager::SegmentManager() {
int blockID, num = 0;
smallBitmap = new uint8_t[SEGMENT_TYPE_SMALL_BITMAP_SIZE];
mediumBitmap = new uint8_t[SEGMENT_TYPE_MEDIUM_BITMAP_SIZE];
bigBitmap = new uint8_t[SEGMENT_TYPE_BIG_BITMAP_SIZE];
#ifdef YCSB_TEST
blockID = SEGMENT_TYPE_BIG_START;
while (num < SEGMENT_TYPE_BIG_BITMAP_SIZE) {
Driver::read(bigBitmap + num, blockID);
num += BLOCK_SIZE;
blockID++;
}
#else
num = 0;
blockID = SEGMENT_TYPE_SMALL_START;
while (num < SEGMENT_TYPE_SMALL_BITMAP_SIZE) {
Driver::read(smallBitmap + num, blockID);
num += BLOCK_SIZE;
blockID++;
}
num = 0;
blockID = SEGMENT_TYPE_MEDIUM_START;
while (num < SEGMENT_TYPE_MEDIUM_BITMAP_SIZE) {
Driver::read(mediumBitmap + num, blockID);
num += BLOCK_SIZE;
blockID++;
}
num = 0;
blockID = SEGMENT_TYPE_BIG_START;
while (num < SEGMENT_TYPE_BIG_BITMAP_SIZE) {
Driver::read(mediumBitmap + num, blockID);
num += BLOCK_SIZE;
blockID++;
}
#endif
}
SegmentManager::~SegmentManager() {
delete[] smallBitmap;
delete[] mediumBitmap;
delete[] bigBitmap;
}
uint32_t SegmentManager::setBitmap(SegmentType segmentType, uint64_t segmentID,
SegmentStatus segmentStatus) {
switch (segmentType) {
case SEGMENT_TYPE_SMALL:
return setBit(segmentID, smallBitmap, SEGMENT_TYPE_SMALL_START,
segmentStatus);
case SEGMENT_TYPE_MEDIUM:
return setBit(segmentID, mediumBitmap, SEGMENT_TYPE_MEDIUM_START,
segmentStatus);
case SEGMENT_TYPE_BIG:
return setBit(segmentID, bigBitmap, SEGMENT_TYPE_BIG_START,
segmentStatus);
default:
return SEGMENT_TYPE_ERROR;
}
}
uint32_t SegmentManager::getIdleSegment(SegmentType segmentType,
uint64_t &segmentID,
uint64_t &firstBlockID) {
uint32_t stateCode;
switch (segmentType) {
case SEGMENT_TYPE_SMALL:
stateCode =
findFirstIdle(smallBitmap, SEGMENT_TYPE_SMALL_BITMAP_SIZE, segmentID);
if (stateCode != SUCCESS) return stateCode;
firstBlockID = SEGMENT_TYPE_SMALL_START +
(SEGMENT_TYPE_SMALL_CELL_SIZE / BLOCK_SIZE) * segmentID;
return setBit(segmentID, smallBitmap, SEGMENT_TYPE_SMALL_START,
SEGMENT_STATUS_BUSY);
case SEGMENT_TYPE_MEDIUM:
stateCode = findFirstIdle(mediumBitmap, SEGMENT_TYPE_MEDIUM_BITMAP_SIZE,
segmentID);
if (stateCode != SUCCESS) return stateCode;
firstBlockID = SEGMENT_TYPE_MEDIUM_START +
(SEGMENT_TYPE_MEDIUM_CELL_SIZE / BLOCK_SIZE) * segmentID;
return setBit(segmentID, mediumBitmap, SEGMENT_TYPE_MEDIUM_START,
SEGMENT_STATUS_BUSY);
case SEGMENT_TYPE_BIG:
stateCode =
findFirstIdle(bigBitmap, SEGMENT_TYPE_BIG_BITMAP_SIZE, segmentID);
if (stateCode != SUCCESS) return stateCode;
firstBlockID = SEGMENT_TYPE_BIG_START +
(SEGMENT_TYPE_BIG_CELL_SIZE / BLOCK_SIZE) * segmentID;
return setBit(segmentID, bigBitmap, SEGMENT_TYPE_BIG_START,
SEGMENT_STATUS_BUSY);
default:
return SEGMENT_TYPE_ERROR;
}
}
uint32_t SegmentManager::setBit(uint64_t segmentID, uint8_t *buf,
uint64_t segmentStart,
SegmentStatus segmentStatus) {
uint32_t integer, remainder;
uint8_t tmp = 1;
integer = segmentID / 8;
remainder = segmentID % 8;
tmp = tmp << remainder;
if (segmentStatus == SEGMENT_STATUS_BUSY) {
buf[integer] |= tmp;
} else if (segmentStatus == SEGMENT_STATUS_IDLE) {
buf[integer] &= ~tmp;
} else {
return SEGMENT_STATUS_ERROR;
}
uint64_t num = integer / BLOCK_SIZE;
uint64_t blockID = num + segmentStart;
Driver::write(buf + num * BLOCK_SIZE, blockID);
return SUCCESS;
}
uint32_t SegmentManager::findFirstIdle(uint8_t *buf, uint64_t segmentNum,
uint64_t &segmentID) {
uint64_t num, place;
uint8_t res, tmp, isfound;
for (isfound = num = 0; num < segmentNum; num++) {
for (place = 0; place < 8; place++) {
tmp = 0x01 << place;
tmp = tmp & buf[num];
res = (tmp >> place);
if (res == 0) {
isfound = 1;
break;
}
}
if (isfound == 1) break;
}
if (isfound == 0) {
return SEGMENT_IS_EXHAUSTED;
}
segmentID = num * 8 + place;
return SUCCESS;
}
} // namespace LightTable

View File

@ -0,0 +1,31 @@
/**
* @file SystemTable.cc
* @brief SystemTable
* @version 0.1
* @author SYS Lab
* @date 2022.11.01
*/
#include "SystemTable.h"
namespace LightTable {
SystemTable::SystemTable(uint64_t tableID, const char *tableName,
uint64_t firstBlockID, uint64_t segmentID,
SegmentType segmentType,
std::vector<Schema::SchemaEntry> schemaEntrys,
bool usePrimaryKeyIndex)
: Table(tableID, tableName, firstBlockID, segmentID, segmentType,
schemaEntrys, usePrimaryKeyIndex)
{}
SystemTable::SystemTable(uint64_t tableID, const char *tableName,
uint64_t firstBlockID, uint64_t segmentID,
SegmentType segmentType, bool usePrimaryKeyIndex)
: Table(tableID, tableName, firstBlockID, segmentID, segmentType,
usePrimaryKeyIndex)
{}
} // namespace LightTable

View File

@ -0,0 +1,639 @@
/**
* @file Table.cc
* @brief Table
* @version 0.1
* @author SYS Lab
* @date 2022.11.01
*/
#include "Table.h"
namespace LightTable {
Table::Table(uint64_t tableID, const char *tableName, uint64_t firstBlockID,
uint64_t segmentID, SegmentType segmentType,
std::vector<Schema::SchemaEntry> schemaEntrys,
bool usePrimaryKeyIndex)
: prefetchBlockManager(firstBlockID, segmentID, segmentType),
schema(schemaEntrys),
rowMap(),
tupleNum(0),
t(time(0)),
indexLocation{TABLE1_INDEX_BLOCKID, META_ENTRY_NUM},
metaLogLocation{TABLE1_META_LOG_BLOCKID, META_ENTRY_NUM},
indexLogLocation{TABLE1_INDEX_LOG_BLOCKID, META_ENTRY_NUM},
dataLogLocation{TABLE1_DATA_LOG_BLOCKID, META_ENTRY_NUM} {
this->tableID = tableID;
memcpy(this->tableName, tableName, sizeof(tableName) + 1);
this->usePrimaryKeyIndex = usePrimaryKeyIndex;
std::map<uint64_t, Schema::SchemaEntry> allSchemaEntrys;
schema.queryAllEntry(allSchemaEntrys);
}
Table::Table(uint64_t tableID, const char *tableName, uint64_t firstBlockID,
uint64_t segmentID, SegmentType segmentType,
bool usePrimaryKeyIndex)
: prefetchBlockManager(firstBlockID, segmentID, segmentType),
schema(),
rowMap() {
this->tableID = tableID;
memcpy(this->tableName, tableName, sizeof(tableName) + 1);
// this->buf = buf;
// this->queryCache = queryCache;
// this->blockPreload = blockPreload;
this->usePrimaryKeyIndex = usePrimaryKeyIndex;
}
uint32_t Table::drop() {
uint32_t ret = SUCCESS;
ret = truncate();
if (ret != SUCCESS) {
return ret;
}
schema.drop();
// std::map<uint64_t, Schema::SchemaEntry> allSchemaEntrys;
// schema.queryAllEntry(allSchemaEntrys);
// uint64_t columnCount = allSchemaEntrys.size();
// uint64_t length = 10 + columnCount * (SCHEMA_ENTRY_SERIALIZED_LENGTH + 1);
// char *schemaData = new char[length];
// uint32_t size = 0;
// MetaHandle::serialize(allSchemaEntrys, tableID, schemaData, size);
// MetaBufferItem *schemaMetaItem = new MetaBufferItem(tableID, schemaData,
// size); buf->append(schemaMetaItem); delete[] schemaData;
return SUCCESS;
}
// uint32_t Table::truncate() {
// uint32_t size = 0;
// char *pbmData;
// MetaBufferItem *pbmMeta;
// char *hashTableData;
// MetaBufferItem *hashTableMeta;
// std::map<uint64_t, PrefetchBlockManager::PrefetchBlockManagerEntry> entrys;
// prefetchBlockManager.getAllPrefetchBlockEntrys(entrys);
// std::map<uint64_t, PrefetchBlockManager::PrefetchBlockManagerEntry>::iterator
// pbmIter = entrys.begin();
// while (pbmIter != entrys.end()) {
// prefetchBlockManager.lockBlock(pbmIter->first);
// prefetchBlockManager.setOffset(pbmIter->first, 0);
// prefetchBlockManager.unlockBlock(pbmIter->first);
// pbmData = new char[PREFETCH_BLOCK_SERIALIZED_LENGTH];
// MetaHandle::serialize(pbmIter->second, tableID, pbmData, size);
// pbmMeta = new MetaBufferItem(tableID, pbmData, size);
// // buf->append(pbmMeta);
// pbmIter++;
// }
// std::vector<HashBucket *> buckets;
// hashTable.getAllBuckets(buckets);
// for (uint32_t i = 0; i < buckets.size(); i++) {
// std::map<uint64_t, RowLocation> bucketItems;
// buckets[i]->getAllBucketItems(bucketItems);
// std::map<uint64_t, RowLocation>::iterator itemIter;
// itemIter = bucketItems.begin();
// while (itemIter != bucketItems.end()) {
// itemIter->second.blockID = 0;
// hashTableData = new char[ROWMAP_SERIALIZED_LENGTH];
// MetaHandle::serialize(
// std::pair<uint64_t, RowLocation>(itemIter->first, itemIter->second),
// tableID, hashTableData, size);
// hashTableMeta = new MetaBufferItem(tableID, hashTableData, size);
// // buf->append(hashTableMeta);
// itemIter = bucketItems.erase(itemIter);
// itemIter++;
// }
// }
// return SUCCESS;
// }
uint32_t Table::parsePrimaryKey(const uint8_t *rowData, char *primaryKeyData) {
if (strncmp(schema.getPrimaryKeySchema().type, "uint64_t", 8) == 0) {
uint64_t primaryKeyI64 = 0;
memcpy(&primaryKeyI64, rowData, schema.getPrimaryKeySchema().length);
sprintf(primaryKeyData, "%ld", primaryKeyI64);
} else if (strncmp(schema.getPrimaryKeySchema().type, "string", 6) == 0) {
memcpy(primaryKeyData, rowData, schema.getPrimaryKeySchema().length);
} else {
return TYPE_INVALID;
}
return SUCCESS;
}
uint32_t Table::insertRow(const uint8_t *rowData) {
uint32_t ret = SUCCESS;
uint64_t blockID = 0;
uint64_t blockOffset = 0;
uint8_t blockData[BLOCK_SIZE];
tupleNum++;
t = time(0);
#ifndef YCSB_TEST
blockID = prefetchBlockManager.blockAllocate(schema.getEntrySize());
while (blockID == 0) {
blockID = prefetchBlockManager.blockAllocate(schema.getEntrySize());
}
ret = prefetchBlockManager.getOffset(blockID, blockOffset);
if (ret != SUCCESS) {
// TODO allocate new seg
return ret;
}
#else
blockID = prefetchBlockManager.getNextBlock();
#endif
if (blockOffset != 0) {
Driver::read(blockData, blockID);
}
memcpy(blockData + blockOffset, rowData, schema.getEntrySize());
#ifdef SDCARD_TEST
start_time = std::chrono::steady_clock::now();
#endif
Driver::write(blockData, blockID);
#ifdef SDCARD_TEST
for (int i = 0; i < SDCARD_TEST_NUM; ++i)
Driver::write(blockData, SDCARD_TEST_WRITE_BLOCKID + 100 * i);
end_time = std::chrono::steady_clock::now();
diff_sdcard_write = std::chrono::duration_cast<std::chrono::microseconds>(
end_time - start_time)
.count();
#endif
char *primaryKeyData = new char[schema.getPrimaryKeySchema().length];
ret = parsePrimaryKey(rowData, primaryKeyData);
if (ret != SUCCESS) {
delete[] primaryKeyData;
prefetchBlockManager.unlockBlock(blockID);
return ret;
}
uint64_t key = hashTable.getMapKey(primaryKeyData);
uint32_t bucketID = hashTable.hashToBucket(key);
RowLocation rowLocation = {blockID, blockOffset};
ret = hashTable.addItem(bucketID, key, rowLocation);
if (ret != SUCCESS) {
delete[] primaryKeyData;
prefetchBlockManager.unlockBlock(blockID);
return ret;
}
#ifdef TABLE_STORAGE_SECOND_INDEX
ret = secondaryIndex.insert(primaryKeyData,
schema.getPrimaryKeySchema().length, rowLocation);
if (ret != SUCCESS) {
delete[] primaryKeyData;
prefetchBlockManager.unlockBlock(blockID);
return ret;
}
#endif
#ifndef YCSB_TEST
ret = prefetchBlockManager.advanceOffset(blockID, schema.getEntrySize());
prefetchBlockManager.setBlockState(blockID, PREFETCH_BLOCK_STATUS_IDLE);
#endif
delete[] primaryKeyData;
return ret;
}
uint32_t Table::insertRow_logging(const uint8_t *rowData) {
uint32_t ret = SUCCESS;
uint64_t blockID = 0;
uint64_t blockOffset = 0;
tupleNum++;
t = time(0);
char *primaryKeyData = new char[schema.getPrimaryKeySchema().length];
ret = parsePrimaryKey(rowData, primaryKeyData);
if (ret != SUCCESS) {
delete[] primaryKeyData;
prefetchBlockManager.unlockBlock(blockID);
return ret;
}
uint64_t key = hashTable.getMapKey(primaryKeyData);
uint32_t bucketID = hashTable.hashToBucket(key);
RowLocation rowLocation = {blockID, blockOffset};
ret = hashTable.addItem(bucketID, key, rowLocation);
if (ret != SUCCESS) {
delete[] primaryKeyData;
prefetchBlockManager.unlockBlock(blockID);
return ret;
}
metaLogEntry metaEntry{.tableID = tableID, .tupleNum = tupleNum, .t = t};
if (metaLogLocation.emptySlotNum != 0) {
memcpy(metaLog + (META_ENTRY_SIZE *
(META_ENTRY_NUM - metaLogLocation.emptySlotNum)),
&metaEntry, sizeof(metaLogEntry));
} else {
metaLogLocation.blockID++;
metaLogLocation.emptySlotNum = META_ENTRY_NUM;
memset(metaLog, 0, BLOCK_SIZE);
memcpy(metaLog, &metaEntry, sizeof(metaLogEntry));
}
Driver::write(metaLog, metaLogLocation.blockID);
metaLogLocation.emptySlotNum--;
uint32_t size = 0;
char *hashTableMetaData = new char[ROWMAP_SERIALIZED_LENGTH];
// MetaHandle::serialize(std::pair<uint64_t, RowLocation>(key, rowLocation),
// tableID, hashTableMetaData, size);
// MetaBufferItem *hashTableMeta =
// new MetaBufferItem(tableID, hashTableMetaData, size);
// if (indexLogLocation.emptySlotNum != 0) {
// memcpy(indexLog + (META_ENTRY_SIZE *
// (META_ENTRY_NUM - indexLogLocation.emptySlotNum)),
// hashTableMeta->metaItem,
// META_ENTRY_SIZE > hashTableMeta->metaItemSize
// ? hashTableMeta->metaItemSize
// : META_ENTRY_SIZE);
// } else {
// indexLogLocation.blockID++;
// indexLogLocation.emptySlotNum = META_ENTRY_NUM;
// memset(indexLog, 0, BLOCK_SIZE);
// memcpy(indexLog, hashTableMeta->metaItem,
// META_ENTRY_SIZE > hashTableMeta->metaItemSize
// ? hashTableMeta->metaItemSize
// : META_ENTRY_SIZE);
// }
Driver::write(indexLog, indexLogLocation.blockID);
indexLogLocation.emptySlotNum--;
memcpy(metaData, &tupleNum, 8);
memcpy(metaData + 8, &t, sizeof(std::time_t));
Driver::write(metaData, TABLE1_META_BLOCKID);
// if (indexLocation.emptySlotNum != 0) {
// memcpy(indexData + (META_ENTRY_SIZE *
// (META_ENTRY_NUM - indexLocation.emptySlotNum)),
// hashTableMeta->metaItem,
// META_ENTRY_SIZE > hashTableMeta->metaItemSize
// ? hashTableMeta->metaItemSize
// : META_ENTRY_SIZE);
// } else {
// indexLocation.blockID++;
// indexLocation.emptySlotNum = META_ENTRY_NUM;
// memset(indexData, 0, BLOCK_SIZE);
// memcpy(indexData, hashTableMeta->metaItem,
// META_ENTRY_SIZE > hashTableMeta->metaItemSize
// ? hashTableMeta->metaItemSize
// : META_ENTRY_SIZE);
// }
Driver::write(indexData, indexLocation.blockID);
indexLocation.emptySlotNum--;
uint8_t blockData[BLOCK_SIZE];
blockID = dataLogLocation.blockID;
memcpy(blockData, rowData, schema.getEntrySize());
Driver::write(blockData, blockID);
dataLogLocation.blockID++;
blockID = prefetchBlockManager.getNextBlock();
if (blockOffset != 0) {
Driver::read(blockData, blockID);
}
memcpy(blockData + blockOffset, rowData, schema.getEntrySize());
Driver::write(blockData, blockID);
delete[] hashTableMetaData;
// delete hashTableMeta;
delete[] primaryKeyData;
return ret;
}
uint32_t Table::deleteRow(const char *primaryKey) {
uint32_t ret = SUCCESS;
RowLocation rowLocation;
ret = locateRow(primaryKey, rowLocation);
if (ret != SUCCESS) {
return ret;
}
uint64_t deleteBlockID = rowLocation.blockID;
uint64_t deleteRowOffset = rowLocation.rowOffset;
while (prefetchBlockManager.lockBlock(rowLocation.blockID) != SUCCESS)
;
uint64_t currentOffset = 0;
ret = prefetchBlockManager.getOffset(rowLocation.blockID, currentOffset);
uint64_t key = hashTable.getMapKey(primaryKey);
if (rowLocation.rowOffset + schema.getEntrySize() != currentOffset) {
ret = deleteRowData(key, rowLocation);
if (ret != SUCCESS) {
return ret;
}
}
uint32_t size = 0;
uint32_t bucketID = hashTable.hashToBucket(key);
hashTable.deleteItem(bucketID, key);
char *hashTableMetaData = new char[ROWMAP_SERIALIZED_LENGTH];
rowLocation.blockID = 0;
// MetaHandle::serialize(std::pair<uint64_t, RowLocation>(key, rowLocation),
// tableID, hashTableMetaData, size);
// MetaBufferItem *hashTableMeta= new MetaBufferItem(tableID,
// hashTableMetaData,
// size);
// buf->append(hashTableMeta);
if (deleteRowOffset + schema.getEntrySize() != currentOffset) {
std::map<uint64_t, RowLocation> locationItems;
hashTable.refreshRowLocations(deleteBlockID, deleteRowOffset,
schema.getEntrySize(), locationItems);
// std::map<uint64_t, RowLocation>::iterator iter = locationItems.begin();
// while (iter != locationItems.end()) {
// MetaHandle::serialize(std::pair<uint64_t, RowLocation>(iter->first,
// iter->second), tableID, hashTableMetaData,
// size);
// MetaBufferItem *nextMeta= new MetaBufferItem(tableID,
// hashTableMetaData,
// size);
// buf->append(nextMeta);
// }
}
uint64_t newOffset = currentOffset - schema.getEntrySize();
prefetchBlockManager.setOffset(deleteBlockID, newOffset);
prefetchBlockManager.unlockBlock(deleteBlockID);
PrefetchBlockManager::PrefetchBlockManagerEntry blockEntry;
prefetchBlockManager.getPrefetchBlockEntry(deleteBlockID, blockEntry);
// char *pbmData = new char[PREFETCH_BLOCK_SERIALIZED_LENGTH];
// MetaHandle::serialize(blockEntry, tableID, pbmData, size);
// MetaBufferItem *pbmMeta = new MetaBufferItem(tableID, pbmData, size);
// buf->append(pbmMeta);
return SUCCESS;
}
uint32_t Table::deleteRowData(uint64_t key, RowLocation rowLocation) {
uint8_t blockData[BLOCK_SIZE];
Driver::read(blockData, rowLocation.blockID);
uint64_t start = rowLocation.rowOffset;
uint64_t nextRow = start + schema.getEntrySize();
memcpy(blockData + start, blockData + nextRow, BLOCK_SIZE - nextRow);
Driver::write(blockData, rowLocation.blockID);
return SUCCESS;
}
uint32_t Table::updateRow(const char *primaryKey, const uint8_t *rowData) {
uint32_t ret = SUCCESS;
RowLocation rowLocation;
ret = locateRow(primaryKey, rowLocation);
if (ret == BUCKET_ITEM_NOT_FOUND) {
return insertRow(rowData);
} else if (ret != SUCCESS) {
return ret;
}
uint8_t blockData[BLOCK_SIZE];
while (prefetchBlockManager.lockBlock(rowLocation.blockID) != SUCCESS)
;
Driver::read(blockData, rowLocation.blockID);
// char *undoTuple = new char[schema.getEntrySize()];
// memcpy(undoTuple, blockData+rowLocation.rowOffset, schema.getEntrySize());
// UndoLogEntry *logEntry = new UndoLogEntry(this->tableID, primaryKey,
// schema.getPrimaryKeyLength(),
// undoTuple, schema.getEntrySize(),
// rowLocation.blockID, rowLocation.rowOffset);
// buf->append(logEntry);
memcpy(blockData + rowLocation.rowOffset, rowData, schema.getEntrySize());
if (SUCCESS != Driver::write(blockData, rowLocation.blockID)) {
// memcpy(blockData + rowLocation.rowOffset, undoTuple,
// schema.getEntrySize());
// ret = UPDATE_TUPLE_ERROR;
}
// logEntry->expireUndoLog();
prefetchBlockManager.unlockBlock(rowLocation.blockID);
return ret;
}
uint32_t Table::locateRow(const char *primaryKey, RowLocation &rowLocation) {
uint32_t ret = SUCCESS;
uint64_t key = hashTable.getMapKey(primaryKey);
uint32_t bucketID = hashTable.hashToBucket(key);
ret = hashTable.getRowLocation(bucketID, key, rowLocation);
return ret;
}
uint32_t Table::selectRow(const char *primaryKey, uint8_t *rowData) {
RowLocation rowLocation;
return selectRow(primaryKey, rowData, rowLocation);
}
uint32_t Table::selectRow(const char *primaryKey, uint8_t *rowData,
RowLocation &rowLocation) {
uint32_t ret = SUCCESS;
uint8_t blockData[BLOCK_SIZE];
ret = locateRow(primaryKey, rowLocation);
if (ret != SUCCESS) {
return ret;
}
#ifndef YCSB_TEST
while (prefetchBlockManager.lockBlock(rowLocation.blockID) != SUCCESS)
;
#endif
#ifdef SDCARD_TEST
start_time = std::chrono::steady_clock::now();
#endif
Driver::read(blockData, rowLocation.blockID);
#ifdef SDCARD_TEST
for (int i = 0; i < SDCARD_TEST_NUM; ++i)
Driver::read(blockData, SDCARD_TEST_READ_BLOCKID + 100 * i);
end_time = std::chrono::steady_clock::now();
diff_sdcard_read = (std::chrono::duration_cast<std::chrono::microseconds>(
end_time - start_time)
.count());
#endif
#ifndef YCSB_TEST
prefetchBlockManager.unlockBlock(rowLocation.blockID);
#endif
ret = getRowFromBlock(primaryKey, rowData, blockData, rowLocation);
return ret;
}
uint32_t Table::getRowFromBlock(const char *primaryKey, uint8_t *rowData,
const uint8_t *blockData,
const RowLocation rowLocation) {
uint32_t ret = SUCCESS;
char *primaryKeyData = new char[schema.getPrimaryKeySchema().length];
if (rowLocation.rowOffset + schema.getEntrySize() > BLOCK_SIZE) {
delete[] primaryKeyData;
return ROWLOCATION_INVALID;
}
ret = parsePrimaryKey(blockData + rowLocation.rowOffset, primaryKeyData);
if (ret != SUCCESS) {
delete[] primaryKeyData;
return ret;
}
if (strncmp(primaryKeyData, primaryKey,
schema.getPrimaryKeySchema().length) != 0) {
delete[] primaryKeyData;
return ERROR_TABLE;
}
memcpy(rowData, blockData + rowLocation.rowOffset, schema.getEntrySize());
delete[] primaryKeyData;
return SUCCESS;
}
uint32_t Table::selectColumnItem(const char *primaryKey, const char *columnName,
uint8_t *columnData) {
uint32_t ret = SUCCESS;
uint8_t *rowData = new uint8_t[schema.getEntrySize()];
RowLocation rowLocation;
ret = selectRow(primaryKey, rowData, rowLocation);
if (ret != SUCCESS) {
delete[] rowData;
return ret;
}
uint64_t columnOffset = 0;
uint64_t columnID = 0;
uint32_t columnLength = 0;
ret = getColumnOffset(columnName, columnID, columnLength, columnOffset);
memcpy(columnData, rowData + columnOffset, columnLength);
delete[] rowData;
return SUCCESS;
}
uint32_t Table::updateColumnItem(const char *primaryKey, const char *columnName,
const uint8_t *columnData) {
uint32_t ret = SUCCESS;
uint8_t *blockData = new uint8_t[BLOCK_SIZE];
RowLocation rowLocation;
ret = locateRow(primaryKey, rowLocation);
if (ret != SUCCESS) {
return ret;
}
#ifndef YCSB_TEST
while (prefetchBlockManager.lockBlock(rowLocation.blockID) != SUCCESS)
;
#endif
Driver::read(blockData, rowLocation.blockID);
// char *undoTuple = new char[schema.getEntrySize()];
// memcpy(undoTuple, blockData+rowLocation.rowOffset, schema.getEntrySize());
// UndoLogEntry *logEntry = new UndoLogEntry(this->tableID, primaryKey,
// schema.getPrimaryKeyLength(),
// undoTuple, schema.getEntrySize(),
// rowLocation.blockID, rowLocation.rowOffset);
// buf->append(logEntry);
uint64_t columnOffset, columnID;
uint32_t columnLength;
ret = getColumnOffset(columnName, columnID, columnLength, columnOffset);
uint64_t columnStart = rowLocation.rowOffset + columnOffset;
memcpy(blockData + columnStart, columnData, columnLength);
if (SUCCESS != Driver::write(blockData, rowLocation.blockID)) {
// memcpy(blockData + rowLocation.rowOffset, undoTuple,
// schema.getEntrySize());
// ret = UPDATE_TUPLE_ERROR;
}
// logEntry->expireUndoLog();
#ifndef YCSB_TEST
prefetchBlockManager.unlockBlock(rowLocation.blockID);
#endif
delete[] blockData;
return SUCCESS;
}
uint32_t Table::updateColumnItem_logging(const char *primaryKey,
const char *columnName,
const uint8_t *columnData) {
// TODO
return SUCCESS;
}
uint32_t Table::getColumnOffset(const char *columnName, uint64_t &columnID,
uint32_t &columnLength, uint64_t &offset) {
uint32_t ret = SUCCESS;
offset = 0;
columnID = 0;
columnLength = 0;
ret = getColumnID(columnName, columnID);
if (ret != SUCCESS) {
return ret;
}
std::map<uint64_t, Schema::SchemaEntry> schemaEntrys;
ret = schema.queryAllEntry(schemaEntrys);
if (ret != SUCCESS) {
return ret;
}
columnLength = schemaEntrys[columnID].length;
for (uint64_t i = 1; i < columnID; i++) {
offset += schemaEntrys[i].length;
}
return SUCCESS;
}
uint64_t Table::getRowCount() { return hashTable.getItemCount(); }
uint64_t Table::getTableID() { return tableID; }
char *Table::getTableName() { return tableName; }
uint32_t Table::setTableID(uint64_t tableID) {
this->tableID = tableID;
return SUCCESS;
}
uint32_t Table::setTableName(const char *tableName) {
memcpy(this->tableName, tableName, sizeof(tableName) + 1);
return SUCCESS;
}
uint32_t Table::getColumnID(const char *columnName, uint64_t &columnID) {
return schema.getColumnID(columnName, columnID);
}
Schema &Table::getSchema() { return schema; }
HashTable &Table::getHashTable() { return hashTable; }
} // namespace LightTable

View File

@ -478,7 +478,7 @@ static x_err_t I2cBitSendAddress(struct I2cBus *bus, struct I2cDataStandard *msg
retries = ignore_nack ? 0 : msg->retries;
if (flags & I2C_ADDR_10BIT) {
if (flags & I2C_ADDR_10BIT_MODE) {
addr1 = 0xf0 | ((msg->addr >> 7) & 0x06);
addr2 = msg->addr & 0xff;

View File

@ -385,7 +385,7 @@ static x_err_t I2cBitSendAddress(struct I2cBus *bus, struct I2cDataStandard *msg
retries = ignore_nack ? 0 : msg->retries;
if (flags & I2C_ADDR_10BIT) {
if (flags & I2C_ADDR_10BIT_MODE) {
addr1 = 0xf0 | ((msg->addr >> 7) & 0x06);
addr2 = msg->addr & 0xff;

View File

@ -376,7 +376,7 @@ static x_err_t I2cBitSendAddress(struct I2cBus *bus, struct I2cDataStandard *msg
retries = ignore_nack ? 0 : msg->retries;
if (flags & I2C_ADDR_10BIT) {
if (flags & I2C_ADDR_10BIT_MODE) {
addr1 = 0xf0 | ((msg->addr >> 7) & 0x06);
addr2 = msg->addr & 0xff;

View File

@ -34,6 +34,10 @@ Modification:
#include <hc32_ll.h>
#include <connect_usart.h>
#ifdef BSP_USING_GPIO
#include <connect_gpio.h>
#endif
#ifdef BSP_USING_SDIO
#include <connect_sdio.h>
#endif
@ -42,6 +46,10 @@ Modification:
#include <connect_spi.h>
#endif
#ifdef BSP_USING_I2C
#include <connect_i2c.h>
#endif
#ifdef BSP_USING_USB
#include <connect_usb.h>
#endif
@ -145,12 +153,18 @@ void SysTick_Handler(void)
struct InitSequenceDesc _board_init[] =
{
#ifdef BSP_USING_GPIO
{ "hw_pin", HwGpioInit },
#endif
#ifdef BSP_USING_SDIO
{ "sdio", HwSdioInit },
#endif
#ifdef BSP_USING_SPI
{ "spi", HwSpiInit },
#endif
#ifdef BSP_USING_I2C
{ "i2c", HwI2cInit },
#endif
#ifdef BSP_USING_USB
{ "usb", HwUsbHostInit },
#endif

View File

@ -9,4 +9,8 @@ export APPLFLAGS := -mcpu=cortex-m4 -mthumb -mfpu=fpv4-sp-d16 -mfloat-abi=hard -
export DEFINES := -DHAVE_CCONFIG_H -DHC32F4A0 -DUSE_DDL_DRIVER -DHAVE_SIGINFO
ifeq ($(CONFIG_RESOURCES_LWIP), y)
export LINK_LWIP := $(KERNEL_ROOT)/resources/ethernet/LwIP/liblwip.a
endif
export ARCH = arm

View File

@ -6,6 +6,22 @@ menuconfig BSP_USING_UART
source "$BSP_DIR/third_party_driver/usart/Kconfig"
endif
menuconfig BSP_USING_GPIO
bool "Using GPIO device "
default y
select RESOURCES_PIN
if BSP_USING_GPIO
source "$BSP_DIR/third_party_driver/gpio/Kconfig"
endif
menuconfig BSP_USING_LWIP
bool "Using LwIP by ethernet device"
default n
select RESOURCES_LWIP
if BSP_USING_LWIP
source "$BSP_DIR/third_party_driver/ethernet/Kconfig"
endif
menuconfig BSP_USING_SPI
bool "Using SPI device"
default n
@ -14,6 +30,14 @@ menuconfig BSP_USING_SPI
source "$BSP_DIR/third_party_driver/spi/Kconfig"
endif
menuconfig BSP_USING_I2C
bool "Using I2C device"
default n
select RESOURCES_I2C
if BSP_USING_I2C
source "$BSP_DIR/third_party_driver/i2c/Kconfig"
endif
menuconfig BSP_USING_SDIO
bool "Using SD CARD device"
default n

View File

@ -4,10 +4,22 @@ ifeq ($(CONFIG_BSP_USING_UART),y)
SRC_DIR += usart
endif
ifeq ($(CONFIG_BSP_USING_GPIO),y)
SRC_DIR += gpio
endif
ifeq ($(CONFIG_BSP_USING_LWIP),y)
SRC_DIR += ethernet
endif
ifeq ($(CONFIG_BSP_USING_SPI),y)
SRC_DIR += spi
endif
ifeq ($(CONFIG_BSP_USING_I2C),y)
SRC_DIR += i2c
endif
ifeq ($(CONFIG_BSP_USING_SDIO),y)
SRC_DIR += sdio
endif

View File

@ -12,6 +12,14 @@ ifeq ($(CONFIG_BSP_USING_SPI),y)
SRC_FILES += hc32_ll_spi.c
endif
ifeq ($(CONFIG_BSP_USING_I2C),y)
SRC_FILES += hc32_ll_i2c.c
endif
ifeq ($(CONFIG_BSP_USING_LWIP),y)
SRC_FILES += hc32_ll_eth.c
endif
ifeq ($(CONFIG_BSP_USING_USB),y)
SRC_FILES += hc32_ll_usb.c
endif

View File

@ -0,0 +1,3 @@
SRC_FILES := ethernetif.c
include $(KERNEL_ROOT)/compiler.mk

View File

@ -0,0 +1,783 @@
/**
*******************************************************************************
* @file eth/eth_loopback/source/ethernetif.c
* @brief This file implements Ethernet network interface drivers.
@verbatim
Change Logs:
Date Author Notes
2022-03-31 CDT First version
@endverbatim
*******************************************************************************
* Copyright (C) 2022, Xiaohua Semiconductor Co., Ltd. All rights reserved.
*
* This software component is licensed by XHSC 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
*
*******************************************************************************
*/
/**
* @file ethernetif.c
* @brief support hc32f4a0-board ethernetif function and register to Lwip
* @version 3.0
* @author AIIT XUOS Lab
* @date 2022-12-05
*/
/*************************************************
File name: ethernetif.c
Description: support hc32f4a0-board ethernetif configure and register to Lwip
Others: take projects\ev_hc32f4a0_lqfp176\examples\eth\eth_loopback\source\ethernetif.c for references
History:
1. Date: 2022-12-05
Author: AIIT XUOS Lab
Modification:
1include harware_ethernetif.hhc32_ll_eth.hhc32_ll_gpio.hhc32_ll_utility.hhc32_ll_fcg.h and lwip H files;
2modify ethernetif_init as err_t;
3add ETH_RST_PORT and ETH_RST_PIN;
4add ETH_LINK_LED_PORT and ETH_LINK_LED_PIN;
5add ethernetif_config_enet_set;
6add ETHERNET_LOOPBACK_TEST with testnetif and txPbuf.
*************************************************/
/*******************************************************************************
* Include files
******************************************************************************/
#include <hardware_ethernetif.h>
#include <hc32_ll_eth.h>
#include <hc32_ll_gpio.h>
#include <hc32_ll_utility.h>
#include <hc32_ll_fcg.h>
#include <lwip/timeouts.h>
#include <netif/etharp.h>
/**
* @addtogroup HC32F4A0_DDL_Examples
* @{
*/
/**
* @addtogroup ETH_Loopback
* @{
*/
/*******************************************************************************
* Local type definitions ('typedef')
******************************************************************************/
/*******************************************************************************
* Local pre-processor symbols/macros ('#define')
******************************************************************************/
/* Define those to better describe your network interface. */
#define IFNAME0 'h'
#define IFNAME1 'd'
/* PHY hardware reset time */
#define PHY_HW_RST_DELAY (0x40U)
/* ETH_RST = PH11 */
#define ETH_RST_PORT (GPIO_PORT_H)
#define ETH_RST_PIN (GPIO_PIN_11)
/* ETH_LINK_LED = PD00 LED2 */
#define ETH_LINK_LED_PORT (GPIO_PORT_D)
#define ETH_LINK_LED_PIN (GPIO_PIN_00)
//#define ETHERNET_LOOPBACK_TEST
#ifdef ETHERNET_LOOPBACK_TEST
#define USER_KEY_PORT (GPIO_PORT_I)
#define USER_KEY_PIN (GPIO_PIN_07)
/* ethe global netif */
static struct netif testnetif;
/* eth tx buffer */
static struct pbuf txPbuf;
static char txBuf[] = "Ethernet Loop-Back Test";
#endif
/*******************************************************************************
* Global variable definitions (declared in header file with 'extern')
******************************************************************************/
/*******************************************************************************
* Local function prototypes ('static')
******************************************************************************/
/*******************************************************************************
* Local variable definitions ('static')
******************************************************************************/
/* Global Ethernet handle*/
static stc_eth_handle_t EthHandle;
/* Ethernet Tx DMA Descriptor */
__ALIGN_BEGIN static stc_eth_dma_desc_t EthDmaTxDscrTab[ETH_TX_BUF_NUM];
/* Ethernet Rx DMA Descriptor */
__ALIGN_BEGIN static stc_eth_dma_desc_t EthDmaRxDscrTab[ETH_RX_BUF_NUM];
/* Ethernet Transmit Buffer */
__ALIGN_BEGIN static uint8_t EthTxBuff[ETH_TX_BUF_NUM][ETH_TX_BUF_SIZE];
/* Ethernet Receive Buffer */
__ALIGN_BEGIN static uint8_t EthRxBuff[ETH_RX_BUF_NUM][ETH_RX_BUF_SIZE];
/* Ethernet link status */
static uint8_t u8PhyLinkStatus = 0U, u8EthInitStatus = 0U;
/*******************************************************************************
* Function implementation - global ('extern') and local ('static')
******************************************************************************/
/**
* @defgroup ETH_IF_Global_Functions Ethernet Interface Global Functions
* @{
*/
void *ethernetif_config_enet_set(uint8_t enet_port)
{
return NONE;
}
void Time_Update_LwIP(void)
{
//no need to do
}
/**
* @brief Initializes the Ethernet GPIO.
* @param None
* @retval None
*/
static void Ethernet_GpioInit(void)
{
/* ETH_RST */
stc_gpio_init_t stcGpioInit;
(void)GPIO_StructInit(&stcGpioInit);
stcGpioInit.u16PinState = PIN_STAT_RST;
stcGpioInit.u16PinDir = PIN_DIR_OUT;
(void)GPIO_Init(ETH_RST_PORT, ETH_RST_PIN, &stcGpioInit);
GPIO_ResetPins(ETH_RST_PORT, ETH_RST_PIN);
SysTick_Delay(PHY_HW_RST_DELAY);
GPIO_SetPins(ETH_RST_PORT, ETH_RST_PIN);
SysTick_Delay(PHY_HW_RST_DELAY);
/* ETH_LINK_LED LED2 */
(void)GPIO_StructInit(&stcGpioInit);
stcGpioInit.u16PinState = PIN_STAT_RST;
stcGpioInit.u16PinDir = PIN_DIR_OUT;
(void)GPIO_Init(ETH_LINK_LED_PORT, ETH_LINK_LED_PIN, &stcGpioInit);
GPIO_ResetPins(ETH_LINK_LED_PORT, ETH_LINK_LED_PIN);
/* Configure MII/RMII selection IO for ETH */
#ifdef ETH_INTERFACE_RMII
/* Ethernet RMII pins configuration */
/*
ETH_SMI_MDIO ----------------> PA2
ETH_SMI_MDC -----------------> PC1
ETH_RMII_TX_EN --------------> PG11
ETH_RMII_TXD0 ---------------> PG13
ETH_RMII_TXD1 ---------------> PG14
ETH_RMII_REF_CLK ------------> PA1
ETH_RMII_CRS_DV -------------> PA7
ETH_RMII_RXD0 ---------------> PC4
ETH_RMII_RXD1 ---------------> PC5
ETH_RMII_RX_ER --------------> PI10
*/
/* Configure PA1, PA2 and PA7 */
GPIO_SetFunc(GPIO_PORT_A, (GPIO_PIN_01 | GPIO_PIN_02 | GPIO_PIN_07), GPIO_FUNC_11);
/* Configure PC1, PC4 and PC5 */
GPIO_SetFunc(GPIO_PORT_C, (GPIO_PIN_01 | GPIO_PIN_04 | GPIO_PIN_05), GPIO_FUNC_11);
/* Configure PG11, PG13 and PG14 */
GPIO_SetFunc(GPIO_PORT_G, (GPIO_PIN_11 | GPIO_PIN_13 | GPIO_PIN_14), GPIO_FUNC_11);
/* Configure PI10 */
GPIO_SetFunc(GPIO_PORT_I, GPIO_PIN_10, GPIO_FUNC_11);
#else
/* Ethernet MII pins configuration */
/*
ETH_SMI_MDIO ----------------> PA2
ETH_SMI_MDC -----------------> PC1
ETH_MII_TX_CLK --------------> PB6
ETH_MII_TX_EN ---------------> PG11
ETH_MII_TXD0 ----------------> PG13
ETH_MII_TXD1 ----------------> PG14
ETH_MII_TXD2 ----------------> PB9
ETH_MII_TXD3 ----------------> PB8
ETH_MII_RX_CLK --------------> PA1
ETH_MII_RX_DV ---------------> PA7
ETH_MII_RXD0 ----------------> PC4
ETH_MII_RXD1 ----------------> PC5
ETH_MII_RXD2 ----------------> PB0
ETH_MII_RXD3 ----------------> PB1
ETH_MII_RX_ER ---------------> PI10
ETH_MII_CRS -----------------> PH2
ETH_MII_COL -----------------> PH3
*/
/* Configure PA1, PA2 and PA7 */
GPIO_SetFunc(GPIO_PORT_A, (GPIO_PIN_01 | GPIO_PIN_02 | GPIO_PIN_07), GPIO_FUNC_11);
/* Configure PB0, PB1, PB6, PB8 and PB9 */
GPIO_SetFunc(GPIO_PORT_B, (GPIO_PIN_00 | GPIO_PIN_01 | GPIO_PIN_06 | GPIO_PIN_08 | GPIO_PIN_09), GPIO_FUNC_11);
/* Configure PC1, PC4 and PC5 */
GPIO_SetFunc(GPIO_PORT_C, (GPIO_PIN_01 | GPIO_PIN_04 | GPIO_PIN_05), GPIO_FUNC_11);
/* Configure PG11, PG13 and PG14 */
GPIO_SetFunc(GPIO_PORT_G, (GPIO_PIN_11 | GPIO_PIN_13 | GPIO_PIN_14), GPIO_FUNC_11);
/* Configure PH2, PH3 */
GPIO_SetFunc(GPIO_PORT_H, (GPIO_PIN_02 | GPIO_PIN_03), GPIO_FUNC_11);
/* Configure PI10 */
GPIO_SetFunc(GPIO_PORT_I, GPIO_PIN_10, GPIO_FUNC_11);
#endif
}
/**
* @brief In this function, the hardware should be initialized.
* @param netif The already initialized network interface structure for this ethernetif.
* @retval int32_t:
* - LL_OK: Initialize success
* - LL_ERR: Initialize failed
*/
static int32_t low_level_init(struct netif *netif)
{
int32_t i32Ret = LL_ERR;
stc_eth_init_t stcEthInit;
uint16_t u16RegVal;
/* Enable ETH clock */
FCG_Fcg1PeriphClockCmd(FCG1_PERIPH_ETHMAC, ENABLE);
/* Init Ethernet GPIO */
Ethernet_GpioInit();
/* Reset ETHERNET */
(void)ETH_DeInit();
/* Configure structure initialization */
(void)ETH_CommStructInit(&EthHandle.stcCommInit);
(void)ETH_StructInit(&stcEthInit);
#ifdef ETH_INTERFACE_RMII
EthHandle.stcCommInit.u32Interface = ETH_MAC_IF_RMII;
#else
EthHandle.stcCommInit.u32Interface = ETH_MAC_IF_MII;
#endif
stcEthInit.stcMacInit.u32ReceiveAll = ETH_MAC_RX_ALL_ENABLE;
/* Configure ethernet peripheral */
if (LL_OK == ETH_Init(&EthHandle, &stcEthInit)) {
u8EthInitStatus = 1U;
i32Ret = LL_OK;
}
#ifdef ETHERNET_LOOPBACK_TEST
/* Enable PHY loopback */
(void)ETH_PHY_LoopBackCmd(&EthHandle, ENABLE);
#endif
/* Initialize Tx Descriptors list: Chain Mode */
(void)ETH_DMA_TxDescListInit(&EthHandle, EthDmaTxDscrTab, &EthTxBuff[0][0], ETH_TX_BUF_NUM);
/* Initialize Rx Descriptors list: Chain Mode */
(void)ETH_DMA_RxDescListInit(&EthHandle, EthDmaRxDscrTab, &EthRxBuff[0][0], ETH_RX_BUF_NUM);
/* set MAC hardware address length */
netif->hwaddr_len = 6U;
/* set MAC hardware address */
netif->hwaddr[0] = (EthHandle.stcCommInit).au8MacAddr[0];
netif->hwaddr[1] = (EthHandle.stcCommInit).au8MacAddr[1];
netif->hwaddr[2] = (EthHandle.stcCommInit).au8MacAddr[2];
netif->hwaddr[3] = (EthHandle.stcCommInit).au8MacAddr[3];
netif->hwaddr[4] = (EthHandle.stcCommInit).au8MacAddr[4];
netif->hwaddr[5] = (EthHandle.stcCommInit).au8MacAddr[5];
/* maximum transfer unit */
netif->mtu = 1500U;
/* Enable MAC and DMA transmission and reception */
(void)ETH_Start();
/* Configure PHY LED mode */
u16RegVal = PHY_PAGE_ADDR_7;
(void)ETH_PHY_WriteReg(&EthHandle, PHY_PSR, u16RegVal);
(void)ETH_PHY_ReadReg(&EthHandle, PHY_P7_IWLFR, &u16RegVal);
MODIFY_REG16(u16RegVal, PHY_LED_SELECT, PHY_LED_SELECT_10);
(void)ETH_PHY_WriteReg(&EthHandle, PHY_P7_IWLFR, u16RegVal);
u16RegVal = PHY_PAGE_ADDR_0;
(void)ETH_PHY_WriteReg(&EthHandle, PHY_PSR, u16RegVal);
#ifdef ETH_INTERFACE_RMII
/* Disable Power Saving Mode */
(void)ETH_PHY_ReadReg(&EthHandle, PHY_PSMR, &u16RegVal);
CLR_REG16_BIT(u16RegVal, PHY_EN_PWR_SAVE);
(void)ETH_PHY_WriteReg(&EthHandle, PHY_PSMR, u16RegVal);
/* Configure PHY to generate an interrupt when Eth Link state changes */
u16RegVal = PHY_PAGE_ADDR_7;
(void)ETH_PHY_WriteReg(&EthHandle, PHY_PSR, u16RegVal);
/* Enable Interrupt on change of link status */
(void)ETH_PHY_ReadReg(&EthHandle, PHY_P7_IWLFR, &u16RegVal);
SET_REG16_BIT(u16RegVal, PHY_INT_LINK_CHANGE);
(void)ETH_PHY_WriteReg(&EthHandle, PHY_P7_IWLFR, u16RegVal);
u16RegVal = PHY_PAGE_ADDR_0;
(void)ETH_PHY_WriteReg(&EthHandle, PHY_PSR, u16RegVal);
#endif
return i32Ret;
}
/**
* @brief This function should do the actual transmission of the packet.
* @param netif The network interface structure for this ethernetif.
* @param p The MAC packet to send.
* @retval int32_t:
* - LL_OK: The packet could be sent
* - LL_ERR: The packet couldn't be sent
*/
int32_t low_level_output(struct netif *netif, struct pbuf *p)
{
int32_t i32Ret;
struct pbuf *q;
uint8_t *txBuffer;
__IO stc_eth_dma_desc_t *DmaTxDesc;
uint32_t byteCnt;
uint32_t frameLength = 0UL;
uint32_t bufferOffset;
uint32_t payloadOffset;
DmaTxDesc = EthHandle.stcTxDesc;
txBuffer = (uint8_t *)((EthHandle.stcTxDesc)->u32Buf1Addr);
bufferOffset = 0UL;
/* Copy frame from pbufs to driver buffers */
for (q = p; q != NULL; q = q->next) {
/* If this buffer isn't available, goto error */
if (0UL != (DmaTxDesc->u32ControlStatus & ETH_DMA_TXDESC_OWN)) {
i32Ret = LL_ERR;
goto error;
}
/* Get bytes in current buffer */
byteCnt = q->len;
payloadOffset = 0UL;
/* Check if the length of data to copy is bigger than Tx buffer size */
while ((byteCnt + bufferOffset) > ETH_TX_BUF_SIZE) {
/* Copy data to Tx buffer*/
(void)memcpy((uint8_t *) & (txBuffer[bufferOffset]), (uint8_t *) & (((uint8_t *)q->payload)[payloadOffset]), (ETH_TX_BUF_SIZE - bufferOffset));
/* Point to next descriptor */
DmaTxDesc = (stc_eth_dma_desc_t *)(DmaTxDesc->u32Buf2NextDescAddr);
/* Check if the buffer is available */
if (0UL != (DmaTxDesc->u32ControlStatus & ETH_DMA_TXDESC_OWN)) {
i32Ret = LL_ERR;
goto error;
}
txBuffer = (uint8_t *)(DmaTxDesc->u32Buf1Addr);
byteCnt = byteCnt - (ETH_TX_BUF_SIZE - bufferOffset);
payloadOffset = payloadOffset + (ETH_TX_BUF_SIZE - bufferOffset);
frameLength = frameLength + (ETH_TX_BUF_SIZE - bufferOffset);
bufferOffset = 0UL;
}
/* Copy the remaining bytes */
(void)memcpy((uint8_t *) & (txBuffer[bufferOffset]), (uint8_t *) & (((uint8_t *)q->payload)[payloadOffset]), byteCnt);
bufferOffset = bufferOffset + byteCnt;
frameLength = frameLength + byteCnt;
}
/* Prepare transmit descriptors to give to DMA */
(void)ETH_DMA_SetTransFrame(&EthHandle, frameLength);
i32Ret = LL_OK;
error:
/* When Transmit Underflow flag is set, clear it and issue a Transmit Poll Demand to resume transmission */
if (RESET != ETH_DMA_GetStatus(ETH_DMA_FLAG_UNS)) {
/* Clear DMA UNS flag */
ETH_DMA_ClearStatus(ETH_DMA_FLAG_UNS);
/* Resume DMA transmission */
WRITE_REG32(CM_ETH->DMA_TXPOLLR, 0UL);
}
return i32Ret;
}
/**
* @brief Should allocate a pbuf and transfer the bytes of the incoming packet from the interface into the pbuf.
* @param netif The network interface structure for this ethernetif.
* @retval A pbuf filled with the received packet (including MAC header) or NULL on memory error.
*/
static struct pbuf *low_level_input(struct netif *netif)
{
struct pbuf *p = NULL;
struct pbuf *q;
uint32_t len;
uint8_t *rxBuffer;
__IO stc_eth_dma_desc_t *DmaRxDesc;
uint32_t byteCnt;
uint32_t bufferOffset;
uint32_t payloadOffset;
uint32_t i;
/* Get received frame */
if (LL_OK != ETH_DMA_GetReceiveFrame(&EthHandle)) {
return NULL;
}
/* Obtain the size of the packet */
len = (EthHandle.stcRxFrame).u32Len;
rxBuffer = (uint8_t *)(EthHandle.stcRxFrame).u32Buf;
if (len > 0UL) {
/* Allocate a pbuf chain of pbufs from the buffer */
p = (struct pbuf *)malloc(sizeof(struct pbuf) + len);
if (NULL != p) {
p->next = NULL;
p->payload = &((uint8_t *)p)[sizeof(struct pbuf)];
p->len = len;
(void)memset(p->payload, 0, p->len);
}
}
if (p != NULL) {
DmaRxDesc = (EthHandle.stcRxFrame).pstcFSDesc;
bufferOffset = 0UL;
for (q = p; q != NULL; q = q->next) {
byteCnt = q->len;
payloadOffset = 0UL;
/* Check if the length of bytes to copy in current pbuf is bigger than Rx buffer size */
while ((byteCnt + bufferOffset) > ETH_RX_BUF_SIZE) {
/* Copy data to pbuf */
(void)memcpy((uint8_t *) & (((uint8_t *)q->payload)[payloadOffset]), (uint8_t *) & (rxBuffer[bufferOffset]), (ETH_RX_BUF_SIZE - bufferOffset));
/* Point to next descriptor */
DmaRxDesc = (stc_eth_dma_desc_t *)(DmaRxDesc->u32Buf2NextDescAddr);
rxBuffer = (uint8_t *)(DmaRxDesc->u32Buf1Addr);
byteCnt = byteCnt - (ETH_RX_BUF_SIZE - bufferOffset);
payloadOffset = payloadOffset + (ETH_RX_BUF_SIZE - bufferOffset);
bufferOffset = 0UL;
}
/* Copy remaining data in pbuf */
(void)memcpy((uint8_t *) & (((uint8_t *)q->payload)[payloadOffset]), (uint8_t *) & (rxBuffer[bufferOffset]), byteCnt);
bufferOffset = bufferOffset + byteCnt;
}
}
/* Release descriptors to DMA */
DmaRxDesc = (EthHandle.stcRxFrame).pstcFSDesc;
for (i = 0UL; i < (EthHandle.stcRxFrame).u32SegCount; i++) {
DmaRxDesc->u32ControlStatus |= ETH_DMA_RXDESC_OWN;
DmaRxDesc = (stc_eth_dma_desc_t *)(DmaRxDesc->u32Buf2NextDescAddr);
}
/* Clear Segment_Count */
(EthHandle.stcRxFrame).u32SegCount = 0UL;
/* When Rx Buffer unavailable flag is set, clear it and resume reception */
if (RESET != ETH_DMA_GetStatus(ETH_DMA_FLAG_RUS)) {
/* Clear DMA RUS flag */
ETH_DMA_ClearStatus(ETH_DMA_FLAG_RUS);
/* Resume DMA reception */
WRITE_REG32(CM_ETH->DMA_RXPOLLR, 0UL);
}
return p;
}
/**
* @brief Should be called at the beginning of the program to set up the network interface.
* @param netif The network interface structure for this ethernetif.
* @retval err_t:
* - LL_OK: The IF is initialized
* - LL_ERR: The IF is uninitialized
*/
err_t ethernetif_init(struct netif *netif)
{
netif->name[0] = IFNAME0;
netif->name[1] = IFNAME1;
/* initialize the hardware */
return low_level_init(netif);
}
/**
* @brief This function should be called when a packet is ready to be read from the interface.
* @param netif The network interface structure for this ethernetif.
* @retval None
*/
void ethernetif_input(struct netif *netif)
{
struct pbuf *p;
/* Move received packet into a new pbuf */
p = low_level_input(netif);
/* No packet could be read, silently ignore this */
if (p != NULL) {
EthernetIF_InputCallback(netif, p);
free(p);
}
}
/**
* @brief Check the netif link status.
* @param netif the network interface
* @retval None
*/
void EthernetIF_CheckLink(struct netif *netif)
{
uint16_t u16RegVal = 0U;
static uint8_t u8PreStatus = 0U;
if (1U == u8EthInitStatus) {
u8EthInitStatus = 0U;
u8PhyLinkStatus = ETH_LINK_UP;
u8PreStatus = 1U;
/* Notify link status change */
EthernetIF_NotifyLinkChange(netif);
} else {
/* Read PHY_BSR */
(void)ETH_PHY_ReadReg(&EthHandle, PHY_BSR, &u16RegVal);
/* Check whether the link is up or down*/
if ((0x0000U != u16RegVal) && (0xFFFFU != u16RegVal)) {
if ((0U != (u16RegVal & PHY_LINK_STATUS)) && (0U == u8PreStatus)) {
u8PhyLinkStatus = ETH_LINK_UP;
u8PreStatus = 1U;
EthernetIF_LinkCallback(netif);
}
if ((0U == (u16RegVal & PHY_LINK_STATUS)) && (1U == u8PreStatus)) {
u8PhyLinkStatus = ETH_LINK_DOWN;
u8PreStatus = 0U;
EthernetIF_LinkCallback(netif);
}
}
}
}
/**
* @brief Update the netif link status.
* @param netif The network interface.
* @retval None
*/
void EthernetIF_UpdateLink(struct netif *netif)
{
uint16_t u16RegVal;
if (1U == u8EthInitStatus) {
u8EthInitStatus = 0U;
u8PhyLinkStatus = ETH_LINK_UP;
/* Notify link status change */
EthernetIF_NotifyLinkChange(netif);
} else {
u16RegVal = PHY_PAGE_ADDR_0;
(void)ETH_PHY_WriteReg(&EthHandle, PHY_PSR, u16RegVal);
/* Read PHY_IISDR */
(void)ETH_PHY_ReadReg(&EthHandle, PHY_IISDR, &u16RegVal);
/* Check whether the link interrupt has occurred or not */
if (0U != (u16RegVal & PHY_FLAG_LINK_STATUS_CHANGE)) {
/* Read PHY_BSR */
(void)ETH_PHY_ReadReg(&EthHandle, PHY_BSR, &u16RegVal);
if ((0x0000U != u16RegVal) && (0xFFFFU != u16RegVal)) {
if (ETH_LINK_UP != u8PhyLinkStatus) {
/* Wait until the auto-negotiation will be completed */
SysTick_Delay(2U);
(void)ETH_PHY_ReadReg(&EthHandle, PHY_BSR, &u16RegVal);
}
/* Check whether the link is up or down*/
if (0U != (u16RegVal & PHY_LINK_STATUS)) {
u8PhyLinkStatus = ETH_LINK_UP;
} else {
u8PhyLinkStatus = ETH_LINK_DOWN;
}
EthernetIF_LinkCallback(netif);
}
}
}
}
/**
* @brief Ethernet interface periodic handle
* @param netif The network interface
* @retval None
*/
void EthernetIF_PeriodicHandle(struct netif *netif)
{
#ifndef ETH_INTERFACE_RMII
uint32_t curTick;
static uint32_t u32LinkTimer = 0UL;
curTick = SysTick_GetTick();
/* Check link status periodically */
if ((curTick - u32LinkTimer) >= LINK_TIMER_INTERVAL) {
u32LinkTimer = curTick;
EthernetIF_CheckLink(netif);
}
#endif /* ETH_INTERFACE_RMII */
}
/**
* @brief Link callback function
* @note This function is called on change of link status to update low level driver configuration.
* @param netif The network interface
* @retval None
*/
void EthernetIF_LinkCallback(struct netif *netif)
{
__IO uint32_t tickStart = 0UL;
uint16_t u16RegVal = 0U;
int32_t i32negoResult = LL_ERR;
if (ETH_LINK_UP == u8PhyLinkStatus) {
/* Restart the auto-negotiation */
if (ETH_AUTO_NEGO_DISABLE != (EthHandle.stcCommInit).u16AutoNego) {
/* Enable Auto-Negotiation */
(void)ETH_PHY_ReadReg(&EthHandle, PHY_BCR, &u16RegVal);
u16RegVal |= PHY_AUTONEGOTIATION;
(void)ETH_PHY_WriteReg(&EthHandle, PHY_BCR, u16RegVal);
/* Wait until the auto-negotiation will be completed */
tickStart = SysTick_GetTick();
do {
(void)ETH_PHY_ReadReg(&EthHandle, PHY_BSR, &u16RegVal);
if (PHY_AUTONEGO_COMPLETE == (u16RegVal & PHY_AUTONEGO_COMPLETE)) {
break;
}
/* Check for the Timeout (3s) */
} while ((SysTick_GetTick() - tickStart) <= 3000U);
if (PHY_AUTONEGO_COMPLETE == (u16RegVal & PHY_AUTONEGO_COMPLETE)) {
i32negoResult = LL_OK;
/* Configure ETH duplex mode according to the result of automatic negotiation */
if (0U != (u16RegVal & (PHY_100BASE_TX_FD | PHY_10BASE_T_FD))) {
(EthHandle.stcCommInit).u32DuplexMode = ETH_MAC_DUPLEX_MD_FULL;
} else {
(EthHandle.stcCommInit).u32DuplexMode = ETH_MAC_DUPLEX_MD_HALF;
}
/* Configure ETH speed according to the result of automatic negotiation */
if (0U != (u16RegVal & (PHY_100BASE_TX_FD | PHY_100BASE_TX_HD))) {
(EthHandle.stcCommInit).u32Speed = ETH_MAC_SPEED_100M;
} else {
(EthHandle.stcCommInit).u32Speed = ETH_MAC_SPEED_10M;
}
}
}
/* AutoNegotiation disable or failed*/
if (LL_ERR == i32negoResult) {
(void)ETH_PHY_ReadReg(&EthHandle, PHY_BCR, &u16RegVal);
CLR_REG16_BIT(u16RegVal, PHY_FULLDUPLEX_100M);
/* Set MAC Speed and Duplex Mode to PHY */
(void)ETH_PHY_WriteReg(&EthHandle, PHY_BCR,
((uint16_t)((EthHandle.stcCommInit).u32DuplexMode >> 3U) |
(uint16_t)((EthHandle.stcCommInit).u32Speed >> 1U) | u16RegVal));
}
/* ETH MAC Re-Configuration */
ETH_MAC_SetDuplexSpeed((EthHandle.stcCommInit).u32DuplexMode, (EthHandle.stcCommInit).u32Speed);
/* Restart MAC interface */
(void)ETH_Start();
} else {
/* Stop MAC interface */
(void)ETH_Stop();
}
/* Notify link status change */
EthernetIF_NotifyLinkChange(netif);
}
/**
* @brief Ethernet interface periodic handle
* @param netif The network interface
* @retval int32_t:
* - LL_OK: The IF is link up
* - LL_ERR: The IF is link down
*/
int32_t EthernetIF_IsLinkUp(struct netif *netif)
{
return (0U != u8PhyLinkStatus) ? LL_OK : LL_ERR;
}
/**
* @brief Notify link status change.
* @param netif The network interface
* @retval None
*/
__WEAKDEF void EthernetIF_NotifyLinkChange(struct netif *netif)
{
/* This is function could be implemented in user file when the callback is needed */
if (LL_OK == EthernetIF_IsLinkUp(netif)) {
GPIO_SetPins(ETH_LINK_LED_PORT, ETH_LINK_LED_PIN);
} else {
GPIO_ResetPins(ETH_LINK_LED_PORT, ETH_LINK_LED_PIN);
}
}
/**
* @brief Input data handle callback.
* @param netif The network interface structure for this ethernetif
* @param p The MAC packet to receive
* @retval None
*/
__WEAKDEF void EthernetIF_InputCallback(struct netif *netif, struct pbuf *p)
{
/* This is function could be implemented in user file when the callback is needed */
#ifdef ETHERNET_LOOPBACK_TEST
if ((0 == (memcmp(p->payload, txPbuf.payload, p->len))) && (p->len == txPbuf.len)) {
KPrintf("eth receive data OK! \r\n");
KPrintf("receive data %d %s\n", p->len, p->payload);
} else {
KPrintf("eth receive data error! \r\n");
}
#endif
}
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
#ifdef ETHERNET_LOOPBACK_TEST
static void EthLoopBackTask(void *parameter)
{
while (1) {
if (RESET == GPIO_ReadInputPins(USER_KEY_PORT, USER_KEY_PIN)) {
KPrintf("ready to send eth data\n");
if (LL_OK != low_level_output(&testnetif, &txPbuf)) {
KPrintf("eth send data error! \r\n");
}
}
//KPrintf("ready to receive eth loop back data\n");
/* Read a received packet */
ethernetif_input(&testnetif);
/* Handle periodic timers */
EthernetIF_PeriodicHandle(&testnetif);
}
}
static void EthLoopBackTest(void)
{
x_err_t ret = EOK;
stc_gpio_init_t stcGpioInit;
/* KEY initialize */
(void)GPIO_StructInit(&stcGpioInit);
stcGpioInit.u16PinState = PIN_STAT_RST;
stcGpioInit.u16PinDir = PIN_DIR_IN;
(void)GPIO_Init(USER_KEY_PORT, USER_KEY_PIN, &stcGpioInit);
GPIO_ResetPins(USER_KEY_PORT, USER_KEY_PIN);
/* Configure the Ethernet */
(void)ethernetif_init(&testnetif);
/* fill data to txPbuf */
txPbuf.next = NULL;
txPbuf.payload = txBuf;
txPbuf.len = strlen(txBuf);
int eth_loopback_task = 0;
eth_loopback_task = KTaskCreate("eth_loopback", EthLoopBackTask, NONE,
2048, 8);
if(eth_loopback_task < 0) {
KPrintf("eth_loopback_task create failed ...%s %d.\n", __FUNCTION__,__LINE__);
return;
}
StartupKTask(eth_loopback_task);
return;
}
SHELL_EXPORT_CMD(SHELL_CMD_PERMISSION(0)|SHELL_CMD_TYPE(SHELL_TYPE_CMD_MAIN),
EthLoopBackTest, EthLoopBackTest, EthLoopBackTest);
#endif
/******************************************************************************
* EOF (not truncated)
*****************************************************************************/

View File

@ -0,0 +1,11 @@
config PIN_BUS_NAME
string "pin bus name"
default "pin"
config PIN_DRIVER_NAME
string "pin driver name"
default "pin_drv"
config PIN_DEVICE_NAME
string "pin device name"
default "pin_dev"

View File

@ -0,0 +1,3 @@
SRC_FILES := connect_gpio.c
include $(KERNEL_ROOT)/compiler.mk

View File

@ -0,0 +1,795 @@
/*
* Copyright (c) 2006-2022, RT-Thread Development Team
*******************************************************************************
* Copyright (C) 2022, Xiaohua Semiconductor Co., Ltd. All rights reserved.
*
* This software component is licensed by XHSC 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
*
*******************************************************************************
*/
/**
* @file connect_gpio.c
* @brief support hc32f4a0-board gpio function using bus driver framework
* @version 3.0
* @author AIIT XUOS Lab
* @date 2022-12-05
*/
/*************************************************
File name: connect_gpio.c
Description: support hc32f4a0-board gpio configure and gpio bus register function
Others: take projects/ev_hc32f4a0_lqfp176/examples/gpio/gpio_output/source/main.c for references
History:
1. Date: 2022-12-05
Author: AIIT XUOS Lab
Modification:
1. support hc32f4a0-board gpio configure, write and read
2. support hc32f4a0-board gpio bus device and driver register
*************************************************/
#include <connect_gpio.h>
#define GPIO_PIN_INDEX(pin) ((uint8_t)((pin) & 0x0F))
#define ITEM_NUM(items) sizeof(items) / sizeof(items[0])
#ifndef HC32_PIN_CONFIG
#define HC32_PIN_CONFIG(pin, callback, config) \
{ \
.pinbit = pin, \
.irq_callback = callback, \
.irq_config = config, \
}
#endif /* HC32_PIN_CONFIG */
#define __HC32_PIN(index, gpio_port, gpio_pin) { 0, GPIO_PORT_##gpio_port, GPIO_PIN_##gpio_pin}
#define __HC32_PIN_DEFAULT {-1, 0, 0}
struct PinIndex
{
int index;
uint8_t port;
uint16_t pin;
};
static void EXTINT0_IRQHandler(void);
static void EXTINT1_IRQHandler(void);
static void EXTINT2_IRQHandler(void);
static void EXTINT3_IRQHandler(void);
static void EXTINT4_IRQHandler(void);
static void EXTINT5_IRQHandler(void);
static void EXTINT6_IRQHandler(void);
static void EXTINT7_IRQHandler(void);
static void EXTINT8_IRQHandler(void);
static void EXTINT9_IRQHandler(void);
static void EXTINT10_IRQHandler(void);
static void EXTINT11_IRQHandler(void);
static void EXTINT12_IRQHandler(void);
static void EXTINT13_IRQHandler(void);
static void EXTINT14_IRQHandler(void);
static void EXTINT15_IRQHandler(void);
static struct Hc32PinIrqMap pin_irq_map[] =
{
HC32_PIN_CONFIG(GPIO_PIN_00, EXTINT0_IRQHandler, EXTINT0_IRQ_CONFIG),
HC32_PIN_CONFIG(GPIO_PIN_01, EXTINT1_IRQHandler, EXTINT1_IRQ_CONFIG),
HC32_PIN_CONFIG(GPIO_PIN_02, EXTINT2_IRQHandler, EXTINT2_IRQ_CONFIG),
HC32_PIN_CONFIG(GPIO_PIN_03, EXTINT3_IRQHandler, EXTINT3_IRQ_CONFIG),
HC32_PIN_CONFIG(GPIO_PIN_04, EXTINT4_IRQHandler, EXTINT4_IRQ_CONFIG),
HC32_PIN_CONFIG(GPIO_PIN_05, EXTINT5_IRQHandler, EXTINT5_IRQ_CONFIG),
HC32_PIN_CONFIG(GPIO_PIN_06, EXTINT6_IRQHandler, EXTINT6_IRQ_CONFIG),
HC32_PIN_CONFIG(GPIO_PIN_07, EXTINT7_IRQHandler, EXTINT7_IRQ_CONFIG),
HC32_PIN_CONFIG(GPIO_PIN_08, EXTINT8_IRQHandler, EXTINT8_IRQ_CONFIG),
HC32_PIN_CONFIG(GPIO_PIN_09, EXTINT9_IRQHandler, EXTINT9_IRQ_CONFIG),
HC32_PIN_CONFIG(GPIO_PIN_10, EXTINT10_IRQHandler, EXTINT10_IRQ_CONFIG),
HC32_PIN_CONFIG(GPIO_PIN_11, EXTINT11_IRQHandler, EXTINT11_IRQ_CONFIG),
HC32_PIN_CONFIG(GPIO_PIN_12, EXTINT12_IRQHandler, EXTINT12_IRQ_CONFIG),
HC32_PIN_CONFIG(GPIO_PIN_13, EXTINT13_IRQHandler, EXTINT13_IRQ_CONFIG),
HC32_PIN_CONFIG(GPIO_PIN_14, EXTINT14_IRQHandler, EXTINT14_IRQ_CONFIG),
HC32_PIN_CONFIG(GPIO_PIN_15, EXTINT15_IRQHandler, EXTINT15_IRQ_CONFIG),
};
static const struct PinIndex pins[] =
{
__HC32_PIN_DEFAULT,
__HC32_PIN(1, E, 02),
__HC32_PIN(2, E, 03),
__HC32_PIN(3, E, 04),
__HC32_PIN(4, E, 05),
__HC32_PIN(5, E, 06),
__HC32_PIN_DEFAULT,
__HC32_PIN(7, I, 08),
__HC32_PIN_DEFAULT,
__HC32_PIN(9, C, 14),
__HC32_PIN(10, C, 15),
__HC32_PIN(11, I, 09),
__HC32_PIN(12, I, 10),
__HC32_PIN(13, I, 11),
__HC32_PIN_DEFAULT,
__HC32_PIN_DEFAULT,
__HC32_PIN(16, F, 00),
__HC32_PIN(17, F, 01),
__HC32_PIN(18, F, 02),
__HC32_PIN(19, F, 03),
__HC32_PIN(20, F, 04),
__HC32_PIN(21, F, 05),
__HC32_PIN_DEFAULT,
__HC32_PIN_DEFAULT,
__HC32_PIN(24, F, 06),
__HC32_PIN(25, F, 07),
__HC32_PIN(26, F, 08),
__HC32_PIN(27, F, 09),
__HC32_PIN(28, F, 10),
__HC32_PIN(29, H, 00),
__HC32_PIN(30, H, 01),
__HC32_PIN_DEFAULT,
__HC32_PIN(32, C, 00),
__HC32_PIN(33, C, 01),
__HC32_PIN(34, C, 02),
__HC32_PIN(35, C, 03),
__HC32_PIN_DEFAULT,
__HC32_PIN_DEFAULT,
__HC32_PIN_DEFAULT,
__HC32_PIN_DEFAULT,
__HC32_PIN(40, A, 00),
__HC32_PIN(41, A, 01),
__HC32_PIN(42, A, 02),
__HC32_PIN(43, H, 02),
__HC32_PIN(44, H, 03),
__HC32_PIN(45, H, 04),
__HC32_PIN(46, H, 05),
__HC32_PIN(47, A, 03),
__HC32_PIN_DEFAULT,
__HC32_PIN_DEFAULT,
__HC32_PIN(50, A, 04),
__HC32_PIN(51, A, 05),
__HC32_PIN(52, A, 06),
__HC32_PIN(53, A, 07),
__HC32_PIN(54, C, 04),
__HC32_PIN(55, C, 05),
__HC32_PIN(56, B, 00),
__HC32_PIN(57, B, 01),
__HC32_PIN(58, B, 02),
__HC32_PIN(59, F, 11),
__HC32_PIN(60, F, 12),
__HC32_PIN_DEFAULT,
__HC32_PIN_DEFAULT,
__HC32_PIN(63, F, 13),
__HC32_PIN(64, F, 14),
__HC32_PIN(65, F, 15),
__HC32_PIN(66, G, 00),
__HC32_PIN(67, G, 01),
__HC32_PIN(68, E, 07),
__HC32_PIN(69, E, 08),
__HC32_PIN(70, E, 09),
__HC32_PIN_DEFAULT,
__HC32_PIN_DEFAULT,
__HC32_PIN(73, E, 10),
__HC32_PIN(74, E, 11),
__HC32_PIN(75, E, 12),
__HC32_PIN(76, E, 13),
__HC32_PIN(77, E, 14),
__HC32_PIN(78, E, 15),
__HC32_PIN(79, B, 10),
__HC32_PIN(80, B, 11),
__HC32_PIN_DEFAULT,
__HC32_PIN_DEFAULT,
__HC32_PIN(83, H, 06),
__HC32_PIN(84, H, 07),
__HC32_PIN(85, H, 08),
__HC32_PIN(86, H, 09),
__HC32_PIN(87, H, 10),
__HC32_PIN(88, H, 11),
__HC32_PIN(89, H, 12),
__HC32_PIN_DEFAULT,
__HC32_PIN_DEFAULT,
__HC32_PIN(92, B, 12),
__HC32_PIN(93, B, 13),
__HC32_PIN(94, B, 14),
__HC32_PIN(95, B, 15),
__HC32_PIN(96, D, 08),
__HC32_PIN(97, D, 09),
__HC32_PIN(98, D, 10),
__HC32_PIN(99, D, 11),
__HC32_PIN(100, D, 12),
__HC32_PIN(101, D, 13),
__HC32_PIN_DEFAULT,
__HC32_PIN_DEFAULT,
__HC32_PIN(104, D, 14),
__HC32_PIN(105, D, 15),
__HC32_PIN(106, G, 02),
__HC32_PIN(107, G, 03),
__HC32_PIN(108, G, 04),
__HC32_PIN(109, G, 05),
__HC32_PIN(110, G, 06),
__HC32_PIN(111, G, 07),
__HC32_PIN(112, G, 08),
__HC32_PIN_DEFAULT,
__HC32_PIN_DEFAULT,
__HC32_PIN(115, C, 06),
__HC32_PIN(116, C, 07),
__HC32_PIN(117, C, 08),
__HC32_PIN(118, C, 09),
__HC32_PIN(119, A, 08),
__HC32_PIN(120, A, 09),
__HC32_PIN(121, A, 10),
__HC32_PIN(122, A, 11),
__HC32_PIN(123, A, 12),
__HC32_PIN(124, A, 13),
__HC32_PIN_DEFAULT,
__HC32_PIN_DEFAULT,
__HC32_PIN_DEFAULT,
__HC32_PIN(128, H, 13),
__HC32_PIN(129, H, 14),
__HC32_PIN(130, H, 15),
__HC32_PIN(131, I, 00),
__HC32_PIN(132, I, 01),
__HC32_PIN(133, I, 02),
__HC32_PIN(134, I, 03),
__HC32_PIN_DEFAULT,
__HC32_PIN_DEFAULT,
__HC32_PIN(137, A, 14),
__HC32_PIN(138, A, 15),
__HC32_PIN(139, C, 10),
__HC32_PIN(140, C, 11),
__HC32_PIN(141, C, 12),
__HC32_PIN(142, D, 00),
__HC32_PIN(143, D, 01),
__HC32_PIN(144, D, 02),
__HC32_PIN(145, D, 03),
__HC32_PIN(146, D, 04),
__HC32_PIN(147, D, 05),
__HC32_PIN_DEFAULT,
__HC32_PIN_DEFAULT,
__HC32_PIN(150, D, 06),
__HC32_PIN(151, D, 07),
__HC32_PIN(152, G, 09),
__HC32_PIN(153, G, 10),
__HC32_PIN(154, G, 11),
__HC32_PIN(155, G, 12),
__HC32_PIN(156, G, 13),
__HC32_PIN(157, G, 14),
__HC32_PIN_DEFAULT,
__HC32_PIN_DEFAULT,
__HC32_PIN(160, G, 15),
__HC32_PIN(161, B, 03),
__HC32_PIN(162, B, 04),
__HC32_PIN(163, B, 05),
__HC32_PIN(164, B, 06),
__HC32_PIN(165, B, 07),
__HC32_PIN(166, I, 13),
__HC32_PIN(167, B, 08),
__HC32_PIN(168, B, 09),
__HC32_PIN(169, E, 00),
__HC32_PIN(170, E, 01),
__HC32_PIN(171, I, 12),
__HC32_PIN_DEFAULT,
__HC32_PIN(173, I, 04),
__HC32_PIN(174, I, 05),
__HC32_PIN(175, I, 06),
__HC32_PIN(176, I, 07),
};
struct PinIrqHdr pin_irq_hdr_tab[] =
{
{-1, 0, NONE, NONE},
{-1, 0, NONE, NONE},
{-1, 0, NONE, NONE},
{-1, 0, NONE, NONE},
{-1, 0, NONE, NONE},
{-1, 0, NONE, NONE},
{-1, 0, NONE, NONE},
{-1, 0, NONE, NONE},
{-1, 0, NONE, NONE},
{-1, 0, NONE, NONE},
{-1, 0, NONE, NONE},
{-1, 0, NONE, NONE},
{-1, 0, NONE, NONE},
{-1, 0, NONE, NONE},
{-1, 0, NONE, NONE},
{-1, 0, NONE, NONE}
};
static void PinIrqHandler(uint16_t pinbit)
{
int32_t irqindex = -1;
if (SET == EXTINT_GetExtIntStatus(pinbit))
{
EXTINT_ClearExtIntStatus(pinbit);
irqindex = __CLZ(__RBIT(pinbit));
if (pin_irq_hdr_tab[irqindex].hdr) {
pin_irq_hdr_tab[irqindex].hdr(pin_irq_hdr_tab[irqindex].args);
}
}
}
static void EXTINT0_IRQHandler(void)
{
PinIrqHandler(pin_irq_map[0].pinbit);
}
static void EXTINT1_IRQHandler(void)
{
PinIrqHandler(pin_irq_map[1].pinbit);
}
static void EXTINT2_IRQHandler(void)
{
PinIrqHandler(pin_irq_map[2].pinbit);
}
static void EXTINT3_IRQHandler(void)
{
PinIrqHandler(pin_irq_map[3].pinbit);
}
static void EXTINT4_IRQHandler(void)
{
PinIrqHandler(pin_irq_map[4].pinbit);
}
static void EXTINT5_IRQHandler(void)
{
PinIrqHandler(pin_irq_map[5].pinbit);
}
static void EXTINT6_IRQHandler(void)
{
PinIrqHandler(pin_irq_map[6].pinbit);
}
static void EXTINT7_IRQHandler(void)
{
PinIrqHandler(pin_irq_map[7].pinbit);
}
static void EXTINT8_IRQHandler(void)
{
PinIrqHandler(pin_irq_map[8].pinbit);
}
static void EXTINT9_IRQHandler(void)
{
PinIrqHandler(pin_irq_map[9].pinbit);
}
static void EXTINT10_IRQHandler(void)
{
PinIrqHandler(pin_irq_map[10].pinbit);
}
static void EXTINT11_IRQHandler(void)
{
PinIrqHandler(pin_irq_map[11].pinbit);
}
static void EXTINT12_IRQHandler(void)
{
PinIrqHandler(pin_irq_map[12].pinbit);
}
static void EXTINT13_IRQHandler(void)
{
PinIrqHandler(pin_irq_map[13].pinbit);
}
static void EXTINT14_IRQHandler(void)
{
PinIrqHandler(pin_irq_map[14].pinbit);
}
static void EXTINT15_IRQHandler(void)
{
PinIrqHandler(pin_irq_map[15].pinbit);
}
const struct PinIndex *GetPin(uint8_t pin)
{
const struct PinIndex *index;
if (pin < ITEM_NUM(pins)) {
index = &pins[pin];
if (index->index == -1)
index = NONE;
} else {
index = NONE;
}
return index;
}
static int32 GpioConfigMode(int mode, const struct PinIndex* index)
{
stc_gpio_init_t stcGpioInit;
NULL_PARAM_CHECK(index);
GPIO_StructInit(&stcGpioInit);
switch (mode)
{
case GPIO_CFG_OUTPUT:
stcGpioInit.u16PinDir = PIN_DIR_OUT;
stcGpioInit.u16PinOutputType = PIN_OUT_TYPE_CMOS;
break;
case GPIO_CFG_INPUT:
stcGpioInit.u16PinDir = PIN_DIR_IN;
break;
case GPIO_CFG_INPUT_PULLUP:
stcGpioInit.u16PinDir = PIN_DIR_IN;
stcGpioInit.u16PullUp = PIN_PU_ON;
break;
case GPIO_CFG_INPUT_PULLDOWN:
stcGpioInit.u16PinDir = PIN_DIR_IN;
stcGpioInit.u16PullUp = PIN_PU_OFF;
break;
case GPIO_CFG_OUTPUT_OD:
stcGpioInit.u16PinDir = PIN_DIR_OUT;
stcGpioInit.u16PinOutputType = PIN_OUT_TYPE_NMOS;
break;
default:
break;
}
GPIO_Init(index->pin, index->pin, &stcGpioInit);
}
static int32 GpioIrqRegister(int32 pin, int32 mode, void (*hdr)(void *args), void *args)
{
const struct PinIndex *index = GetPin(pin);
int32 irqindex = -1;
irqindex = GPIO_PIN_INDEX(index->pin);
if (irqindex >= ITEM_NUM(pin_irq_map)) {
return -ENONESYS;
}
x_base level = CriticalAreaLock();
if (pin_irq_hdr_tab[irqindex].pin == pin &&
pin_irq_hdr_tab[irqindex].hdr == hdr &&
pin_irq_hdr_tab[irqindex].mode == mode &&
pin_irq_hdr_tab[irqindex].args == args
) {
CriticalAreaUnLock(level);
return EOK;
}
if (pin_irq_hdr_tab[irqindex].pin != -1) {
CriticalAreaUnLock(level);
return -EDEV_BUSY;
}
pin_irq_hdr_tab[irqindex].pin = pin;
pin_irq_hdr_tab[irqindex].hdr = hdr;
pin_irq_hdr_tab[irqindex].mode = mode;
pin_irq_hdr_tab[irqindex].args = args;
CriticalAreaUnLock(level);
return EOK;
}
static uint32 GpioIrqFree(x_base pin)
{
const struct PinIndex* index = GetPin(pin);
int32 irqindex = -1;
irqindex = GPIO_PIN_INDEX(index->pin);
if (irqindex >= ITEM_NUM(pin_irq_map)) {
return -ENONESYS;
}
x_base level = CriticalAreaLock();
if (pin_irq_hdr_tab[irqindex].pin == -1) {
CriticalAreaUnLock(level);
return EOK;
}
pin_irq_hdr_tab[irqindex].pin = -1;
pin_irq_hdr_tab[irqindex].hdr = NONE;
pin_irq_hdr_tab[irqindex].mode = 0;
pin_irq_hdr_tab[irqindex].args = NONE;
CriticalAreaUnLock(level);
return EOK;
}
static void GpioIrqConfig(uint8_t u8Port, uint16_t u16Pin, uint16_t u16ExInt)
{
__IO uint16_t *PCRx;
uint16_t pin_num;
pin_num = __CLZ(__RBIT(u16Pin));
PCRx = (__IO uint16_t *)((uint32_t)(&CM_GPIO->PCRA0) + ((uint32_t)u8Port * 0x40UL) + (pin_num * 4UL));
MODIFY_REG16(*PCRx, GPIO_PCR_INTE, u16ExInt);
}
static int32 GpioIrqEnable(x_base pin)
{
struct Hc32PinIrqMap *irq_map;
const struct PinIndex* index = GetPin(pin);
int32 irqindex = -1;
stc_extint_init_t stcExtIntInit;
irqindex = GPIO_PIN_INDEX(index->pin);
if (irqindex >= ITEM_NUM(pin_irq_map)) {
return -ENONESYS;
}
x_base level = CriticalAreaLock();
if (pin_irq_hdr_tab[irqindex].pin == -1) {
CriticalAreaUnLock(level);
return -ENONESYS;
}
/* Extint config */
EXTINT_StructInit(&stcExtIntInit);
switch (pin_irq_hdr_tab[irqindex].mode)
{
case GPIO_IRQ_EDGE_RISING:
stcExtIntInit.u32Edge = EXTINT_TRIG_RISING;
break;
case GPIO_IRQ_EDGE_FALLING:
stcExtIntInit.u32Edge = EXTINT_TRIG_FALLING;
break;
case GPIO_IRQ_EDGE_BOTH:
stcExtIntInit.u32Edge = EXTINT_TRIG_BOTH;
break;
case GPIO_IRQ_LEVEL_LOW:
stcExtIntInit.u32Edge = EXTINT_TRIG_LOW;
break;
}
EXTINT_Init(index->pin, &stcExtIntInit);
NVIC_EnableIRQ(irq_map->irq_config.irq_num);
GpioIrqConfig(index->pin, index->pin, PIN_EXTINT_ON);
CriticalAreaUnLock(level);
return EOK;
}
static int32 GpioIrqDisable(x_base pin)
{
struct Hc32PinIrqMap *irq_map;
const struct PinIndex* index = GetPin(pin);
x_base level = CriticalAreaLock();
GpioIrqConfig(index->pin, index->pin, PIN_EXTINT_OFF);
NVIC_DisableIRQ(irq_map->irq_config.irq_num);
CriticalAreaUnLock(level);
return EOK;
}
static uint32 Hc32PinConfigure(struct PinParam *param)
{
NULL_PARAM_CHECK(param);
uint32 ret = EOK;
const struct PinIndex *index = GetPin(param->pin);
switch(param->cmd)
{
case GPIO_CONFIG_MODE:
GpioConfigMode(param->mode, index);
break;
case GPIO_IRQ_REGISTER:
ret = GpioIrqRegister(param->pin, param->irq_set.irq_mode, param->irq_set.hdr, param->irq_set.args);
break;
case GPIO_IRQ_FREE:
ret = GpioIrqFree(param->pin);
break;
case GPIO_IRQ_ENABLE:
ret = GpioIrqEnable(param->pin);
break;
case GPIO_IRQ_DISABLE:
ret = GpioIrqDisable(param->pin);
break;
default:
ret = -EINVALED;
break;
}
return ret;
}
static uint32 Hc32PinInit(void)
{
static x_bool pin_init_flag = RET_FALSE;
if (!pin_init_flag) {
pin_init_flag = RET_TRUE;
}
return EOK;
}
static uint32 Hc32GpioDrvConfigure(void *drv, struct BusConfigureInfo *configure_info)
{
NULL_PARAM_CHECK(drv);
NULL_PARAM_CHECK(configure_info);
x_err_t ret = EOK;
struct PinParam *param;
switch (configure_info->configure_cmd)
{
case OPE_INT:
ret = Hc32PinInit();
break;
case OPE_CFG:
param = (struct PinParam *)configure_info->private_data;
ret = Hc32PinConfigure(param);
break;
default:
break;
}
return ret;
}
uint32 Hc32PinWrite(void *dev, struct BusBlockWriteParam *write_param)
{
NULL_PARAM_CHECK(dev);
NULL_PARAM_CHECK(write_param);
struct PinStat *pinstat = (struct PinStat *)write_param->buffer;
const struct PinIndex* index = GetPin(pinstat->pin);
NULL_PARAM_CHECK(index);
if (GPIO_LOW == pinstat->val) {
GPIO_ResetPins(index->pin, index->pin);
} else {
GPIO_SetPins(index->pin, index->pin);
}
return EOK;
}
uint32 Hc32PinRead(void *dev, struct BusBlockReadParam *read_param)
{
NULL_PARAM_CHECK(dev);
NULL_PARAM_CHECK(read_param);
struct PinStat *pinstat = (struct PinStat *)read_param->buffer;
const struct PinIndex* index = GetPin(pinstat->pin);
NULL_PARAM_CHECK(index);
if(GPIO_ReadInputPins(index->pin, index->pin) == PIN_RESET) {
pinstat->val = GPIO_LOW;
} else {
pinstat->val = GPIO_HIGH;
}
return pinstat->val;
}
static const struct PinDevDone dev_done =
{
.open = NONE,
.close = NONE,
.write = Hc32PinWrite,
.read = Hc32PinRead,
};
int HwGpioInit(void)
{
x_err_t ret = EOK;
static struct PinBus pin;
memset(&pin, 0, sizeof(struct PinBus));
ret = PinBusInit(&pin, PIN_BUS_NAME);
if (ret != EOK) {
KPrintf("gpio bus init error %d\n", ret);
return ERROR;
}
static struct PinDriver drv;
memset(&drv, 0, sizeof(struct PinDriver));
drv.configure = &Hc32GpioDrvConfigure;
ret = PinDriverInit(&drv, PIN_DRIVER_NAME, NONE);
if (ret != EOK) {
KPrintf("pin driver init error %d\n", ret);
return ERROR;
}
ret = PinDriverAttachToBus(PIN_DRIVER_NAME, PIN_BUS_NAME);
if (ret != EOK) {
KPrintf("pin driver attach error %d\n", ret);
return ERROR;
}
static struct PinHardwareDevice dev;
memset(&dev, 0, sizeof(struct PinHardwareDevice));
dev.dev_done = &dev_done;
ret = PinDeviceRegister(&dev, NONE, PIN_DEVICE_NAME);
if (ret != EOK) {
KPrintf("pin device register error %d\n", ret);
return ERROR;
}
ret = PinDeviceAttachToBus(PIN_DEVICE_NAME, PIN_BUS_NAME);
if (ret != EOK) {
KPrintf("pin device register error %d\n", ret);
return ERROR;
}
return ret;
}
//#define GPIO_LED_TEST
#ifdef GPIO_LED_TEST
static void GpioLedDelay(void)
{
volatile uint32_t i = 0;
for (i = 0; i < 8000000; ++i)
{
__asm("NOP"); /* delay */
}
}
void GpioLedTest(void)
{
BusType pin;
struct BusConfigureInfo configure_info;
struct BusBlockWriteParam write_param;
int ret = 0;
int pinSet = -1;
pin = BusFind(PIN_BUS_NAME);
if (!pin) {
KPrintf("find %s failed!\n", PIN_BUS_NAME);
return;
}
pin->owner_driver = BusFindDriver(pin, PIN_DRIVER_NAME);
pin->owner_haldev = BusFindDevice(pin, PIN_DEVICE_NAME);
configure_info.configure_cmd = OPE_INT;
ret = BusDrvConfigure(pin->owner_driver, &configure_info);
if (ret != EOK) {
KPrintf("initialize %s failed!\n", PIN_BUS_NAME);
return;
}
struct PinParam led_gpio_param;
struct PinStat led_gpio_stat;
// 134 -> PortI Pin03 LED3
x_base pinIndex = 134;
led_gpio_param.cmd = GPIO_CONFIG_MODE;
led_gpio_param.pin = pinIndex;
led_gpio_param.mode = GPIO_CFG_OUTPUT;
configure_info.configure_cmd = OPE_CFG;
configure_info.private_data = (void *)&led_gpio_param;
ret = BusDrvConfigure(pin->owner_driver, &configure_info);
if (ret != EOK) {
KPrintf("config pin failed!\n");
return;
}
while (1) {
GpioLedDelay();
if (pinSet) {
/* set led pin as high*/
led_gpio_stat.pin = pinIndex;
led_gpio_stat.val = GPIO_HIGH;
write_param.buffer = (void *)&led_gpio_stat;
BusDevWriteData(pin->owner_haldev, &write_param);
pinSet = 0;
} else {
/* set led pin as low*/
led_gpio_stat.pin = pinIndex;
led_gpio_stat.val = GPIO_LOW;
write_param.buffer = (void *)&led_gpio_stat;
BusDevWriteData(pin->owner_haldev, &write_param);
pinSet = 1;
}
}
}
SHELL_EXPORT_CMD(SHELL_CMD_PERMISSION(0)|SHELL_CMD_TYPE(SHELL_TYPE_CMD_MAIN),
GpioLedTest, GpioLedTest, gpio led test);
#endif

View File

@ -0,0 +1,22 @@
config I2C_BUS_NAME_1
string "i2c 1 bus name"
default "i2c1"
config I2C_DRV_NAME_1
string "i2c bus 1 driver name"
default "i2c1_drv"
config I2C_1_DEVICE_NAME_0
string "i2c bus 1 device 0 name"
default "i2c1_dev0"
config I2C_DEVICE_MODE
bool "choose i2c device mode as master or slave"
default y
choice
prompt "choose i2c mode"
default I2C_DEVICE_MASTER
config I2C_DEVICE_MASTER
bool "set i2c master"
config I2C_DEVICE_SLAVE
bool "set i2c slave"
endchoice

Some files were not shown because too many files have changed in this diff Show More