This is an automated email from Gerrit. "Ryan QIAN <jianghao.q...@outlook.com>" just uploaded a new patch set to Gerrit, which you can find at https://review.openocd.org/c/openocd/+/7931
-- gerrit commit 0991ecd34a9a126302d4a874db250bf42f5f183a Author: Ryan QIAN <jianghao.q...@hpmicro.com> Date: Sat Oct 7 18:25:12 2023 +0800 contrib/loaders/flash/hpmicro: add hpmicro device xpi support - add xpi flash support for hpmicro devices Change-Id: If48f8e08f294adf6e7ea6670b22679d4b597314c Signed-off-by: Ryan QIAN <jianghao.q...@hpmicro.com> diff --git a/contrib/loaders/flash/hpmicro/Makefile b/contrib/loaders/flash/hpmicro/Makefile new file mode 100644 index 0000000000..1b3ea9865d --- /dev/null +++ b/contrib/loaders/flash/hpmicro/Makefile @@ -0,0 +1,51 @@ +# Copyright (c) 2023 HPMicro +# SPDX-License-Identifier: BSD-3-Clause +# +BIN2C = ../../../../src/helper/bin2char.sh + + +PROJECT=hpm_xpi_flash +CROSS_COMPILE ?= riscv32-unknown-elf- +CC=$(CROSS_COMPILE)gcc +AS=$(CROSS_COMPILE)gcc +OBJCOPY=$(CROSS_COMPILE)objcopy +OBJDUMP=$(CROSS_COMPILE)objdump +LD=$(CROSS_COMPILE)ld +LDSCRIPT=linker.ld + +OPT=-O3 + +ASFLAGS= +CFLAGS=$(OPT) -fomit-frame-pointer -Wall +LDFLAGS=-nostartfiles -T$(LDSCRIPT) -Wl,-Map=$(PROJECT).map -static -Wl,--gc-sections +OBJS=$(ASRC:.S=.o) $(SRC:.c=.o) + +SRC=openocd_flash_algo.c +ASRC=func_table.S + +all: $(OBJS) $(PROJECT).elf $(PROJECT).bin $(PROJECT).lst $(PROJECT).inc + +%o: %c + @$(CC) -c $(CFLAGS) -I . $< -o $@ + +%o: %S + @$(AS) -c $(ASFLAGS) -I . $< -o $@ + +%elf: $(OBJS) + @$(CC) $(OBJS) $(LDFLAGS) -o $@ + +%lst: %elf + @$(OBJDUMP) -h -S $< > $@ + +%bin: %elf + @$(OBJCOPY) -Obinary $< $@ + +%inc: %bin + $(BIN2C) < $< > $@ + +clean: + @-rm -f *.o *.elf *.lst *.bin *.inc + +.PHONY: all clean + +.INTERMEDIATE: $(patsubst %.S,%.o,$(SRCS)) $(patsubst %.S,%.elf,$(SRCS)) $(patsubst %.S,%.bin,$(SRCS)) diff --git a/contrib/loaders/flash/hpmicro/func_table.S b/contrib/loaders/flash/hpmicro/func_table.S new file mode 100644 index 0000000000..66394317b5 --- /dev/null +++ b/contrib/loaders/flash/hpmicro/func_table.S @@ -0,0 +1,23 @@ +/* + * Copyright (c) 2021 HPMicro + * + * SPDX-License-Identifier: BSD-3-Clause + * + */ + .section .func_table, "ax" + .global _init +_init: + jal flash_init + ebreak + jal flash_erase + ebreak + jal flash_program + ebreak + jal flash_read + ebreak + jal flash_get_info + ebreak + jal flash_erase_chip + ebreak + jal flash_deinit + ebreak diff --git a/contrib/loaders/flash/hpmicro/hpm_common.h b/contrib/loaders/flash/hpmicro/hpm_common.h new file mode 100644 index 0000000000..f4852b1368 --- /dev/null +++ b/contrib/loaders/flash/hpmicro/hpm_common.h @@ -0,0 +1,283 @@ +/* + * Copyright (c) 2021-2023 HPMicro + * + * SPDX-License-Identifier: BSD-3-Clause + * + */ + +#ifndef _HPM_COMMON_H +#define _HPM_COMMON_H + +#include <assert.h> +#include <stdbool.h> +#include <stdint.h> +#include <string.h> +#include <stdlib.h> + +/** + * + * @brief COMMON driver APIs + * @defgroup common_interface COMMON driver APIs + * @{ + * + */ + +#define __R volatile const /* Define "read-only" permission */ +#define __RW volatile /* Define "read-write" permission */ +#define __W volatile /* Define "write-only" permission */ + +#ifndef __I +#define __I __R +#endif + +#ifndef __IO +#define __IO __RW +#endif + +#ifndef __O +#define __O __W +#endif + +#ifndef ARRAY_SIZE +#define ARRAY_SIZE(a) (sizeof(a) / sizeof((a)[0])) +#endif + +#ifndef MAX +#define MAX(a, b) ((a) > (b) ? (a) : (b)) +#endif +#ifndef MIN +#define MIN(a, b) ((a) < (b) ? (a) : (b)) +#endif + +#define HPM_BITSMASK(val, offset) ((uint32_t)(val) << (offset)) +#define IS_HPM_BITMASK_SET(val, mask) (((uint32_t)(val) & (uint32_t)(mask)) != 0U) +#define IS_HPM_BIT_SET(val, offset) (((uint32_t)(val) & (1UL << (offset))) != 0U) +#define IS_HPM_BITMASK_CLR(val, mask) (((uint32_t)(val) & (uint32_t)(mask)) == 0U) +#define IS_HPM_BIT_CLR(val, offset) (((uint32_t)(val) & (1UL << (offset))) == 0U) + +#define HPM_BREAK_IF(cond) do {if (cond) break;} while(0) +#define HPM_CONTINUE_IF(cond) do {if (cond) continue;} while(0) + +#define HPM_CHECK_RET(x) \ + do { \ + stat = (x); \ + if (status_success != stat) { \ + return stat; \ + } \ + } while (false) + +#define SIZE_1KB (1024UL) +#define SIZE_1MB (1048576UL) + +typedef uint32_t hpm_stat_t; + +/* @brief Enum definition for the Status group + * Rule: + * [Group] 0-999 for the SoC driver and the corresponding components + * 1000 or above for the application status group + * [Code] Valid value: 0-999 + * + */ +#define MAKE_STATUS(group, code) ((uint32_t)(group)*1000U + (uint32_t)(code)) +/* @brief System status group definitions */ +enum { + status_group_common = 0, + status_group_uart = 1, + status_group_i2c = 2, + status_group_spi = 3, + status_group_usb = 4, + status_group_i2s = 5, + status_group_xpi = 6, + status_group_l1c, + status_group_dma, + status_group_femc, + status_group_sdp, + status_group_xpi_nor, + status_group_otp, + status_group_lcdc, + status_group_mbx, + status_group_rng, + status_group_pdma, + status_group_wdg, + status_group_pmic_sec, + status_group_can, + status_group_sdxc, + status_group_pcfg, + status_group_clk, + status_group_pllctl, + status_group_pllctlv2, + status_group_ffa, + status_group_mcan, + + status_group_middleware_start = 500, + status_group_sdmmc = status_group_middleware_start, + status_group_audio_codec, + status_group_dma_manager, +}; + +/* @brief Common status code definitions */ +enum { + status_success = MAKE_STATUS(status_group_common, 0), + status_fail = MAKE_STATUS(status_group_common, 1), + status_invalid_argument = MAKE_STATUS(status_group_common, 2), + status_timeout = MAKE_STATUS(status_group_common, 3), +}; + +#if defined(__GNUC__) + +/* alway_inline */ +#define ATTR_ALWAYS_INLINE __attribute__((always_inline)) + +/* weak */ +#define ATTR_WEAK __attribute__((weak)) + +/* alignment */ +#define ATTR_ALIGN(alignment) __attribute__((aligned(alignment))) + +/* place var_declare at section_name, e.x. PLACE_AT(".target_section", var); */ +#define ATTR_PLACE_AT(section_name) __attribute__((section(section_name))) + +#define ATTR_PLACE_AT_WITH_ALIGNMENT(section_name, alignment) \ +ATTR_PLACE_AT(section_name) ATTR_ALIGN(alignment) + +#define ATTR_PLACE_AT_NONCACHEABLE ATTR_PLACE_AT(".noncacheable.bss") +#define ATTR_PLACE_AT_NONCACHEABLE_WITH_ALIGNMENT(alignment) \ + ATTR_PLACE_AT_NONCACHEABLE ATTR_ALIGN(alignment) + +#define ATTR_PLACE_AT_NONCACHEABLE_BSS ATTR_PLACE_AT(".noncacheable.bss") +#define ATTR_PLACE_AT_NONCACHEABLE_BSS_WITH_ALIGNMENT(alignment) \ + ATTR_PLACE_AT_NONCACHEABLE_BSS ATTR_ALIGN(alignment) + +/* initialize variable x with y using PLACE_AT_NONCACHEABLE_INIT(x) = {y}; */ +#define ATTR_PLACE_AT_NONCACHEABLE_INIT ATTR_PLACE_AT(".noncacheable.init") +#define ATTR_PLACE_AT_NONCACHEABLE_INIT_WITH_ALIGNMENT(alignment) \ + ATTR_PLACE_AT_NONCACHEABLE_INIT ATTR_ALIGN(alignment) + +#define ATTR_RAMFUNC ATTR_PLACE_AT(".fast") +#define ATTR_RAMFUNC_WITH_ALIGNMENT(alignment) \ + ATTR_RAMFUNC ATTR_ALIGN(alignment) + +#define ATTR_SHARE_MEM ATTR_PLACE_AT(".sh_mem") + +#define NOP() __asm volatile("nop") +#define WFI() __asm volatile("wfi") + +#define HPM_ATTR_MACHINE_INTERRUPT __attribute__ ((section(".isr_vector"), interrupt("machine"), aligned(4))) + +#elif defined(__ICCRISCV__) + + + /* alway_inline */ +#define ATTR_ALWAYS_INLINE __attribute__((always_inline)) + +/* weak */ +#define ATTR_WEAK __weak + +/* alignment */ +#define ATTR_ALIGN(alignment) __attribute__((aligned(alignment))) + +/* place var_declare at section_name, e.x. PLACE_AT(".target_section", var); */ +#define ATTR_PLACE_AT(section_name) __attribute__((section(section_name))) + +#define ATTR_PLACE_AT_WITH_ALIGNMENT(section_name, alignment) \ +ATTR_PLACE_AT(section_name) ATTR_ALIGN(alignment) + +#define ATTR_PLACE_AT_NONCACHEABLE ATTR_PLACE_AT(".noncacheable.bss") +#define ATTR_PLACE_AT_NONCACHEABLE_WITH_ALIGNMENT(alignment) \ + ATTR_PLACE_AT_NONCACHEABLE ATTR_ALIGN(alignment) + +#define ATTR_PLACE_AT_NONCACHEABLE_BSS ATTR_PLACE_AT(".noncacheable.bss") +#define ATTR_PLACE_AT_NONCACHEABLE_BSS_WITH_ALIGNMENT(alignment) \ + ATTR_PLACE_AT_NONCACHEABLE_BSS ATTR_ALIGN(alignment) + +/* initialize variable x with y using PLACE_AT_NONCACHEABLE_INIT(x) = {y}; */ +#define ATTR_PLACE_AT_NONCACHEABLE_INIT ATTR_PLACE_AT(".noncacheable.init") +#define ATTR_PLACE_AT_NONCACHEABLE_INIT_WITH_ALIGNMENT(alignment) \ + ATTR_PLACE_AT_NONCACHEABLE_INIT ATTR_ALIGN(alignment) + +#define ATTR_RAMFUNC ATTR_PLACE_AT(".fast") +#define ATTR_RAMFUNC_WITH_ALIGNMENT(alignment) \ + ATTR_RAMFUNC ATTR_ALIGN(alignment) + +#define ATTR_SHARE_MEM ATTR_PLACE_AT(".sh_mem") + +#define NOP() __asm volatile("nop") +#define WFI() __asm volatile("wfi") + +#define HPM_ATTR_MACHINE_INTERRUPT __machine __interrupt + +#else +#error Unknown toolchain +#endif + +#ifdef __cplusplus +extern "C" { +#endif + + +/** + * @brief Count bits set to 1 + * + * @param value Data to be counted + * + * @return number of bits set to 1 + */ +static inline uint32_t count_set_bits(uint32_t value) +{ + if (value == 0) { + return 0; + } + return 1 + count_set_bits(value & (value - 1)); +} + +/** + * @brief Count bits set to 1 from least significant bit + * + * @param value Data to be counted + * + * @return number of bits set to 1 + * @return 0xFFFFFFFF if no bit was set to 1 + */ +static inline uint32_t get_first_set_bit_from_lsb(uint32_t value) +{ + uint32_t i = 0; + if (!value) { + return 0xFFFFFFFFUL; + } + while (value && !(value & 0x1)) { + value >>= 1; + i++; + } + return i; +} + +/** + * @brief Count bits set to 1 from most significant bit + * + * @param value Data to be counted + * + * @return number of bits set to 1 + * @return 0xFFFFFFFF if no bit was set to 1 + */ +static inline uint32_t get_first_set_bit_from_msb(uint32_t value) +{ + uint32_t i = 31; + if (!value) { + return 0xFFFFFFFFUL; + } + while (value && !(value & 0x80000000)) { + value <<= 1; + value &= ~1; + i--; + } + return i; +} + +#ifdef __cplusplus +} +#endif + +/** + * @} + */ +#endif /* _HPM_COMMON_H */ diff --git a/contrib/loaders/flash/hpmicro/hpm_romapi.h b/contrib/loaders/flash/hpmicro/hpm_romapi.h new file mode 100644 index 0000000000..1c8ce500b6 --- /dev/null +++ b/contrib/loaders/flash/hpmicro/hpm_romapi.h @@ -0,0 +1,164 @@ +/* + * Copyright (c) 2021-2023 HPMicro + * + * SPDX-License-Identifier: BSD-3-Clause + * + */ + +#ifndef HPM_ROMAPI_H +#define HPM_ROMAPI_H + +/** + * @brief ROM APIs + * @defgroup romapi_interface ROM APIs + * @{ + */ + +#include "hpm_common.h" +#include "hpm_romapi_xpi_def.h" +#include "hpm_romapi_xpi_soc_def.h" +#include "hpm_romapi_xpi_nor_def.h" + +/* XPI0 base address */ +#define HPM_XPI0_BASE (0xF3040000UL) /**< XPI0 Base address */ +/* XPI0 base pointer */ +#define HPM_XPI0 ((XPI_Type *) HPM_XPI0_BASE) /**< XPI0 Base pointer */ +/* XPI1 base address */ +#define HPM_XPI1_BASE (0xF3044000UL) /**< XPI1 Base address */ +/* XPI1 base pointer */ +#define HPM_XPI1 ((XPI_Type *) HPM_XPI1_BASE) /**< XPI1 Base pointer */ + + +/*********************************************************************************************************************** + * + * + * Definitions + * + * + **********************************************************************************************************************/ + + +/** + * @brief XPI driver interface + */ +typedef struct { + /**< XPI driver interface: version */ + uint32_t version; + /**< XPI driver interface: get default configuration */ + hpm_stat_t (*get_default_config)(xpi_config_t *xpi_config); + /**< XPI driver interface: get default device configuration */ + hpm_stat_t (*get_default_device_config)(xpi_device_config_t *dev_config); + /**< XPI driver interface: initialize the XPI using xpi_config */ + hpm_stat_t (*init)(XPI_Type *base, xpi_config_t *xpi_config); + /**< XPI driver interface: configure the AHB buffer */ + hpm_stat_t (*config_ahb_buffer)(XPI_Type *base, xpi_ahb_buffer_cfg_t *ahb_buf_cfg); + /**< XPI driver interface: configure the device */ + hpm_stat_t (*config_device)(XPI_Type *base, xpi_device_config_t *dev_cfg, xpi_channel_t channel); + /**< XPI driver interface: update instruction talbe */ + hpm_stat_t (*update_instr_table)(XPI_Type *base, const uint32_t *inst_base, uint32_t seq_idx, uint32_t num); + /**< XPI driver interface: transfer command/data using block interface */ + hpm_stat_t (*transfer_blocking)(XPI_Type *base, xpi_xfer_ctx_t *xfer); + /**< Software reset the XPI controller */ + void (*software_reset)(XPI_Type *base); + /**< XPI driver interface: Check whether IP is idle */ + bool (*is_idle)(XPI_Type *base); + /**< XPI driver interface: update delay line setting */ + void (*update_dllcr)(XPI_Type *base, uint32_t serial_root_clk_freq, uint32_t data_valid_time, xpi_channel_t channel, + uint32_t dly_target); + /**< XPI driver interface: Get absolute address for APB transfer */ + hpm_stat_t (*get_abs_apb_xfer_addr)(XPI_Type *base, xpi_xfer_channel_t channel, uint32_t in_addr, + uint32_t *out_addr); +} xpi_driver_interface_t; + +/** + * @brief XPI NOR driver interface + */ +typedef struct { + /**< XPI NOR driver interface: API version */ + uint32_t version; + /**< XPI NOR driver interface: Get FLASH configuration */ + hpm_stat_t (*get_config)(XPI_Type *base, xpi_nor_config_t *nor_cfg, xpi_nor_config_option_t *cfg_option); + /**< XPI NOR driver interface: initialize FLASH */ + hpm_stat_t (*init)(XPI_Type *base, xpi_nor_config_t *nor_config); + /**< XPI NOR driver interface: Enable write access to FLASH */ + hpm_stat_t (*enable_write)(XPI_Type *base, xpi_xfer_channel_t channel, const xpi_nor_config_t *nor_config, + uint32_t addr); + /**< XPI NOR driver interface: Get FLASH status register */ + hpm_stat_t (*get_status)(XPI_Type *base, xpi_xfer_channel_t channel, const xpi_nor_config_t *nor_config, + uint32_t addr, + uint16_t *out_status); + /**< XPI NOR driver interface: Wait when FLASH is still busy */ + hpm_stat_t (*wait_busy)(XPI_Type *base, xpi_xfer_channel_t channel, const xpi_nor_config_t *nor_config, + uint32_t addr); + /**< XPI NOR driver interface: erase a specified FLASH region */ + hpm_stat_t (*erase)(XPI_Type *base, xpi_xfer_channel_t channel, const xpi_nor_config_t *nor_config, uint32_t start, + uint32_t length); + /**< XPI NOR driver interface: Erase the whole FLASH */ + hpm_stat_t (*erase_chip)(XPI_Type *base, xpi_xfer_channel_t channel, const xpi_nor_config_t *nor_config); + /**< XPI NOR driver interface: Erase specified FLASH sector */ + hpm_stat_t (*erase_sector)(XPI_Type *base, xpi_xfer_channel_t channel, const xpi_nor_config_t *nor_config, + uint32_t addr); + /**< XPI NOR driver interface: Erase specified FLASH block */ + hpm_stat_t (*erase_block)(XPI_Type *base, xpi_xfer_channel_t channel, const xpi_nor_config_t *nor_config, + uint32_t addr); + /**< XPI NOR driver interface: Program data to specified FLASH address */ + hpm_stat_t (*program)(XPI_Type *base, xpi_xfer_channel_t channel, const xpi_nor_config_t *nor_config, + const uint32_t *src, + uint32_t dst_addr, uint32_t length); + /**< XPI NOR driver interface: read data from specified FLASH address */ + hpm_stat_t (*read)(XPI_Type *base, xpi_xfer_channel_t channel, const xpi_nor_config_t *nor_config, uint32_t *dst, + uint32_t start, uint32_t length); + /**< XPI NOR driver interface: program FLASH page using nonblocking interface */ + hpm_stat_t (*page_program_nonblocking)(XPI_Type *base, xpi_xfer_channel_t channel, + const xpi_nor_config_t *nor_config, + const uint32_t *src, uint32_t dst_addr, uint32_t length); + /**< XPI NOR driver interface: erase FLASH sector using nonblocking interface */ + hpm_stat_t (*erase_sector_nonblocking)(XPI_Type *base, xpi_xfer_channel_t channel, + const xpi_nor_config_t *nor_config, + uint32_t addr); + /**< XPI NOR driver interface: erase FLASH block using nonblocking interface */ + hpm_stat_t (*erase_block_nonblocking)(XPI_Type *base, xpi_xfer_channel_t channel, + const xpi_nor_config_t *nor_config, + uint32_t addr); + /**< XPI NOR driver interface: erase the whole FLASh using nonblocking interface */ + hpm_stat_t (*erase_chip_nonblocking)(XPI_Type *base, xpi_xfer_channel_t channel, + const xpi_nor_config_t *nor_config); + + uint32_t reserved0[3]; + + /**< XPI NOR driver interface: automatically configuration flash based on the cfg_option setting */ + hpm_stat_t (*auto_config)(XPI_Type *base, xpi_nor_config_t *nor_cfg, xpi_nor_config_option_t *cfg_option); + + /**< XPI NOR driver interface: Get FLASH properties */ + hpm_stat_t (*get_property)(XPI_Type *base, xpi_nor_config_t *nor_cfg, uint32_t property_id, uint32_t *value); + +} xpi_nor_driver_interface_t; + + + +/** + * @brief Bootloader API table + */ +typedef struct { + /**< Bootloader API table: version */ + const uint32_t version; + /**< Bootloader API table: copyright string address */ + const char *copyright; + /**< Bootloader API table: run_bootloader API */ + const uint32_t reserved0; + /**< Bootloader API table: otp driver interface address */ + const uint32_t reserved1; + /**< Bootloader API table: xpi driver interface address */ + const xpi_driver_interface_t *xpi_driver_if; + /**< Bootloader API table: xpi nor driver interface address */ + const xpi_nor_driver_interface_t *xpi_nor_driver_if; + /**< Bootloader API table: xpi ram driver interface address */ + const uint32_t reserved2; +} bootloader_api_table_t; + +/**< Bootloader API table Root */ +#define ROM_API_TABLE_ROOT ((const bootloader_api_table_t *)0x2001FF00U) + + + +#endif /* HPM_ROMAPI_H */ diff --git a/contrib/loaders/flash/hpmicro/hpm_romapi_xpi_def.h b/contrib/loaders/flash/hpmicro/hpm_romapi_xpi_def.h new file mode 100644 index 0000000000..49a4f5065d --- /dev/null +++ b/contrib/loaders/flash/hpmicro/hpm_romapi_xpi_def.h @@ -0,0 +1,218 @@ +/* + * Copyright (c) 2021 HPMicro + * + * SPDX-License-Identifier: BSD-3-Clause + * + */ +#ifndef HPM_ROMAPI_XPI_DEF_H +#define HPM_ROMAPI_XPI_DEF_H + +/** + * @brief XPI ROM APIs + * @defgroup xpi_interface XPI driver APIs + * @{ + */ + +#include "hpm_common.h" + +/** + * @brief XPI_Type definitions for + * @note For compatibility + */ +typedef uint32_t XPI_Type; + +/** + * @brief XPI Read Sample Clock source options + */ +typedef enum { + xpi_rxclksrc_internal_loopback = 0, /**< Internal loopback */ + xpi_rxclksrc_dqs_loopback = 1, /**< Loopback from DQS pad */ + xpi_rxclksrc_external_dqs = 3, /**< Read is driven by External DQS pad */ +} xpi_rxclksrc_type_t; + + +/** + * @brief XPI pad definitions + */ +#define XPI_1PAD (0U) /**< Single pad */ +#define XPI_2PADS (1U) /**< Dual pads */ +#define XPI_4PADS (2U) /**< Quad pads */ +#define XPI_8PADS (3U) /**< Octal pads */ + +/** + * @brief XPI IO pin group options + */ +typedef enum { + xpi_io_1st_group, /**< First/Primary group */ + xpi_io_2nd_group, /**< Second/Secondary group */ +} xpi_io_group_t; + +/** + * @brief XPI Transfer Channel type definitions + */ +typedef enum { + xpi_xfer_channel_a1, /**< The address is based on the device connected to Channel A1 */ + xpi_xfer_channel_a2, /**< The address is based on the device connected to Channel A2 */ + xpi_xfer_channel_b1, /**< The address is based on the device connected to Channel B1 */ + xpi_xfer_channel_b2, /**< The address is based on the device connected to Channel B2 */ + xpi_xfer_channel_auto, /**< The channel is auto determined */ +} xpi_xfer_channel_t; + +/** + * @brief XPI Channel defitions + */ +typedef enum { + xpi_channel_a1, /**< Port: Channel A1 */ + xpi_channel_a2, /**< Port: Channel A2 */ + xpi_channel_b1, /**< Port: Channel B1 */ + xpi_channel_b2, /**< Port: Channel B2 */ +} xpi_channel_t; + +/** + * @brief XPI APB Transfer type + */ +typedef enum { + xpi_apb_xfer_type_cmd, /**< APB Command Type: Command only */ + xpi_apb_xfer_type_config, /**< APB Command Type: Configuration */ + xpi_apb_xfer_type_read, /**< APB Command Type: Read */ + xpi_apb_xfer_type_write, /**< APB Command Type: Write */ +} xpi_apb_xfer_type_t; + +/** + * @brief XPI Xfer Mode + */ +typedef enum { + xpi_xfer_mode_polling, /**< Transfer mode: Polling */ + xpi_xfer_mode_dma, /**< Transfer mode: DMA */ + xpi_xfer_mode_interrupt, /**< Transfer mode: Interrupt */ +} xpi_xfer_mode_t; + +/** + * @brief XPI Xfer context + */ +typedef struct { + uint32_t addr; /**< device address for XPI transfer */ + uint8_t channel; /**< channel for XPI transfer */ + uint8_t cmd_type; /**< command type for XPI transfer */ + uint8_t seq_idx; /**< Sequence index for XPI transfer */ + uint8_t seq_num; /**< Sequence number for XPI transfer */ + uint32_t *buf; /**< Buffer for XPI transfer */ + uint32_t xfer_size; /**< Transfer size in bytes */ +} xpi_xfer_ctx_t; + +/** + * @brief XPI instruction sequence + */ +typedef struct { + uint32_t entry[4]; +} xpi_instr_seq_t; + +/** + * @brief XPI Phase definitions + */ +#define XPI_PHASE_STOP (0x00U) /**< Phase: Stop */ +#define XPI_PHASE_CMD_SDR (0x01U) /**< Phase: Send CMD in SDR mode */ +#define XPI_PHASE_RADDR_SDR (0x02U) /**< Phase: Send Row Address in SDR Mode */ +#define XPI_PHASE_CADDR_SDR (0x03U) /**< Phase: Send Column Address in SDR Mode */ +#define XPI_PHASE_MODE4_SDR (0x06U) /**< Phase: Send Mode 4 in SDR Mode */ +#define XPI_PHASE_MODE8_SDR (0x07U) /**< Phase: Send Mode 8 in SDR Mode */ +#define XPI_PHASE_WRITE_SDR (0x08U) /**< Phase: Write data in SDR Mode */ +#define XPI_PHASE_READ_SDR (0x09U) /**< Phase: Read data in SDR Mode */ +#define XPI_PHASE_DUMMY_SDR (0X0CU) /**< Phase: Send Dummy in SDR Mode */ +#define XPI_PHASE_DUMMY_RWDS_SDR (0x0DU) /**< Phase: Send Dummy RWDS in SDR Mode */ + +#define XPI_PHASE_CMD_DDR (0x21U) /**< Phase: Send CMD in DDR Mode */ +#define XPI_PHASE_RADDR_DDR (0x22U) /**< Phase: Send Raw Address in DDR Mode */ +#define XPI_PHASE_CADDR_DDR (0x23U) /**< Phase: Send Column address in DDR Mode */ +#define XPI_PHASE_MODE4_DDR (0x26U) /**< Phase: Send Mode 4 in DDR Mode */ +#define XPI_PHASE_MODE8_DDR (0x27U) /**< Phase: Send Mode 8 in DDR Mode */ +#define XPI_PHASE_WRITE_DDR (0x28U) /**< Phase: Write data in DDR Mode */ +#define XPI_PHASE_READ_DDR (0x29U) /**< Phase: Read data in SDR Mode */ +#define XPI_PHASE_DUMMY_DDR (0x2CU) /**< Phase: Send DUMMY in DDR Mode */ +#define XPI_PHASE_DUMMY_RWDS_DDR (0x2DU) /**< Phase: Send DUMMY RWDS in DDR Mode */ + +/** + * @brief XPI API command error codes + */ +enum { + status_xpi_apb_jump_on_cs = MAKE_STATUS(status_group_xpi, 1), + status_xpi_apb_unknown_inst = MAKE_STATUS(status_group_xpi, 2), + status_xpi_apb_dummy_sdr_in_ddr_seq = MAKE_STATUS(status_group_xpi, 3), + status_xpi_apb_dummy_ddr_in_sdr_seq = MAKE_STATUS(status_group_xpi, 4), + status_xpi_apb_exceed_addr_range = MAKE_STATUS(status_group_xpi, 5), + status_xpi_apb_seq_timeout = MAKE_STATUS(status_group_xpi, 6), + status_xpi_apb_cross_boundary = MAKE_STATUS(status_group_xpi, 7), +}; + +/** + * @brief Delay line definitions + */ +enum { + xpi_dll_half_cycle = 0xFU, + xpi_dll_quarter_cycle = 0x7U, + xpi_dll_sdr_default_cycle = xpi_dll_half_cycle, + xpi_dll_ddr_default_cycle = xpi_dll_quarter_cycle, +}; + +/** + * @brief XPI configuration structure + */ +typedef struct { + uint8_t rxclk_src; /**< Read sample clock source */ + uint8_t reserved0[7]; /**< Reserved */ + uint8_t tx_watermark_in_dwords; /**< Tx watermark in double words */ + uint8_t rx_watermark_in_dwords; /**< Rx watermark in double words */ + uint8_t enable_differential_clk; /**< Enable differential clock */ + uint8_t reserved1[5]; /**< Reserved */ + uint32_t access_flags; /**< Access flags */ +} xpi_config_t; + +/** + * @brief XPI Device Configuration structure + */ +typedef struct { + uint32_t size_in_kbytes; /**< Device size in kbytes */ + uint32_t serial_root_clk_freq; /**< XPI serial root clock frequency */ + + uint8_t enable_write_mask; /**< Enable write mask, typically for PSRAM/HyperRAM */ + uint8_t data_valid_time; /**< Data valid time, Unit 0.1ns */ + uint8_t reserved0[2]; + + uint8_t cs_hold_time; /**< CS hold time, cycles in terms of FLASH clock */ + uint8_t cs_setup_time; /**< CS setup time, cycles in terms of FLASH clock */ + uint16_t cs_interval; /**< CS interval, cycles in terms of FLASH clock */ + + uint8_t reserved1; + uint8_t column_addr_size; /**< Column address bits */ + uint8_t enable_word_address; /**< Enable word address, for HyperFLASH/HyperRAM */ + uint8_t dly_target; /**< Delay target */ + + uint8_t ahb_write_seq_idx; /**< AHB write sequence index */ + uint8_t ahb_write_seq_num; /**< AHB write sequence number */ + uint8_t ahb_read_seq_idx; /**< AHB read sequence index */ + uint8_t ahb_read_seq_num; /**< AHB read sequence number */ + + uint8_t ahb_write_wait_interval; /**< AHB write wait interval, in terms of FLASH clock */ + uint8_t reserved2[3]; +} xpi_device_config_t; + +/** + * @brief SUB Instruction + * @param [in] phase Phase + * @param [in] pad Pad for Phase + * @param [in] op Operand for Phase + */ +#define SUB_INSTR(phase, pad, op) ((uint32_t)(((uint16_t)(phase) << 10) | ((uint16_t)(pad) << 8) | ((uint16_t)(op)))) +/** + * @brief Generate a single word INSTRUCTION sequence word + * @note Here intentionally use the MACRO because when the arguments are constant value, the compiler + * can generate the const entry word during pre-processing + */ +#define XPI_INSTR_SEQ(phase0, pad0, op0, phase1, pad1, op1) (SUB_INSTR(phase0, pad0, op0) | (SUB_INSTR(phase1, pad1, op1)<<16)) + + +/** + * @} + */ + +#endif /* HPM_ROMAPI_XPI_DEF_H */ diff --git a/contrib/loaders/flash/hpmicro/hpm_romapi_xpi_nor_def.h b/contrib/loaders/flash/hpmicro/hpm_romapi_xpi_nor_def.h new file mode 100644 index 0000000000..63a334d14e --- /dev/null +++ b/contrib/loaders/flash/hpmicro/hpm_romapi_xpi_nor_def.h @@ -0,0 +1,309 @@ +/* + * Copyright (c) 2021 HPMicro + * + * SPDX-License-Identifier: BSD-3-Clause + * + */ +#ifndef HPM_ROMAPI_XPI_NOR_DEF_H +#define HPM_ROMAPI_XPI_NOR_DEF_H + +/** + * @brief XPI NOR ROM APIs + * @defgroup xpi_nor_interface XPI NOR driver APIs + * @ingroup romapi_interfaces + * @{ + */ + + +#include "hpm_common.h" +#include "hpm_romapi_xpi_def.h" + +#define XPI_NOR_CFG_TAG 0x524f4E58U /**< ASCII: "XNOR" */ + +/** + * @brief XPI NOR properties + */ +enum { + xpi_nor_property_total_size, /**< Total size in bytes */ + xpi_nor_property_page_size, /**< Page size in bytes */ + xpi_nor_property_sector_size, /**<sector size in bytes */ + xpi_nor_property_block_size, /**< block size in bytes */ + xpi_nor_property_max = xpi_nor_property_block_size, +}; + + +/** + * @brief XPI NOR safe frequency option + */ +enum { + xpi_nor_clk_safe_clk_freq = 1, +}; + +/** + * @brief XPI NOR miscellaneous options + */ +enum { + xpi_nor_option_misc_spi_only = 1, /**< SPI only */ + xpi_nor_option_misc_internal_loopback = 2, /**< Internal loopback mode */ + xpi_nor_option_misc_ext_dqs = 3, /**< External DQS pin */ +}; + +/** + * @brief XPI NOR connection option + */ +enum { + xpi_nor_connection_sel_chna_cs0, /**< Channel A, CS0 */ + xpi_nor_connection_sel_chnb_cs0, /**< Channel B, CS0 */ + xpi_nor_connection_sel_chna_cs0_chnb_cs0, /**< Channel A + Channel B, CS0 */ + xpi_nor_connection_sel_chna_cs0_cs1, /**< Channel A, CS0 + CS1 */ + xpi_nor_connection_sel_chnb_cs0_cs1 /**< Channel B, CS0 + CS1 */ +}; + +/** + * @brief QE bit enable sequence option + */ +typedef enum { + xpi_nor_quad_en_auto_or_ignore = 0U, /**< Auto enable or ignore */ + xpi_nor_quad_en_set_bit6_in_status_reg1 = 1U, /**< QE bit is at bit6 in Status register 1 */ + xpi_nor_quad_en_set_bit1_in_status_reg2 = 2U, /**< QE bit is at bit1 in Status register 2 register 2 */ + xpi_nor_quad_en_set_bit7_in_status_reg2 = 3U, /**< QE bit is at bit7 in Status register 2 */ + xpi_nor_quad_en_set_bi1_in_status_reg2_via_0x31_cmd = 4U, /**< QE bit is in status register 2 and configured by CMD 0x31 */ +} xpi_nor_quad_enable_seq_t; + +/** + * @brief XPI working mode + */ +typedef enum { + xpi_working_mode_extend_spi, /**< XPI works in extended SPI mode, including 1-1-1, 1-2-2, 1-4-4, 1-8-8 */ + xpi_working_mode_xpi, /**< XPI works in XPI mode, including, 1-1-1, 2-2-2, 4-4-4, 8-8-8 */ + xpi_working_mode_hyperbus, /**< XPI works in HyperBus mode */ +} xpi_working_mode_t; + + +/** + * @brief XPI NOR configuration command type + */ +typedef enum { + xpi_nor_cfg_cmd_type_no_cfg = 0U, /**< No configuration */ + xpi_nor_cfg_cmd_type_generic = 1U, /**< Generic configuration */ + xpi_nor_cfg_cmd_type_spi2xpi = 2U, /**< SPI to XPI mode */ + xpi_nor_cfg_cmd_type_xpi2spi = 3U, /**< XPI to SPI mode */ +} xpi_nor_cfg_cmd_type_t; + +/** + * @brief XPI NOR probe options + */ +typedef enum { + xpi_nor_probe_sfdp_sdr = 0U, /**< Probe FLASH using SFDP and set FLASH to SDR mode */ + xpi_nor_probe_sfdp_ddr = 1U, /**< Probe FLASH using SDP and set FLASH to DDR mode */ + xpi_nor_quad_read_0xeb = 2U, /**< Set FLASH to default Quad I/O read in SDR mode */ + xpi_nor_dual_read_0xbb = 3U, /**< Set FLASH to default Dual I/O read in SDR mode */ + xpi_nor_hyperbus_1v8 = 4U, /**< Probe FLASH using HyperBus in 1.8V voltage */ + xpi_nor_hyperbus_3v0 = 5U, /**< Probe FLASH using HyperBus in 3.0V voltage */ + xpi_nor_octabus_ddr = 6U, /**< Probe FLASH using Macronix OctaBus and configure FLASH to OPI DDR mode */ + xpi_nor_octabus_sdr = 7U, /**< Probe FLASH using Macronix OctaBus and configure FLASH to OPI SDR mode */ + xpi_nor_xccela_ddr = 8U, /**< Probe FLASH using Xccela Protocol and configure FLASH to OPI DDR mode */ + xpi_nor_xccela_sdr = 9U, /**< Probe FLASH using Xccela Protocol and configure FLASH to SDR mode */ + xpi_nor_ecoxip_ddr = 10U, /**< Probe FLASH using EcoXiP Protocol and configure FLASH to OPI DDR mode */ + xpi_nor_ecoxip_sdr = 11U, /**< Probe FLASH using EcoXiP Protocol and configure FLASH to SDR mode */ +} xpi_nor_probe_t; + +/** + * @brief Standard XPI NOR seuqnce index definitions + */ +typedef enum { + xpi_std_nor_seq_idx_read = 0U, /**< 0 - Read */ + xpi_std_nor_seq_idx_page_program = 1U, /**< 1 - Page Program */ + xpi_std_nor_seq_idx_read_status = 2U, /**< 2 - Read Status */ + xpi_std_nor_seq_idx_read_status_xpi = 3U, /**< 3 - Read Status in xSPI mode */ + xpi_std_nor_seq_idx_write_enable = 4U, /**< 4 - Write Enable */ + xpi_std_nor_seq_idx_write_enable_xpi = 5U, /**< 5 - Write Enable in xSPI mode */ + xpi_std_nor_seq_idx_erase_sector = 6U, /**< 6 - Erase sector */ + xpi_std_nor_seq_idx_erase_block = 7U, /**< 7 - Erase block */ + xpi_std_nor_seq_idx_erase_chip = 8U, /**< 8 - Erase full chip */ + xpi_std_nor_seq_idx_max = 9, /**< 9 */ +} xpi_std_nor_instr_idx_t; + +/** + * @brief XPI NOR option tag + */ +#define XPI_NOR_CFG_OPTION_TAG (0xfcf90U) + +/** + * @brief XPI NOR configuration option + * The ROM SW can detect the FLASH configuration based on the following structure specified by the end-user + */ +typedef struct { + union { + struct { + uint32_t words: 4; /**< Option words, exclude the header itself */ + uint32_t reserved: 8; /**< Reserved for future use */ + uint32_t tag: 20; /**< Must be 0xfcf90 */ + }; + uint32_t U; + } header; + union { + struct { + uint32_t freq_opt: 4; /**< 1 - 30MHz, others, SoC specific setting */ + uint32_t misc: 4; /**< Not used for now */ + uint32_t dummy_cycles: 8; /**< 0 - Auto detected/ use predefined value, others - specified by end-user */ + uint32_t quad_enable_seq: 4; /**< See the xpi_nor_quad_enable_seq_t definitions for more details */ + uint32_t cmd_pads_after_init: 4; /**< See the xpi_data_pad_t definitions for more details */ + uint32_t cmd_pads_after_por: 4; /**< See the xpi_data_pad_t definitions for more details */ + uint32_t probe_type: 4; /**< See the xpi_nor_probe_t definitions for more details */ + }; + uint32_t U; + } option0; + union { + struct { + uint32_t drive_strength: 8; /**< IO drive strength, 0 - pre-defined, Others - specified by end-user */ + uint32_t connection_sel: 4; /**< Device connection selection: 0 - PORTA, 1 - PORTB, 2 - Parallel mode */ + uint32_t pin_group_sel: 4; /**< Pin group selection, 0 - 1st group, 1 - 2nd group, by default, the pin group is 1st group */ + uint32_t io_voltage: 4; /**< SoC pad voltage, 0 - 3.0V, 1-1.8V */ + uint32_t reserved: 12; /**< Reserved for future use */ + }; + uint32_t U; + } option1; + union { + struct { + uint32_t flash_size_option:8; /**< FLASH size option */ + uint32_t flash_sector_size_option:4; /**< FLASH sector size option */ + uint32_t flash_sector_erase_cmd_option:4; /**< Sector Erase command option */ + uint32_t reserved:20; + }; + uint32_t U; + } option2; +} xpi_nor_config_option_t; + +/** + * @brief Sector size options + */ +enum { + serial_nor_sector_size_4kb, /**< Sector size: 4KB */ + serial_nor_sector_size_32kb, /**< Sector size: 32KB */ + serial_nor_sector_size_64kb, /**< Sector size: 64KB */ + serial_nor_sector_size_256kb, /**< Sector size: 256KB */ +}; + +/** + * @brief Sector erase command options + */ +enum { + serial_nor_erase_type_4kb, /**< Sector erase command: 4KB Erase */ + serial_nor_erase_type_32kb, /**< Sector erase command: 32KB Erase */ + serial_nor_erase_type_64kb, /**< Sector erase command: 64KB Erase */ + serial_nor_erase_type_256kb, /**< Sector erase command: 256KB Erase */ +}; + +/** + * @brief FLASH size options + */ +enum { + flash_size_4mb, /**< FLASH size: 4MB */ + flash_size_8mb, /**< FLASH size: 8MB */ + flash_size_16mb, /**< FLASH size: 16MB */ +}; + +/** + * @brief Device Mode confiuration structure + */ +typedef struct { + uint8_t cfg_cmd_type; /**< Configuration command type */ + uint8_t param_size; /**< Size for parameter */ +} device_mode_cfg_t; + +/** + * @brief Device mode parameter structure + */ +typedef struct { + uint32_t instr_seq[4]; /**< Command Instruction sequence*/ + uint32_t param; /**< Parameter */ +} device_mode_param_t; + +/** + * @brief XPI NOR device information structure + */ +typedef struct { + uint32_t size_in_kbytes; /**< Device Size in Kilobytes, offset 0x00 */ + uint16_t page_size; /**< Page size, offset 0x04 */ + uint16_t sector_size_kbytes; /**< Sector size in kilobytes, offset 0x06 */ + uint16_t block_size_kbytes; /**< Block size in kilobytes, offset 0x08 */ + uint8_t busy_offset; /**< Busy offset, offset 0x0a */ + uint8_t busy_polarity; /**< Busy polarity, offset 0x0b */ + uint8_t data_pads; /**< Device Size in Kilobytes, offset 0x0c */ + uint8_t en_ddr_mode; /**< Enable DDR mode, offset 0x0d */ + uint8_t clk_freq_for_device_cfg; /**< Clk frequency for device configuration offset 0x0e */ + uint8_t working_mode_por; /**< Working mode after POR reset offset 0x0f */ + uint8_t working_mode; /**< The device working mode, offset 0x10 */ + uint8_t en_diff_clk; /**< Enable Differential clock, offset 0x11 */ + uint8_t data_valid_time; /**< Data valid time, in 0.1ns, offset 0x12 */ + uint8_t en_half_clk_for_non_read_cmd; /**< Enable half clock for non-read command, offset 0x13 */ + uint8_t clk_freq_for_non_read_cmd; /**< Enable safe clock for non-read command, offset 0x14 */ + uint8_t dll_dly_target; /**< XPI DLL Delay Target, offset 0x15 */ + uint8_t io_voltage; /**< IO voltage, offset 0x16 */ + uint8_t reserved0; /**< Reserved for future use, offset 0x17 */ + uint8_t cs_hold_time; /**< CS hold time, 0 - default value, others - user specified value, offset 0x18 */ + uint8_t cs_setup_time; /**< CS setup time, 0 - default value, others - user specified value, offset 0x19 */ + uint8_t cs_interval; /**< CS interval, intervals between to CS active, offset 0x1a */ + uint8_t en_dev_mode_cfg; /**< Enable device mode configuration, offset 0x1b */ + uint32_t flash_state_ctx; /**< Flash state context, offset 0x1c */ + device_mode_cfg_t mode_cfg_list[2]; /**< Mode configuration sequences, offset 0x20 */ + uint32_t mode_cfg_param[2]; /**< Mode configuration parameters, offset 0x24 */ + uint32_t reserved1; /**< Reserved for future use, offset 0x2C */ + struct { + uint32_t entry[4]; + } cfg_instr_seq[2]; /**< Mode Configuration Instruction sequence, offset 0x30 */ +} xpi_device_info_t; + +/** + * @brief XPI NOR configuration structure + */ +typedef struct { + uint32_t tag; /**< Must be "XNOR", offset 0x000 */ + uint32_t reserved0; /**< Reserved for future use, offset 0x004 */ + uint8_t rxclk_src; /**< RXCLKSRC value, offset 0x008 */ + uint8_t clk_freq; /**< Clock frequency, offset 0x009 */ + uint8_t drive_strength; /**< Drive strength, offset 0x0a */ + uint8_t column_addr_size; /**< Column address size, offset 0x0b */ + uint8_t rxclk_src_for_init; /**< RXCLKSRC during FLASH initialization, offset 0x0c */ + uint8_t config_in_progress; /**< Indicate whether device configuration is in progress, offset: 0x0d */ + uint8_t reserved[2]; /**< Reserved for future use, offset 0x00f */ + struct { + uint8_t enable; /**< Port enable flag, 0 - not enabled, 1 - enabled */ + uint8_t group; /**< 0 - 1st IO group, 1 - 2nd IO group */ + uint8_t reserved[2]; + } chn_info[4]; /**< Device connection information */ + xpi_device_info_t device_info; /**< Device info, offset 0x20 */ + xpi_instr_seq_t instr_set[xpi_std_nor_seq_idx_max];/**< Standard instruction sequence table, offset 0x70 */ +} xpi_nor_config_t; + +/** + * @brief FLASH runtime context structure + */ +typedef union { + struct { + uint32_t wait_time: 7; /**< Wait time */ + uint32_t wait_time_unit: 1; /**< 0 - 10us, 1 - 1ms */ + uint32_t reset_gpio: 8; /**<Reset GPIO */ + uint32_t restore_sequence: 4; /**<Restore sequence */ + uint32_t exit_no_cmd_sequence: 4; /**< Exit no-cmd sequence */ + uint32_t current_mode: 4; /**< Current FLASH mode */ + uint32_t por_mode: 4; /**< FLASH mode upon Power-on Reset */ + }; + uint32_t U; +} flash_run_context_t; + +/** + * @brief XPI NOR API error codes + */ +enum { + status_xpi_nor_sfdp_not_found = MAKE_STATUS(status_group_xpi_nor, 0), /**< SFDP table was not found */ + status_xpi_nor_ddr_read_dummy_cycle_probe_failed = MAKE_STATUS(status_group_xpi_nor, 1), /**< Probing Dummy cyles for DDR read failed */ + status_xpi_nor_flash_not_found = MAKE_STATUS(status_group_xpi_nor, 2), /**< FLASH was not detected */ +}; + +/** + * @} + */ + +#endif /* HPM_ROMAPI_XPI_NOR_DEF_H */ diff --git a/contrib/loaders/flash/hpmicro/hpm_romapi_xpi_soc_def.h b/contrib/loaders/flash/hpmicro/hpm_romapi_xpi_soc_def.h new file mode 100644 index 0000000000..7aff94513f --- /dev/null +++ b/contrib/loaders/flash/hpmicro/hpm_romapi_xpi_soc_def.h @@ -0,0 +1,80 @@ +/* + * Copyright (c) 2021 HPMicro + * + * SPDX-License-Identifier: BSD-3-Clause + * + */ + +#ifndef HPM_ROMAPI_XPI_SOC_DEF_H +#define HPM_ROMAPI_XPI_SOC_DEF_H + +#include "hpm_common.h" +#include "hpm_romapi_xpi_def.h" + +/*********************************************************************************************************************** + * Definitions + **********************************************************************************************************************/ + +#define XPI_CLK_OUT_FREQ_OPTION_30MHz (1U) +#define XPI_CLK_OUT_FREQ_OPTION_50MHz (2U) +#define XPI_CLK_OUT_FREQ_OPTION_66MHz (3U) +#define XPI_CLK_OUT_FREQ_OPTION_80MHz (4U) +#define XPI_CLK_OUT_FREQ_OPTION_104MHz (5U) +#define XPI_CLK_OUT_FREQ_OPTION_120MHz (6U) +#define XPI_CLK_OUT_FREQ_OPTION_133MHz (7U) +#define XPI_CLK_OUT_FREQ_OPTION_166MHz (8U) +#define XPI_CLK_OUT_FREQ_OPTION_200MHz (9U) + +typedef struct { + struct { + uint8_t priority; /* Offset: 0x00 */ + uint8_t master_idx; /* Offset: 0x01 */ + uint8_t buf_size_in_dword; /* Offset: 0x02 */ + bool enable_prefetch; /* Offset: 0x03 */ + } entry[8]; +} xpi_ahb_buffer_cfg_t; + +typedef struct { + uint8_t data_pads; + xpi_channel_t channel; + xpi_io_group_t io_group; + uint8_t drive_strength; + bool enable_dqs; + bool enable_diff_clk; +} xpi_io_config_t; + +typedef enum { + xpi_freq_type_typical, + xpi_freq_type_mhz, +} clk_freq_type_t; + +typedef enum { + xpi_clk_src_auto, + xpi_clk_src_osc, + xpi_clk_src_pll0clk0, + xpi_clk_src_pll1clk0, + xpi_clk_src_pll1clk1, + xpi_clk_src_pll2clk0, + xpi_clk_src_pll2clk1, + xpi_clk_src_pll3clk0, + xpi_clk_src_pll4clk0, +} xpi_clk_src_t; + + +typedef union { + struct { + uint8_t freq; + bool enable_ddr; + xpi_clk_src_t clk_src; + clk_freq_type_t freq_type; + }; + uint32_t freq_opt; +} xpi_clk_config_t; + +typedef enum { + xpi_clock_bus, + xpi_clock_serial_root, + xpi_clock_serial, +} xpi_clock_t; + +#endif /* HPM_ROMAPI_XPI_SOC_DEF_H */ diff --git a/contrib/loaders/flash/hpmicro/hpm_xpi_flash.h b/contrib/loaders/flash/hpmicro/hpm_xpi_flash.h new file mode 100644 index 0000000000..00279dbe3c --- /dev/null +++ b/contrib/loaders/flash/hpmicro/hpm_xpi_flash.h @@ -0,0 +1,21 @@ +/* + * Copyright (c) 2021 hpmicro + * + * SPDX-License-Identifier: BSD-3-Clause + */ + +#ifndef HPM_XPI_FLASH_H +#define HPM_XPI_FLASH_H + +#define FLASH_INIT (0) +#define FLASH_ERASE (0x6) +#define FLASH_PROGRAM (0xc) +#define FLASH_READ (0x12) +#define FLASH_GET_INFO (0x18) +#define FLASH_ERASE_CHIP (0x1e) + +uint8_t flash_algo[] = { +#include "hpm_xpi_flash.inc" +}; + +#endif diff --git a/contrib/loaders/flash/hpmicro/hpm_xpi_flash.inc b/contrib/loaders/flash/hpmicro/hpm_xpi_flash.inc new file mode 100644 index 0000000000..27e6e4a24d --- /dev/null +++ b/contrib/loaders/flash/hpmicro/hpm_xpi_flash.inc @@ -0,0 +1,65 @@ +/* Autogenerated with ../../../../src/helper/bin2char.sh */ +0xef,0x00,0x00,0x05,0x02,0x90,0xef,0x00,0xc0,0x0e,0x02,0x90,0xef,0x00,0xc0,0x1a, +0x02,0x90,0xef,0x00,0xa0,0x1c,0x02,0x90,0xef,0x00,0xa0,0x1e,0x02,0x90,0xef,0x00, +0x00,0x20,0x02,0x90,0xef,0x00,0x20,0x21,0x02,0x90,0x9c,0x41,0x05,0x47,0xbd,0x8b, +0x63,0x7f,0xf7,0x00,0x9c,0x45,0x05,0x67,0x13,0x07,0x07,0xf0,0xf9,0x8f,0x13,0x07, +0x00,0x10,0x63,0x96,0xe7,0x00,0x23,0x20,0x05,0x06,0x23,0x22,0x05,0x06,0x82,0x80, +0x39,0x71,0x22,0xdc,0x13,0x04,0x80,0x23,0x83,0x47,0x44,0x00,0x06,0xde,0x26,0xda, +0x4a,0xd8,0x4e,0xd6,0x52,0xd4,0x18,0xc0,0xb5,0xe7,0xba,0x84,0x13,0x07,0x84,0x00, +0x3a,0x85,0x2e,0x8a,0xb2,0x89,0x81,0x45,0x13,0x06,0x00,0x10,0x36,0x89,0x02,0xcc, +0x02,0xce,0xc9,0x24,0xb7,0x07,0x02,0x20,0x83,0xa6,0x47,0xf1,0x93,0x57,0x79,0x00, +0x89,0x8b,0xf4,0x46,0xaa,0x85,0x52,0xc6,0x4e,0xc8,0x4a,0xca,0x23,0x24,0xf4,0x10, +0x70,0x00,0x26,0x85,0x82,0x96,0x13,0x07,0x00,0x10,0x15,0xe5,0xb2,0x47,0x85,0x46, +0xbd,0x8b,0x63,0xf9,0xf6,0x00,0xd2,0x47,0x85,0x66,0x93,0x86,0x06,0xf0,0xf5,0x8f, +0x63,0x83,0xe7,0x02,0x83,0x47,0x44,0x00,0x23,0x0e,0x04,0x02,0x81,0xe7,0x85,0x47, +0x23,0x02,0xf4,0x00,0x01,0x45,0xf2,0x50,0x62,0x54,0xd2,0x54,0x42,0x59,0xb2,0x59, +0x22,0x5a,0x21,0x61,0x82,0x80,0x1c,0x40,0x23,0xa0,0x07,0x06,0x23,0xa2,0x07,0x06, +0xd1,0xbf,0x01,0x11,0x52,0xc4,0x13,0x0a,0x80,0x23,0x22,0xcc,0x03,0x54,0x0a,0x03, +0x26,0xca,0x4a,0xc8,0x06,0xce,0x4e,0xc6,0x56,0xc2,0x2a,0x04,0xb2,0x84,0x2e,0x89, +0x63,0x7d,0x86,0x00,0x01,0x45,0xb5,0xe8,0xf2,0x40,0x62,0x44,0xd2,0x44,0x42,0x49, +0xb2,0x49,0x22,0x4a,0x92,0x4a,0x05,0x61,0x82,0x80,0xb3,0xf9,0x85,0x02,0xb3,0x0a, +0x34,0x41,0x63,0x05,0x54,0x03,0xb7,0x07,0x02,0x20,0x83,0xa7,0x47,0xf1,0x83,0x25, +0x8a,0x10,0x03,0x25,0x0a,0x00,0x9c,0x4f,0x56,0x87,0xca,0x86,0x13,0x06,0x8a,0x00, +0x82,0x97,0x79,0xf1,0xa6,0x99,0xb3,0x84,0x89,0x40,0x56,0x99,0xe3,0x7c,0x94,0xfa, +0x93,0x0a,0x00,0x24,0xb7,0x09,0x02,0x20,0x21,0xa0,0x22,0x99,0x63,0x71,0x94,0x02, +0x83,0xa7,0x49,0xf1,0x83,0x25,0x8a,0x10,0x03,0x25,0x0a,0x00,0xdc,0x53,0xca,0x86, +0x56,0x86,0x82,0x97,0x81,0x8c,0x75,0xd1,0x41,0xbf,0x93,0x0a,0x00,0x24,0xb7,0x07, +0x02,0x20,0x83,0xa7,0x47,0xf1,0x62,0x44,0x83,0x25,0x8a,0x10,0x03,0x25,0x0a,0x00, +0xf2,0x40,0xb2,0x49,0x22,0x4a,0x9c,0x4f,0x26,0x87,0xca,0x86,0xd2,0x44,0x42,0x49, +0x56,0x86,0x92,0x4a,0x05,0x61,0x82,0x87,0xb7,0x07,0x02,0x20,0x83,0xa7,0x47,0xf1, +0x13,0x08,0x80,0x23,0x83,0xa8,0x87,0x02,0x2e,0x87,0x03,0x25,0x08,0x00,0x83,0x25, +0x88,0x10,0xb6,0x87,0xb2,0x86,0x13,0x06,0x88,0x00,0x82,0x88,0xb7,0x07,0x02,0x20, +0x83,0xa7,0x47,0xf1,0x13,0x08,0x80,0x23,0x2e,0x83,0x83,0xa8,0xc7,0x02,0x83,0x25, +0x88,0x10,0x03,0x25,0x08,0x00,0x32,0x87,0xb6,0x87,0x13,0x06,0x88,0x00,0x9a,0x86, +0x82,0x88,0x81,0xcd,0x93,0x07,0x80,0x23,0x98,0x57,0x83,0xd7,0xe7,0x02,0x01,0x45, +0x2a,0x07,0xaa,0x07,0x98,0xc1,0xdc,0xc1,0x82,0x80,0x09,0x45,0x82,0x80,0xb7,0x07, +0x02,0x20,0x83,0xa7,0x47,0xf1,0x13,0x06,0x80,0x23,0x83,0x25,0x86,0x10,0x08,0x42, +0xdc,0x4f,0x21,0x06,0x82,0x87,0x82,0x80,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00, +0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00, +0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00, +0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00, +0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00, +0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00, +0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00, +0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00, +0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00, +0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00, +0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00, +0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00, +0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00, +0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00, +0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00, +0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00, +0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00, +0x00,0x00,0x00,0x00,0x3d,0x43,0x2a,0x87,0x63,0x73,0xc3,0x02,0x93,0x77,0xf7,0x00, +0xbd,0xef,0xad,0xe5,0x93,0x76,0x06,0xff,0x3d,0x8a,0xba,0x96,0x0c,0xc3,0x4c,0xc3, +0x0c,0xc7,0x4c,0xc7,0x41,0x07,0xe3,0x6b,0xd7,0xfe,0x11,0xe2,0x82,0x80,0xb3,0x06, +0xc3,0x40,0x8a,0x06,0x97,0x02,0x00,0x00,0x96,0x96,0x67,0x80,0xa6,0x00,0x23,0x07, +0xb7,0x00,0xa3,0x06,0xb7,0x00,0x23,0x06,0xb7,0x00,0xa3,0x05,0xb7,0x00,0x23,0x05, +0xb7,0x00,0xa3,0x04,0xb7,0x00,0x23,0x04,0xb7,0x00,0xa3,0x03,0xb7,0x00,0x23,0x03, +0xb7,0x00,0xa3,0x02,0xb7,0x00,0x23,0x02,0xb7,0x00,0xa3,0x01,0xb7,0x00,0x23,0x01, +0xb7,0x00,0xa3,0x00,0xb7,0x00,0x23,0x00,0xb7,0x00,0x82,0x80,0x93,0xf5,0xf5,0x0f, +0x93,0x96,0x85,0x00,0xd5,0x8d,0x93,0x96,0x05,0x01,0xd5,0x8d,0x61,0xb7,0x93,0x96, +0x27,0x00,0x97,0x02,0x00,0x00,0x96,0x96,0x86,0x82,0xe7,0x80,0x86,0xfa,0x96,0x80, +0xc1,0x17,0x1d,0x8f,0x3e,0x96,0xe3,0x74,0xc3,0xf8,0xa5,0xb7, + diff --git a/contrib/loaders/flash/hpmicro/linker.ld b/contrib/loaders/flash/hpmicro/linker.ld new file mode 100644 index 0000000000..b2c9cde232 --- /dev/null +++ b/contrib/loaders/flash/hpmicro/linker.ld @@ -0,0 +1,44 @@ +ENTRY(_init) + +SECTIONS +{ + .text : { + *(.func_table) + KEEP(*(.flash_algo.text*)) + KEEP(*(.rodata)) + KEEP(*(.rodata*)) + KEEP(*(.flash_algo.data*)) + *(.text) + *(.text*) + __etext = .; + } + .discard : { + __noncacheable_start__ = .; + __noncacheable_bss_start__ = .; + __bss_start__ = .; + __bss_end__ = .; + __noncacheable_bss_end__ = .; + _end = .; + __noncacheable_init_start__ = .; + __data_start__ = .; + __data_end__ = .; + __noncacheable_init_end__ = .; + __noncacheable_end__ = .; + __heap_start__ = .; + __heap_end__ = .; + __ramfunc_start__ = .; + __ramfunc_end__ = .; + __noncacheable_bss_start__ = .; + __noncacheable_bss_end__ = .; + __noncacheable_init_start__ = .; + __noncacheable_init_end__ = .; + __tdata_start__ = .; + __tdata_end__ = .; + __tbss_start__ = .; + __tbss_end__ = .; + __data_load_addr__ = .; + __fast_load_addr__ = .; + __tdata_load_addr__ = .; + __noncacheable_init_load_addr__ = .; + } +} diff --git a/contrib/loaders/flash/hpmicro/openocd_flash_algo.c b/contrib/loaders/flash/hpmicro/openocd_flash_algo.c new file mode 100644 index 0000000000..5ded16c34e --- /dev/null +++ b/contrib/loaders/flash/hpmicro/openocd_flash_algo.c @@ -0,0 +1,150 @@ +/* + * Copyright (c) 2021 HPMicro + * + * SPDX-License-Identifier: BSD-3-Clause + * + */ + +#include "hpm_romapi.h" + +#define XPI0_MEM_START (0x80000000UL) +#define XPI1_MEM_START (0x90000000UL) +#define XPI_USE_PORT_B_MASK (0x100) +#define XPI_USE_PORT_A_MASK (0) +#define XPI_USE_PORT_SHIFT (0x8) + +typedef struct { + uint32_t total_sz_in_bytes; + uint32_t sector_sz_in_bytes; +} hpm_flash_info_t; + +__attribute__ ((section(".flash_algo.data"))) xpi_nor_config_t nor_config; +__attribute__ ((section(".flash_algo.data"))) bool xpi_inited = false; +__attribute__ ((section(".flash_algo.data"))) uint32_t channel = xpi_channel_a1; +__attribute__ ((section(".flash_algo.data"))) XPI_Type *xpi_base; + + +__attribute__ ((section(".flash_algo.text"))) void refresh_device_size(XPI_Type *base, xpi_nor_config_option_t *option) +{ + volatile uint32_t *dev_size = (volatile uint32_t *)((uint32_t)base + 0x60); + bool enable_channelb = false; + if (option->header.words > 1) { + enable_channelb = option->option1.connection_sel == xpi_nor_connection_sel_chnb_cs0; + } + if (enable_channelb) { + dev_size[0] = 0; + dev_size[1] = 0; + } +} + +__attribute__ ((section(".flash_algo.text"))) uint32_t flash_init(uint32_t flash_base, uint32_t header, uint32_t opt0, uint32_t opt1, uint32_t xpi_base_addr) +{ + uint32_t i = 0; + xpi_nor_config_option_t cfg_option; + hpm_stat_t stat = status_success; + + xpi_base = (XPI_Type *)xpi_base_addr; + if (xpi_inited) { + return stat; + } + + for (i = 0; i < sizeof(cfg_option); i++) { + *((uint8_t *)&cfg_option + i) = 0; + } + for (i = 0; i < sizeof(nor_config); i++) { + *((uint8_t *)&nor_config + i) = 0; + } + + cfg_option.header.U = header; + cfg_option.option0.U = opt0; + cfg_option.option1.U = opt1; + + if (opt1 & XPI_USE_PORT_B_MASK) { + channel = xpi_channel_b1; + } else { + channel = xpi_channel_a1; + } + + stat = ROM_API_TABLE_ROOT->xpi_nor_driver_if->auto_config(xpi_base, &nor_config, &cfg_option); + if (stat) { + return stat; + } + + refresh_device_size(xpi_base, &cfg_option); + + nor_config.device_info.clk_freq_for_non_read_cmd = 0; + if (!xpi_inited) { + xpi_inited = true; + } + return stat; +} + +__attribute__ ((section(".flash_algo.text"))) uint32_t flash_erase(uint32_t flash_base, uint32_t address, uint32_t size) +{ + hpm_stat_t stat = status_success; + uint32_t left, start, block_size, align; + + left = size; + start = address; + block_size = nor_config.device_info.block_size_kbytes * 1024; + if (left >= block_size) { + align = block_size - (start % block_size); + if (align != block_size) { + stat = ROM_API_TABLE_ROOT->xpi_nor_driver_if->erase(xpi_base, channel, &nor_config, start, align); + if (stat != status_success) { + return stat; + } + left -= align; + start += align; + } + while (left > block_size) { + stat = ROM_API_TABLE_ROOT->xpi_nor_driver_if->erase_block(xpi_base, channel, &nor_config, start); + if (stat != status_success) { + break; + } + left -= block_size; + start += block_size; + } + } + if ((stat == status_success) && left) { + stat = ROM_API_TABLE_ROOT->xpi_nor_driver_if->erase(xpi_base, channel, &nor_config, start, left); + } + return stat; +} + +__attribute__ ((section(".flash_algo.text"))) uint32_t flash_program(uint32_t flash_base, uint32_t address, uint32_t *buf, uint32_t size) +{ + hpm_stat_t stat; + + stat = ROM_API_TABLE_ROOT->xpi_nor_driver_if->program(xpi_base, channel, &nor_config, buf, address, size); + return stat; +} + +__attribute__ ((section(".flash_algo.text"))) uint32_t flash_read(uint32_t flash_base, uint32_t *buf, uint32_t address, uint32_t size) +{ + hpm_stat_t stat; + + stat = ROM_API_TABLE_ROOT->xpi_nor_driver_if->read(xpi_base, channel, &nor_config, buf, address, size); + return stat; +} + +__attribute__ ((section(".flash_algo.text"))) uint32_t flash_get_info(uint32_t flash_base, hpm_flash_info_t *flash_info) +{ + if (!flash_info) { + return status_invalid_argument; + } + + flash_info->total_sz_in_bytes = nor_config.device_info.size_in_kbytes << 10; + flash_info->sector_sz_in_bytes = nor_config.device_info.sector_size_kbytes << 10; + return status_success; +} + +__attribute__ ((section(".flash_algo.text"))) uint32_t flash_erase_chip(uint32_t flash_base) +{ + return ROM_API_TABLE_ROOT->xpi_nor_driver_if->erase_chip(xpi_base, channel, &nor_config); +} + +__attribute__ ((section(".flash_algo.text"))) void flash_deinit(void) +{ + return; +} --