[sync] sync from internal repo

* use nuttx libc, disable system libc
* use tlsf as default
* update lhal flash driver
* add example readme
* add flash ini for new flash tool
* add fw header for new flash tool
This commit is contained in:
jzlv 2023-01-17 20:54:15 +08:00
parent 89592fc9a3
commit 356f258e83
554 changed files with 79150 additions and 46596 deletions

View file

@ -0,0 +1,43 @@
# boot2_isp
## Support CHIP
| CHIP | Remark |
|:----------------:|:------:|
|BL602/BL604 | |
|BL702/BL704/BL706 | |
|BL616/BL618 | |
|BL808 | Only for m0 CPU |
## Compile
- BL602/BL604
```
make CHIP=bl602 BOARD=bl602dk
```
- BL702/BL704/BL706
```
make CHIP=bl702 BOARD=bl702dk
```
- BL616/BL618
```
make CHIP=bl616 BOARD=bl616dk
```
- BL808
```
make CHIP=bl808 BOARD=bl808dk CPU_ID=m0
```
## Flash
```
make flash CHIP=chip_name COMX=xxx # xxx is your com name
```

View file

@ -48,6 +48,8 @@
#define BFLB_EFLASH_LOADER_CHECK_LEN 2048
#define BFLB_EFLASH_MAX_SIZE 2 * 1024 * 1024
// 4bytes、32bit数据大小端转化
#define L2B32(Little) (((Little & 0xff) << 24) | (((Little) & 0xff00) << 8) | (((Little) & 0xff0000) >> 8) | ((Little >> 24) & 0xff))
#if BLSP_BOOT2_SUPPORT_EFLASH_LOADER_RAM
static struct image_cfg_t image_cfg;
@ -479,9 +481,12 @@ static int32_t bflb_eflash_loader_cmd_read_jedec_id(uint16_t cmd, uint8_t *data,
/*ack read jedec ID */
tmp_buf[2] = 4;
tmp_buf[3] = 0;
ackdata[0] = bflb_flash_get_jedec_id();
ackdata[1] = bflb_flash_get_jedec_id();
ackdata[1] &= 0x00ffffff;
ackdata[1] |= 0x80000000;
ackdata[1] = (ackdata[1]) << 8;
ackdata[1] |= 0x80;
ackdata[1] = L2B32(ackdata[1]);
bflb_eflash_loader_if_write((uint32_t *)ackdata, 4 + 4);
return BFLB_EFLASH_LOADER_SUCCESS;
}

View file

@ -120,7 +120,7 @@ struct eflash_loader_cmd_cfg_t {
__PACKED_STRUCT boot_flash_cfg_t
{
uint32_t magiccode; /*'FCFG'*/
SPI_Flash_Cfg_Type cfg;
spi_flash_cfg_type cfg;
uint32_t crc32;
};

View file

@ -39,6 +39,7 @@
#include "partition.h"
#include "bflb_uart.h"
#include "bflb_port_boot2.h"
#include "bflb_uart.h"
static uint32_t g_detected_baudrate;
struct bflb_device_s *uartx;
@ -53,10 +54,39 @@ void bflb_dump_data(uint8_t *buf, uint32_t size)
}
LOG_F("\r\n");
}
static uint32_t uart_read_all_data(uint8_t *buf,uint32_t maxlen)
{
return bflb_uart_get(uartx, buf, maxlen);
}
void ATTR_TCM_SECTION uart0_irq_callback(struct device *dev, void *args, uint32_t size, uint32_t state)
{
}
void ATTR_TCM_SECTION uart_isr(int irq, void *arg)
{
uint32_t intstatus = bflb_uart_get_intstatus(uartx);
if (intstatus & UART_INTSTS_RX_FIFO) {
uint8_t *buf=(uint8_t *)g_eflash_loader_readbuf[g_rx_buf_index];
g_rx_buf_len+=uart_read_all_data(buf+g_rx_buf_len,
BFLB_EFLASH_LOADER_READBUF_SIZE-g_rx_buf_len);
bflb_uart_int_clear(uartx, UART_INTSTS_RX_FIFO);
}
if (intstatus & UART_INTSTS_RTO) {
uint8_t *buf=(uint8_t *)g_eflash_loader_readbuf[g_rx_buf_index];
g_rx_buf_len+=uart_read_all_data(buf+g_rx_buf_len,
BFLB_EFLASH_LOADER_READBUF_SIZE-g_rx_buf_len);
bflb_uart_int_clear(uartx, UART_INTCLR_RTO);
}
}
static void bflb_eflash_loader_usart_if_init(uint32_t bdrate)
{
struct bflb_uart_config_s cfg;
@ -68,8 +98,8 @@ static void bflb_eflash_loader_usart_if_init(uint32_t bdrate)
cfg.stop_bits = UART_STOP_BITS_1;
cfg.parity = UART_PARITY_NONE;
cfg.flow_ctrl = 0;
cfg.tx_fifo_threshold = 7;
cfg.rx_fifo_threshold = 7;
cfg.tx_fifo_threshold = 16;
cfg.rx_fifo_threshold = 16;
bflb_uart_init(uartx, &cfg);
}
@ -80,7 +110,7 @@ void bflb_eflash_loader_usart_if_enable_int(void)
void bflb_eflash_loader_usart_if_send(uint8_t *data, uint32_t len)
{
uartx = bflb_device_get_by_name("uart0");
//uartx = bflb_device_get_by_name("uart0");
bflb_uart_put(uartx, data, len);
}
@ -94,6 +124,35 @@ int32_t bflb_eflash_loader_usart_if_wait_tx_idle(uint32_t timeout)
static uint32_t *bflb_eflash_loader_usart_if_receive(uint32_t *recv_len, uint16_t maxlen, uint16_t timeout)
{
uint8_t *buf = (uint8_t *)g_eflash_loader_readbuf[g_rx_buf_index];
uint16_t datalen = 0;
uint64_t time_now;
time_now = bflb_mtimer_get_time_ms();
do {
if (g_rx_buf_len >= 4) {
/* receive cmd id and data len*/
datalen = buf[2] + (buf[3] << 8);
if (g_rx_buf_len == datalen + 4) {
/*receive all the payload,return */
/* move on to next buffer */
g_rx_buf_index = (g_rx_buf_index + 1) % 2;
g_rx_buf_len = 0;
if (datalen <= BFLB_EFLASH_LOADER_CMD_DATA_MAX_LEN) {
*recv_len = datalen + 4;
return (uint32_t *)buf;
} else {
*recv_len = 0;
return NULL;
}
}
}
} while (bflb_mtimer_get_time_ms() - time_now < timeout);
*recv_len = 0;
return NULL;
}
@ -118,7 +177,7 @@ int32_t bflb_eflash_loader_uart_handshake_poll(uint32_t timeout)
uint32_t handshake_count = 0;
uint32_t rcv_buf_len = 0;
//rcv_buf_len = UART_ReceiveData(g_uart_if_id,buf,128);
uartx = bflb_device_get_by_name("uart0");
//uartx = bflb_device_get_by_name("uart0");
rcv_buf_len = bflb_uart_get(uartx, buf, UART_FIFO_LEN);
//while(1)
@ -167,7 +226,7 @@ int32_t bflb_eflash_loader_uart_handshake_poll(uint32_t timeout)
}
} while (bflb_mtimer_get_time_ms() - nowtime < BFLB_EFLASH_LAODER_COMSUME_55_TIMEOUT);
bflb_eflash_loader_usart_if_send((uint8_t *)"Boot2 ISP Ready", strlen("Boot2 ISP Ready"));
/*init rx info */
g_rx_buf_index = 0;
@ -180,7 +239,10 @@ int32_t bflb_eflash_loader_uart_handshake_poll(uint32_t timeout)
arch_memset(g_eflash_loader_readbuf[0], 0, BFLB_EFLASH_LOADER_READBUF_SIZE);
arch_memset(g_eflash_loader_readbuf[1], 0, BFLB_EFLASH_LOADER_READBUF_SIZE);
bflb_irq_attach(uartx->irq_num, uart_isr, NULL);
bflb_eflash_loader_usart_if_enable_int();
bflb_irq_enable(uartx->irq_num);
bflb_eflash_loader_usart_if_send((uint8_t *)"Boot2 ISP Ready", strlen("Boot2 ISP Ready"));
#endif

View file

@ -43,6 +43,7 @@
#include "blsp_media_boot.h"
#include "bflb_flash.h"
#include "bflb_eflash_loader.h"
#include "bflb_uart.h"
ATTR_NOCACHE_NOINIT_RAM_SECTION uint8_t g_malloc_buf[BFLB_BOOT2_XZ_MALLOC_BUF_SIZE];
@ -88,7 +89,7 @@ int32_t blsp_mediaboot_pre_jump(void)
/* reinit mtimer clock */
//system_mtimer_clock_reinit();
bflb_uart_deinit(uartx);
/* deinit uart */
hal_boot2_debug_uart_gpio_deinit();

View file

@ -184,10 +184,10 @@ int32_t ATTR_TCM_SECTION blsp_boot2_set_encrypt(uint8_t index, boot2_image_confi
len = g_boot_img_cfg->basic_cfg.img_len_cnt;
if (len != 0) {
SF_Ctrl_AES_Set_Key_BE(index, NULL, (SF_Ctrl_AES_Key_Type)(g_boot_img_cfg->basic_cfg.encrypt_type - 1));
SF_Ctrl_AES_Set_IV_BE(index, g_boot_img_cfg->aes_iv, g_boot_img_cfg->basic_cfg.group_image_offset);
bflb_sf_ctrl_aes_set_key_be(index, NULL, (g_boot_img_cfg->basic_cfg.encrypt_type - 1));
bflb_sf_ctrl_aes_set_iv_be(index, g_boot_img_cfg->aes_iv, g_boot_img_cfg->basic_cfg.group_image_offset);
SF_Ctrl_AES_Set_Region(index, 1 /*enable this region*/, 1 /*hardware key*/,
bflb_sf_ctrl_aes_set_region(index, 1 /*enable this region*/, 1 /*hardware key*/,
g_boot_img_cfg->basic_cfg.group_image_offset,
g_boot_img_cfg->basic_cfg.group_image_offset + len - 1,
g_boot_img_cfg->basic_cfg.aes_region_lock /*lock*/);
@ -196,8 +196,8 @@ int32_t ATTR_TCM_SECTION blsp_boot2_set_encrypt(uint8_t index, boot2_image_confi
}
if (aes_enabled) {
SF_Ctrl_AES_Enable_BE();
SF_Ctrl_AES_Enable();
bflb_sf_ctrl_aes_enable_be();
bflb_sf_ctrl_aes_enable();
}
return BFLB_BOOT2_SUCCESS;

View file

@ -1,41 +0,0 @@
/**
******************************************************************************
* @file blsp_version.h
* @version V1.2
* @date
* @brief This file is the peripheral case header file
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT(c) 2018 Bouffalo Lab</center></h2>
*
* 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 of Bouffalo Lab 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 HOLDER 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 __MCU_SDK_VERSION_H__
#define __MCU_SDK_VERSION_H__
#define BL_SDK_VER "1.0.0"
#endif

View file

@ -0,0 +1,11 @@
[cfg]
# 0: no erase, 1:programmed section erase, 2: chip erase
erase = 1
# skip mode set first para is skip addr, second para is skip len, multi-segment region with ; separated
skip_mode = 0x0, 0x0
# 0: not use isp mode, #1: isp mode
boot2_isp_mode = 0
[FW]
filedir = ./build/build_out/boot2_isp_$(CHIPNAME).bin
address = 0x000000

View file

@ -362,7 +362,7 @@ int main(void)
#endif
uint8_t mfg_mode_flag = 0;
//boot_clk_config clk_cfg;
uint8_t flash_cfg_buf[4 + sizeof(SPI_Flash_Cfg_Type) + 4] = { 0 };
uint8_t flash_cfg_buf[4 + sizeof(spi_flash_cfg_type) + 4] = { 0 };
uint32_t crc;
uint8_t *flash_cfg = NULL;
uint32_t flash_cfg_len = 0;

View file

@ -3,8 +3,6 @@
#include "bl602_glb.h"
#include "bl602_ef_ctrl.h"
#include "bl602_hbn.h"
#include "bl602_xip_sflash.h"
#include "bl602_sf_cfg.h"
#include "bl602_sf_cfg_ext.h"
#include "bl602_glb.h"
#include "bl602_xip_sflash_ext.h"
@ -502,7 +500,7 @@ void ATTR_TCM_SECTION hal_boot2_release_cpu(uint32_t core, uint32_t boot_addr)
*******************************************************************************/
uint32_t hal_boot2_get_xip_addr(uint32_t flash_addr)
{
uint32_t img_offset = SF_Ctrl_Get_Flash_Image_Offset();
uint32_t img_offset = bflb_sf_ctrl_get_flash_image_offset(0,0);
if (flash_addr >= img_offset) {
return BL602_FLASH_XIP_BASE + (flash_addr - img_offset);
} else {

View file

@ -36,7 +36,6 @@
#ifndef __BFLB_PORT_BOOT2_H__
#define __BFLB_PORT_BOOT2_H__
#include "bl602_sflash.h"
#include "bl602_glb.h"
#define BL_TCM_BASE BL602_TCM_BASE
@ -101,7 +100,7 @@ typedef struct
struct __attribute__((packed, aligned(4))) hal_flash_config {
uint32_t magicCode; /*'FCFG'*/
SPI_Flash_Cfg_Type cfg;
spi_flash_cfg_type cfg;
uint32_t crc32;
};

View file

@ -5,7 +5,6 @@
#include "bl606p_hbn.h"
#include "bl606p_glb.h"
#include "bl606p_pds.h"
#include "bl606p_xip_sflash.h"
#include "bl606p_tzc_sec.h"
#include "bflb_gpio.h"
#include "softcrc.h"
@ -195,7 +194,7 @@ static uint16_t hal_boot2_x8_psram_calibration(int32_t *psram_dqs_win_num)
LOG_F("r ef:0x%08lx\r\n", g_efuse_cfg.psram_dqs_cfg);
before_ef = g_efuse_cfg.psram_dqs_cfg;
if ((g_efuse_cfg.psram_dqs_cfg & (0x1000)) && (g_efuse_cfg.psram_dqs_cfg != 0xffff)) {
if (g_efuse_cfg.psram_dqs_cfg != 0xffff) {
left_flag = ((g_efuse_cfg.psram_dqs_cfg & (0xf0)) >> 0x4);
right_flag = (g_efuse_cfg.psram_dqs_cfg & (0xf));
c_val = ((left_flag + right_flag) >> 0x1);
@ -225,11 +224,7 @@ static uint16_t hal_boot2_x8_psram_calibration(int32_t *psram_dqs_win_num)
c_val = ((left_flag + right_flag) >> 1);
g_efuse_cfg.psram_dqs_cfg = (((left_flag << 0x4) | (right_flag)) & (0xff));
if (bflb_ef_ctrl_get_trim_parity(g_efuse_cfg.psram_dqs_cfg, 11)) {
g_efuse_cfg.psram_dqs_cfg = ((0x1800) | (g_efuse_cfg.psram_dqs_cfg));
} else {
g_efuse_cfg.psram_dqs_cfg = ((0x1000) | (g_efuse_cfg.psram_dqs_cfg));
}
LOG_F("c ef:0x%08lx\r\n", g_efuse_cfg.psram_dqs_cfg);
*psram_dqs_win_num = right_flag - left_flag;
if (((*psram_dqs_win_num) <= 4) || ((*psram_dqs_win_num) > 0xf)) {
@ -364,11 +359,11 @@ uint32_t hal_boot2_custom(void *custom_param)
ret = hal_boot2_x8_psram_calibration(&psram_dqs_win_num);
if (ret == ERROR) {
while (1) {
printf("psram:%d\r\n", (int)psram_dqs_win_num);
LOG_F("psram:%d\r\n", (int)psram_dqs_win_num);
arch_delay_ms(500);
}
}
printf("psram:%d \r\n", (int)psram_dqs_win_num);
LOG_F("psram:%d \r\n", (int)psram_dqs_win_num);
/* Flush i-cache in case branch prediction logic is wrong when
psram is not inited by hal_boot2_custom but cpu has already prefetch psram */
@ -449,7 +444,7 @@ void hal_boot2_get_efuse_cfg(boot2_efuse_hw_config *efuse_cfg)
}
/* get device info */
//EF_Ctrl_Get_Chip_Info((Efuse_Chip_Info_Type *)&efuse_cfg->dev_info);
bflb_ef_ctrl_get_device_info((bflb_efuse_device_info_type *)&efuse_cfg->dev_info);
/* get chip id */
bflb_efuse_get_chipid(efuse_cfg->chip_id);
@ -858,7 +853,7 @@ void ATTR_TCM_SECTION hal_boot2_release_cpu(uint32_t core, uint32_t boot_addr)
*******************************************************************************/
uint32_t hal_boot2_get_xip_addr(uint32_t flash_addr)
{
uint32_t img_offset = SF_Ctrl_Get_Flash_Image_Offset(0, SF_CTRL_FLASH_BANK0);
uint32_t img_offset = bflb_sf_ctrl_get_flash_image_offset(0, SF_CTRL_FLASH_BANK0);
if (flash_addr >= img_offset) {
return BL606P_FLASH_XIP_BASE + (flash_addr - img_offset);
} else {

View file

@ -36,7 +36,6 @@
#ifndef __BFLB_PORT_BOOT2_H__
#define __BFLB_PORT_BOOT2_H__
#include "bl606p_sflash.h"
#include "bl606p_glb.h"
#include "bl606p_pm.h"
@ -167,13 +166,13 @@ typedef struct
struct __attribute__((packed, aligned(4))) hal_flash_config {
uint32_t magicCode; /*'FCFG'*/
SPI_Flash_Cfg_Type cfg;
spi_flash_cfg_type cfg;
uint32_t crc32;
};
struct hal_psram_config {
uint32_t magicCode; /*'FCFG'*/
SPI_Flash_Cfg_Type cfg;
spi_flash_cfg_type cfg;
uint32_t crc32;
};

View file

@ -23,7 +23,7 @@ HeapMinSize = 0x1000; /* 4KB */
PROVIDE(__boot2_pass_param_addr = 0x62047E00);/* 0x62030000+96*1024-512 */
MEMORY
{
xip_memory (rx) : ORIGIN = 0x58000000, LENGTH = 48K
xip_memory (rx) : ORIGIN = 0x58000000, LENGTH = 58K
itcm_memory (rx) : ORIGIN = 0x62020000, LENGTH = 48K
dtcm_memory (rx) : ORIGIN = 0x6202C000, LENGTH = 4K
nocache_ram_memory (!rx) : ORIGIN = 0x2202D000, LENGTH = 84K

View file

@ -38,11 +38,11 @@
#include "bl616_ef_ctrl.h"
#include "bl616_hbn.h"
#include "bl616_glb.h"
#include "bl616_xip_sflash.h"
#include "bl616_tzc_sec.h"
#include "softcrc.h"
#include "bl616_psram.h"
#include "bflb_flash.h"
#include "log.h"
/****************************************************************************/ /**
* @brief init boot2 system clock
@ -228,8 +228,7 @@ static uint16_t hal_boot2_x8_psram_calibration(int32_t *psram_dqs_win_num)
printf("r ef:0x%08lx\r\n", g_efuse_cfg.psram_dqs_cfg);
#endif
before_ef = g_efuse_cfg.psram_dqs_cfg;
if ((g_efuse_cfg.psram_dqs_cfg & (0x1000)) &&
(((g_efuse_cfg.psram_dqs_cfg & 0x800) >> 11) == EF_Ctrl_Get_Trim_Parity(g_efuse_cfg.psram_dqs_cfg, 11))) {
if (g_efuse_cfg.psram_dqs_cfg != 0xffff) {
left_flag = ((g_efuse_cfg.psram_dqs_cfg & (0xf0)) >> 0x4);
right_flag = (g_efuse_cfg.psram_dqs_cfg & (0xf));
c_val = ((left_flag + right_flag) >> 0x1);
@ -263,11 +262,7 @@ static uint16_t hal_boot2_x8_psram_calibration(int32_t *psram_dqs_win_num)
// printf("window: 0x%02x ~ 0x%02x; c_val: 0x%02x; dqs:0x%04x; code num:%d\r\n", left_flag, right_flag, c_val, dqs_val[c_val], (right_flag - left_flag));
g_efuse_cfg.psram_dqs_cfg = (((left_flag << 0x4) | (right_flag)) & (0xff));
if (EF_Ctrl_Get_Trim_Parity(g_efuse_cfg.psram_dqs_cfg, 11)) {
g_efuse_cfg.psram_dqs_cfg = ((0x1800) | (g_efuse_cfg.psram_dqs_cfg));
} else {
g_efuse_cfg.psram_dqs_cfg = ((0x1000) | (g_efuse_cfg.psram_dqs_cfg));
}
#ifdef CONFIG_DEBUG
printf("c ef:0x%08lx\r\n", g_efuse_cfg.psram_dqs_cfg);
/* printf("window: 0x%02x ~ 0x%02x; c_val: 0x%02x; dqs:0x%08x; code num:%d\r\n", left_flag, right_flag, c_val, dqs_val[c_val], (right_flag - left_flag)); */
@ -282,7 +277,7 @@ static uint16_t hal_boot2_x8_psram_calibration(int32_t *psram_dqs_win_num)
}
/* to do write efuse psram dqs delay */
if (!(before_ef & 0x1fff)) {
// EF_Ctrl_Write_Psram_Trim((Efuse_Psram_Trim_Type *)&g_efuse_cfg.psram_dqs_cfg, ENABLE);
bflb_ef_ctrl_write_common_trim(NULL,"psram",g_efuse_cfg.psram_dqs_cfg,1);
}
}
return psram_id;
@ -314,11 +309,11 @@ uint32_t hal_boot2_custom(void *custom_param)
__ISB();
if (ret == ERROR) {
while (1) {
printf("psram error:%d\r\n", (int)psram_dqs_win_num);
LOG_F("psram error:%d\r\n", (int)psram_dqs_win_num);
arch_delay_ms(500);
}
}
printf("psram suss:%d \r\n", (int)psram_dqs_win_num);
LOG_F("psram suss:%d \r\n", (int)psram_dqs_win_num);
}
return ret;
@ -790,7 +785,7 @@ void ATTR_TCM_SECTION hal_boot2_release_cpu(uint32_t core, uint32_t boot_addr)
*******************************************************************************/
uint32_t hal_boot2_get_xip_addr(uint32_t flash_addr)
{
uint32_t img_offset = SF_Ctrl_Get_Flash_Image_Offset(0, SF_CTRL_FLASH_BANK0);
uint32_t img_offset = bflb_sf_ctrl_get_flash_image_offset(0, SF_CTRL_FLASH_BANK0);
if (flash_addr >= img_offset) {
return BL616_FLASH_XIP_BASE + (flash_addr - img_offset);
} else {

View file

@ -36,7 +36,6 @@
#ifndef __BFLB_PORT_BOOT2_H__
#define __BFLB_PORT_BOOT2_H__
#include "bl616_sflash.h"
#include "bl616_glb.h"
#include "bl616_common.h"
@ -165,7 +164,7 @@ typedef struct
struct __attribute__((packed, aligned(4))) hal_flash_config {
uint32_t magicCode; /*'FCFG'*/
SPI_Flash_Cfg_Type cfg;
spi_flash_cfg_type cfg;
uint32_t crc32;
};

View file

@ -3,7 +3,6 @@
#include "bl702_ef_ctrl.h"
#include "bl702_hbn.h"
#include "bl702_glb.h"
#include "bl702_xip_sflash.h"
#include "bflb_gpio.h"
#include "softcrc.h"
#include "bl702_clock.h"
@ -492,7 +491,7 @@ void ATTR_TCM_SECTION hal_boot2_release_cpu(uint32_t core, uint32_t boot_addr)
*******************************************************************************/
uint32_t hal_boot2_get_xip_addr(uint32_t flash_addr)
{
uint32_t img_offset = SF_Ctrl_Get_Flash_Image_Offset();
uint32_t img_offset = bflb_sf_ctrl_get_flash_image_offset(0,0);
if (flash_addr >= img_offset) {
return BL702_FLASH_XIP_BASE + (flash_addr - img_offset);
} else {

View file

@ -40,7 +40,6 @@
extern "C" {
#endif
#include "bl702_sflash.h"
#include "bl702_glb.h"
#define BL_TCM_BASE BL702_TCM_BASE
@ -105,7 +104,7 @@ typedef struct
struct __attribute__((packed, aligned(4))) hal_flash_config {
uint32_t magicCode; /*'FCFG'*/
SPI_Flash_Cfg_Type cfg;
spi_flash_cfg_type cfg;
uint32_t crc32;
};

View file

@ -4,12 +4,12 @@
#include "bl808_ef_cfg.h"
#include "bl808_hbn.h"
#include "bl808_glb.h"
#include "bl808_xip_sflash.h"
#include "bl808_tzc_sec.h"
#include "bflb_gpio.h"
#include "softcrc.h"
#include "bl808_psram_uhs.h"
#include "bflb_efuse.h"
#include "bl808_uhs_phy.h"
/****************************************************************************/ /**
* @brief init clock
@ -38,17 +38,55 @@ void hal_boot2_init_clock(void)
*******************************************************************************/
uint32_t hal_boot2_custom(void *custom_param)
{
extern uhs_phy_cal_res_struct* uhs_phy_cal_res;
PSRAM_UHS_Cfg_Type psramDefaultCfg = {
2000,
PSRAM_MEM_SIZE_32MB,
PSRAM_PAGE_SIZE_2KB,
PSRAM_UHS_NORMAL_TEMP,
};
bflb_efuse_device_info_type chip_info;
//EF_Ctrl_Trim_DCDC_And_LDO();
AON_Trim_USB20_RCAL();
//GLB_Readjust_LDO18IO_Vout();
if (((g_efuse_cfg.dev_info & HAL_BOOT2_PSRAM_INFO_MASK) >> HAL_BOOT2_PSRAM_INFO_POS) != 0) {
GLB_Config_UHS_PLL(GLB_XTAL_40M, uhsPllCfg_2000M);
Psram_UHS_x16_Init(2000);
Tzc_Sec_PSRAMA_Access_Release();
bflb_ef_ctrl_get_device_info(&chip_info);
if (chip_info.psramInfo == UHS_32MB_PSRAM) {
psramDefaultCfg.psramMemSize = PSRAM_MEM_SIZE_32MB;
} else if (chip_info.psramInfo == UHS_64MB_PSRAM) {
psramDefaultCfg.psramMemSize = PSRAM_MEM_SIZE_64MB;
} else {
return 2;
}
/* Flush i-cache in case branch prediction logic is wrong when
psram is not inited by hal_boot2_custom but cpu has already prefetch psram */
__ISB();
//init uhs PLL; Must open uhs pll first, and then initialize uhs psram
GLB_Config_UHS_PLL(GLB_XTAL_40M, uhsPllCfg_2000M);
//init uhs psram ;
// Psram_UHS_x16_Init(Clock_Peripheral_Clock_Get(BL_PERIPHERAL_CLOCK_PSRAMA) / 1000000);
Psram_UHS_x16_Init_Override(&psramDefaultCfg);
Tzc_Sec_PSRAMA_Access_Release();
#if 0
// example: 2000Mbps typical cal values
uhs_phy_cal_res->rl = 39;
uhs_phy_cal_res->rdqs = 3;
uhs_phy_cal_res->rdq = 0;
uhs_phy_cal_res->wl = 13;
uhs_phy_cal_res->wdqs = 4;
uhs_phy_cal_res->wdq = 5;
uhs_phy_cal_res->ck = 9;
/* TODO: use uhs psram trim update */
set_uhs_latency_r(uhs_phy_cal_res->rl);
cfg_dqs_rx(uhs_phy_cal_res->rdqs);
cfg_dq_rx(uhs_phy_cal_res->rdq);
set_uhs_latency_w(uhs_phy_cal_res->wl);
cfg_dq_drv(uhs_phy_cal_res->wdq);
cfg_ck_cen_drv(uhs_phy_cal_res->wdq + 4, uhs_phy_cal_res->wdq + 1);
cfg_dqs_drv(uhs_phy_cal_res->wdqs);
// set_odt_en();
mr_read_back();
#endif
}
return 0;
}
@ -99,9 +137,8 @@ void hal_boot2_get_efuse_cfg(boot2_efuse_hw_config *efuse_cfg)
efuse_cfg->keep_dbg_port_closed = (uint8_t)(sw_cfg0.keep_dbg_port_closed);
efuse_cfg->boot_pin_cfg = (uint8_t)(sw_cfg0.boot_pin_cfg);
/* get device info */ //FixZc
//EF_Ctrl_Get_Chip_Info((Efuse_Chip_Info_Type *)&efuse_cfg->dev_info);
/* get device info */
bflb_ef_ctrl_get_device_info((bflb_efuse_device_info_type *)&efuse_cfg->dev_info);
/* get chip id */
//EF_Ctrl_Read_Chip_ID(efuse_cfg->chip_id);
bflb_efuse_get_chipid(efuse_cfg->chip_id);
@ -542,7 +579,7 @@ void ATTR_TCM_SECTION hal_boot2_release_cpu(uint32_t core, uint32_t boot_addr)
*******************************************************************************/
uint32_t hal_boot2_get_xip_addr(uint32_t flash_addr)
{
uint32_t img_offset = SF_Ctrl_Get_Flash_Image_Offset(0, SF_CTRL_FLASH_BANK0);
uint32_t img_offset = bflb_sf_ctrl_get_flash_image_offset(0, SF_CTRL_FLASH_BANK0);
if (flash_addr >= img_offset) {
return BL808_FLASH_XIP_BASE + (flash_addr - img_offset);
} else {

View file

@ -36,7 +36,6 @@
#ifndef __BFLB_PORT_BOOT2_H__
#define __BFLB_PORT_BOOT2_H__
#include "bl808_sflash.h"
#include "bl808_glb.h"
#define HAL_PLL_CFG_MAGICCODE "PCFG"
@ -69,6 +68,12 @@
#define HAL_BOOT2_PSRAM_INFO_MASK (0xff0000)
#define HAL_BOOT2_PSRAM_INFO_POS (16)
#define WB_4MB_PSRAM (1)
#define UHS_32MB_PSRAM (2)
#define UHS_64MB_PSRAM (3)
#define WB_32MB_PSRAM (4)
#define NONE_UHS_PSRAM (-1)
typedef enum {
HAL_REBOOT_AS_BOOTPIN, /*!< reboot as bootpin level */
HAL_REBOOT_FROM_INTERFACE, /*!< reboot from interface, download mode */
@ -160,7 +165,7 @@ typedef struct
struct __attribute__((packed, aligned(4))) hal_flash_config {
uint32_t magicCode; /*'FCFG'*/
SPI_Flash_Cfg_Type cfg;
spi_flash_cfg_type cfg;
uint32_t crc32;
};