add EVB_LN822x iot exporer demo

add EVB_LN822x  iot exporer demo
This commit is contained in:
supowang
2020-06-19 11:10:17 +08:00
parent c90e31d90f
commit 875a14aaf0
102 changed files with 9104 additions and 4790 deletions

View File

@@ -0,0 +1,13 @@
#ifndef __DRV_ADC_MEASURE_H__
#define __DRV_ADC_MEASURE_H__
#include <stdint.h>
void drv_adc_init(void);
void drv_adc_trigger(void);
uint16_t drv_adc_read(uint8_t ch);
#endif // __DRV_ADC_MEASURE_H__

View File

@@ -0,0 +1,40 @@
#ifndef __SERIAL_HW_H__
#define __SERIAL_HW_H__
#include "hal/hal_uart.h"
struct SerialHardware;
struct Serial;
typedef enum {
SER_PORT_UART0 = 0,
SER_PORT_UART1 = 1,
SER_PORT_NUM = 2, /**< Number of serial ports */
SER_PORT_ID_INVALID = SER_PORT_NUM
}SerialPortID;
struct SerialHardwareVT
{
void (*init )(struct SerialHardware *ctx, struct Serial *ser, uint32_t baudrate);
void (*cleanup )(struct SerialHardware *ctx);
void (*txStart )(struct SerialHardware *ctx);
bool (*txSending )(struct SerialHardware *ctx);
bool (*setBaudrate)(struct SerialHardware *ctx, uint32_t baudrate);
};
struct SerialHardware
{
const struct SerialHardwareVT *table;
unsigned char *txbuffer;
unsigned char *rxbuffer;
size_t txbuffer_size;
size_t rxbuffer_size;
void *hw_device;
volatile bool isSending;
};
struct SerialHardware *serial_hw_getdesc(SerialPortID port_id);
#endif /* __SERIAL_HW_H__ */

View File

@@ -0,0 +1,31 @@
#include "hal/hal_adc.h"
#include "drv_adc_measure.h"
void drv_adc_init(void)
{
ADC_InitTypeDef adc_init_struct;
adc_init_struct.ADC_Autoff = FDISABLE;
adc_init_struct.ADC_ContinuousConvMode = FENABLE;
adc_init_struct.ADC_DataAlign = ADC_DataAlign_Right;
adc_init_struct.ADC_WaitMode = FDISABLE;
HAL_ADC_Init(ADC, &adc_init_struct);
HAL_ADC_PrescCfg(ADC, 42);//255: 256*2
HAL_ADC_SeqChanSelect_Cfg(ADC, ADC_CHAN_0);
HAL_ADC_Cmd(ADC, FENABLE);
HAL_ADC_SoftwareStartConvCmd(ADC);
}
uint16_t drv_adc_read(uint8_t ch)
{
uint16_t read_adc = 0;
for(volatile uint32_t t = 0; t < 40*3; t++);//delay xx us
read_adc = HAL_ADC_GetConversionValue(ADC, ch);
return read_adc;
}

View File

@@ -8,7 +8,7 @@
#include "netif/ethernetif.h"
#include "wifi_manager/wifi_manager.h"
#include "lwip/tcpip.h"
#include "drv/drv_adc_measure.h"
#include "drv_adc_measure.h"
#include "utils/system_parameter.h"
#include "hal/hal_adc.h"
@@ -161,7 +161,7 @@ void application_entry(void *arg)
ART_ASSERT(1);
}
reg_wifi_msg_callbcak(wifi_manager_get_handle(), WIFI_MSG_ID_STA_DHCP_GOT_IP,wifi_event_sta_got_ip_cb);
reg_wifi_msg_callbcak(WIFI_MSG_ID_STA_DHCP_GOT_IP,wifi_event_sta_got_ip_cb);
wifi_mode_enum_t wifi_mode = WIFI_MODE_STATION;

View File

@@ -2,7 +2,7 @@
#include "cmsis_os.h"
#include "osal/osal.h"
#define APPLICATION_TASK_STK_SIZE 6*256
#define APPLICATION_TASK_STK_SIZE (8*1024)
extern void application_entry(void *arg);
osThreadDef(application_entry, osPriorityLow, 1, APPLICATION_TASK_STK_SIZE);//osPriorityNormal
@@ -17,7 +17,9 @@ __weak void application_entry(void *arg)
#include "wifi_manager/wifi_manager.h"
#include "utils/system_parameter.h"
#include "atcmd/at_task.h"
#include "ln_kv_port.h"
#include "ln_kv_api.h"
#include "flash_partition_table.h"
int main(void)
{
@@ -28,10 +30,13 @@ int main(void)
at_init();
system_parameter_init();
if (KV_ERR_NONE != ln_kv_port_init(KV_SPACE_OFFSET, (KV_SPACE_OFFSET + KV_SPACE_SIZE))) {
LOG(LOG_LVL_ERROR, "KV init filed!\r\n");
}
wifi_init();
lwip_tcpip_init();
wifi_manager_init(wifi_manager_get_handle());
wifi_manager_init();
osThreadCreate(osThread(application_entry), NULL); // Create TOS Tiny task
osKernelStart(); // Start TOS Tiny

View File

@@ -29,29 +29,6 @@ int fgetc(FILE *f)
return ch;
}
//int flash_write(uint32_t addr, const void *buf, size_t len){
// FLASH_Program(addr,len, (uint8_t *)buf);
//}
//int flash_read(uint32_t addr, void *buf, size_t len){
// FLASH_ReadByCache(addr, len, (uint8_t *)buf);
//}
//void nvds_kv_init(void)
//{
// kv_flash_drv_t flash_drv;
// kv_flash_prop_t flash_prop;
//
// flash_drv.write = flash_write;
// flash_drv.read = flash_read;
// flash_drv.erase = FLASH_Erase;
//
// flash_prop.sector_size_log2 = 8;
// flash_prop.pgm_type = KV_FLASH_PROGRAM_TYPE_BYTE;
// flash_prop.flash_start = SYSTEM_PARAMETER_OFFSET;
// flash_prop.flash_size = SIZE_4KB*2;
//}
void board_init(void)
{
SetSysClock();
@@ -64,8 +41,6 @@ void board_init(void)
log_init();//init log serial
cm_backtrace_init("wifi app", "HD_V2", "SW_V0.8");
// nvds_kv_init();
}

View File

@@ -8,7 +8,7 @@
#include "netif/ethernetif.h"
#include "wifi_manager/wifi_manager.h"
#include "lwip/tcpip.h"
#include "drv/drv_adc_measure.h"
#include "drv_adc_measure.h"
#include "utils/system_parameter.h"
#include "hal/hal_adc.h"
@@ -161,7 +161,7 @@ void application_entry(void *arg)
ART_ASSERT(1);
}
reg_wifi_msg_callbcak(wifi_manager_get_handle(), WIFI_MSG_ID_STA_DHCP_GOT_IP,wifi_event_sta_got_ip_cb);
reg_wifi_msg_callbcak(WIFI_MSG_ID_STA_DHCP_GOT_IP,wifi_event_sta_got_ip_cb);
wifi_mode_enum_t wifi_mode = WIFI_MODE_STATION;

View File

@@ -0,0 +1,415 @@
#include "proj_config.h"
#include "ln88xx.h"
#include "serial/serial.h"
#include "hal/hal_syscon.h"
#include "hal/hal_uart.h"
//#include "hal/hal_sleep.h"
#include "utils/debug/art_assert.h"
#define UART0_TX_BUF_SIZE CFG_UART0_TX_BUF_SIZE
#define UART0_RX_BUF_SIZE CFG_UART0_RX_BUF_SIZE
#define UART1_TX_BUF_SIZE CFG_UART1_TX_BUF_SIZE
#define UART1_RX_BUF_SIZE CFG_UART1_RX_BUF_SIZE
/* From the high-level serial driver */
extern Serial_t serial_handles[SER_PORT_NUM];
/* TX and RX buffers */
unsigned char uart0_txbuffer[UART0_TX_BUF_SIZE];
unsigned char uart0_rxbuffer[UART0_RX_BUF_SIZE];
unsigned char uart1_txbuffer[UART1_TX_BUF_SIZE];
unsigned char uart1_rxbuffer[UART1_RX_BUF_SIZE];
/* UART device*/
UART_DevTypeDef g_huart0,g_huart1;
/**
* Internal state structure
*/
struct ARTSerial
{
struct SerialHardware Hardware;
struct Serial *serial;
};
struct ARTSerial UARTDescs[SER_PORT_NUM];
static void uart0_SendDataIrqCallback(uint8_t *ch);
static void uart0_RecvDataIrqCallback(uint8_t *ch);
static void uart1_SendDataIrqCallback(uint8_t *ch);
static void uart1_RecvDataIrqCallback(uint8_t *ch);
/*
* ***************************** Port IO Config ******************************
*/
static void uart_io_pin_request(struct Serial *serial)
{
int en = 1;
ART_ASSERT(serial);
if(serial->port_id == SER_PORT_UART0){
#if defined (LN881x)
HAL_SYSCON_FuncIOSet(GPIO_AF_UART0_RX, GPIO_AF_IO_0, en);
HAL_SYSCON_FuncIOSet(GPIO_AF_UART0_TX, GPIO_AF_IO_1, en);
#elif defined (LN882x)
HAL_SYSCON_FuncIOSet(GPIO_AF_UART0_RX, GPIO_AF_IO_18, en); //LN882x: GPIO_A[8], FULL_MUX_18, PAD24 [rom_uart0 RX]
HAL_SYSCON_FuncIOSet(GPIO_AF_UART0_TX, GPIO_AF_IO_19, en); //LN882x: GPIO_A[9], FULL_MUX_19, PAD25 [rom_uart0 TX]
#else
#error Add your bord type!!!
#endif
}else if(serial->port_id == SER_PORT_UART1){
#if defined (LN881x)
// EVB V2 引脚更改了
HAL_SYSCON_FuncIOSet(GPIO_AF_UART1_RX, GPIO_AF_IO_2, en);
HAL_SYSCON_FuncIOSet(GPIO_AF_UART1_TX, GPIO_AF_IO_4, en);
#elif defined (LN882x)
//TODO:待最终demo板确认
//HAL_SYSCON_FuncIOSet(GPIO_AF_UART1_RX, GPIO_AF_IO_15, en);//LN882x FPGA: GPIO_1[5], FULL_MUX_15, PAD21
//HAL_SYSCON_FuncIOSet(GPIO_AF_UART1_TX, GPIO_AF_IO_16, en);//LN882x FPGA: GPIO_1[6], FULL_MUX_16, PAD22
#if 0//LN8826CT
HAL_SYSCON_FuncIOSet(GPIO_AF_UART1_RX, GPIO_AF_IO_8, en);//LN8826CT EVB: GPIOA8 GPIO_0[8], FULL_MUX_08, PAD08
HAL_SYSCON_FuncIOSet(GPIO_AF_UART1_TX, GPIO_AF_IO_9, en);//LN8826CT EVB: GPIOA9 GPIO_0[9], FULL_MUX_09, PAD09
#else //LN8820 or LN8825
HAL_SYSCON_FuncIOSet(GPIO_AF_UART1_RX, GPIO_AF_IO_16, en);//LN8820 (LN8825) &BLE EVB: GPIOB6, FULL_MUX_16, Pin31
HAL_SYSCON_FuncIOSet(GPIO_AF_UART1_TX, GPIO_AF_IO_17, en);//LN8820 (LN8825) &BLE EVB: GPIOB7, FULL_MUX_17, Pin32
#endif
#else
#error Add your bord type!!!
#endif
}
}
static void uart_io_pin_release(struct Serial *serial)
{
int en = 0;
ART_ASSERT(serial);
if(serial->port_id == SER_PORT_UART0){
#if defined (LN881x)
HAL_SYSCON_FuncIOSet(GPIO_AF_UART0_RX, GPIO_AF_IO_0, en);
HAL_SYSCON_FuncIOSet(GPIO_AF_UART0_TX, GPIO_AF_IO_1, en);
#elif defined (LN882x)
HAL_SYSCON_FuncIOSet(GPIO_AF_UART0_RX, GPIO_AF_IO_18, en);//LN882x: GPIO_1[8], FULL_MUX_18, PAD24 [rom_uart0 RX]
HAL_SYSCON_FuncIOSet(GPIO_AF_UART0_TX, GPIO_AF_IO_19, en);//LN882x: GPIO_1[9], FULL_MUX_19, PAD25 [rom_uart0 TX]
#else
#error Add your bord type!!!
#endif
}else if(serial->port_id == SER_PORT_UART1){
#if defined (LN881x)
// EVB V2 引脚更改了
HAL_SYSCON_FuncIOSet(GPIO_AF_UART1_RX, GPIO_AF_IO_2, en);
HAL_SYSCON_FuncIOSet(GPIO_AF_UART1_TX, GPIO_AF_IO_4, en);
#elif defined (LN882x)
//TODO:待最终demo板确认
HAL_SYSCON_FuncIOSet(GPIO_AF_UART1_RX, GPIO_AF_IO_15, en);//LN882x: GPIO_1[5], FULL_MUX_15, PAD21
HAL_SYSCON_FuncIOSet(GPIO_AF_UART1_TX, GPIO_AF_IO_16, en);//LN882x: GPIO_1[6], FULL_MUX_16, PAD22
#else
#error Add your bord type!!!
#endif
}
}
/*
* ***************************** Device Init ******************************
*/
static void hw_uart0_init(struct SerialHardware *_hw, struct Serial *serial, uint32_t baudrate)
{
struct ARTSerial *hw = NULL;
ART_ASSERT(_hw && serial);
hw = (struct ARTSerial *)_hw;
hw->serial = serial;
g_huart0.Instance = UART0;
g_huart0.Config.BaudRate = baudrate;//115200 921600 2000000
g_huart0.Config.DataLength = UART_DATALEN_8BIT;
g_huart0.Config.Parity = UART_PARITY_NONE;
g_huart0.Config.StopBits = UART_STOP_BIT_1;
g_huart0.Config.FlowControl = UART_FLOW_CONTROL_SOFTWARE;
//request pin for uart
uart_io_pin_request(hw->serial);
//init uart hardware
HAL_UART_Init(&g_huart0);
//config tx/rx trigger
HAL_UART_FIFOControl(&g_huart0, UART_TX_EMPTY_TRIGGER_FIFO_EMPTY, UART_RCVR_TRIGGER_FIFO_HAS_ONE_CHARACTER, UART_DMA_MODE0);
//enable RX interrupt if necessary
HAL_UART_INT_Switch_RecvDataAvailable(&g_huart0, 1);
//enable TX interrupt if necessary
// hal_uart_xfer_data_interrupt(_hw->hw_addr, 1);
//Enable Receiver Line Status Interrupt if necessary
HAL_UART_INT_Switch_RecvLineStatus(&g_huart0, 1);
//Enable Modem Status Interrupt if necessary
//hal_uart_modem_status_interrupt(_hw->hw_addr, 1);
//Enable Programmable THRE Interrupt if necessary
// hal_uart_thre_interrupt(_hw->hw_addr, 1);
HAL_UART_SetIsrRecvCharCallback(g_huart0.Instance, uart0_RecvDataIrqCallback);
HAL_UART_SetIsrSendCharCallback(g_huart0.Instance, uart0_SendDataIrqCallback);
//enable uart master switch
NVIC_EnableIRQ(UART0_IRQn);
/*
* Register with the sleep module to ensure that the serial port can be used during Light sleep
*/
// hal_sleep_register(MOD_UART0, NULL, NULL, NULL);
}
static void hw_uart1_init(struct SerialHardware *_hw, struct Serial *serial, uint32_t baudrate)
{
struct ARTSerial *hw = NULL;
ART_ASSERT(_hw && serial);
hw = (struct ARTSerial *)_hw;
hw->serial = serial;
g_huart1.Instance = UART1;
g_huart1.Config.BaudRate = baudrate;//115200, 921600
g_huart1.Config.DataLength = UART_DATALEN_8BIT;
g_huart1.Config.Parity = UART_PARITY_NONE;
g_huart1.Config.StopBits = UART_STOP_BIT_1;
g_huart1.Config.FlowControl = UART_FLOW_CONTROL_SOFTWARE;
//request pin for uart
uart_io_pin_request(hw->serial);
//init uart hardware
HAL_UART_Init(&g_huart1);
//config tx/rx trigger
HAL_UART_FIFOControl(&g_huart1, UART_TX_EMPTY_TRIGGER_FIFO_EMPTY, UART_RCVR_TRIGGER_FIFO_HAS_ONE_CHARACTER, UART_DMA_MODE0);
//enable RX interrupt if necessary
HAL_UART_INT_Switch_RecvDataAvailable(&g_huart1, 1);
HAL_UART_SetIsrRecvCharCallback(g_huart1.Instance, uart1_RecvDataIrqCallback);
HAL_UART_SetIsrSendCharCallback(g_huart1.Instance, uart1_SendDataIrqCallback);
//enable uart master switch
NVIC_EnableIRQ(UART1_IRQn);
/*
* Register with the sleep module to ensure that the serial port can be used during Light sleep
*/
// hal_sleep_register(MOD_UART1, NULL, NULL, NULL);
}
/*
* ***************************** Device Cleanup ******************************
*/
static void hw_uart_cleanup(struct SerialHardware *_hw)
{
struct ARTSerial *hw = NULL;
ART_ASSERT(_hw);
hw = (struct ARTSerial *)_hw;
HAL_UART_Deinit(hw->Hardware.hw_device);
uart_io_pin_release(hw->serial);
hw->serial = NULL;
}
/*
* ***************************** Device txStart ******************************
*/
//txStart polling mode.
static void hw_uart_txStartPolling(struct SerialHardware * _hw)
{
uint8_t ch;
struct ARTSerial *hw = NULL;
UART_DevTypeDef * pUartDev;
ART_ASSERT(_hw);
hw = (struct ARTSerial *)_hw;
while(!fifo_isempty(&hw->serial->txfifo))
{
ch = fifo_pop(&hw->serial->txfifo);
pUartDev = (UART_DevTypeDef *)hw->Hardware.hw_device;
HAL_UART_WriteOneChar(pUartDev->Instance, &ch);
}
}
//txStart ISR mode.
static void hw_uart_txStartIsr(struct SerialHardware * _hw)
{
struct ARTSerial *hw = NULL;
ART_ASSERT(_hw);
hw = (struct ARTSerial *)_hw;
if (hw->Hardware.isSending){
return;
}
if(!fifo_isempty(&hw->serial->txfifo))
{
hw->Hardware.isSending = true;
/* Enable TX empty interrupts. */
HAL_UART_INT_Switch_TransmitHoldingRegEmpty(hw->Hardware.hw_device, 1);
}
}
/*
* ***************************** Device ixSending ******************************
*/
static bool hw_uart_txIsSending(struct SerialHardware * _hw)
{
struct ARTSerial *hw = NULL;
ART_ASSERT(_hw);
hw = (struct ARTSerial *)_hw;
return hw->Hardware.isSending;
}
/*
* ***************************** Device setBaudrate ******************************
*/
static bool hw_uart_setBaudrate(struct SerialHardware * _hw, uint32_t baudrate)
{
struct ARTSerial *hw = NULL;
UART_DevTypeDef * pUartDev;
ART_ASSERT(_hw);
hw = (struct ARTSerial *)_hw;
pUartDev = (UART_DevTypeDef *)hw->Hardware.hw_device;
if(HAL_OK == HAL_UART_BaudRateConfig(pUartDev, baudrate)){
return true;
} else {
return false;
}
}
/*
* ***************************** Register ISR Callback *****************************
*/
//send data callback in ISR mode.
static void uart0_SendDataIrqCallback(uint8_t *ch)
{
struct ARTSerial *hw = (struct ARTSerial *)&UARTDescs[SER_PORT_UART0];
uint8_t tx_char = 0;
if (fifo_isempty(&hw->serial->txfifo))
{
/* Disable TX empty interrupts if there're no more characters to transmit. */
HAL_UART_INT_Switch_TransmitHoldingRegEmpty(&g_huart0, 0);
hw->Hardware.isSending = false;
}
else
{
tx_char = fifo_pop(&hw->serial->txfifo);
HAL_UART_WriteOneChar(g_huart0.Instance, &tx_char);
}
}
//recieve data callback in ISR mode.
static void uart0_RecvDataIrqCallback(uint8_t *ch)
{
struct ARTSerial *hw = (struct ARTSerial *)&UARTDescs[SER_PORT_UART0];
while (fifo_isfull_locked(&hw->serial->rxfifo)){
serial_purgeRx(hw->serial);
}
fifo_push(&hw->serial->rxfifo, (unsigned char)*ch);
hw->serial->callback();
}
//send data callback in ISR mode.
static void uart1_SendDataIrqCallback(uint8_t *ch)
{
struct ARTSerial *hw = (struct ARTSerial *)&UARTDescs[SER_PORT_UART1];
uint8_t tx_char = 0;
if (fifo_isempty(&hw->serial->txfifo))
{
/* Disable TX empty interrupts if there're no more characters to transmit. */
HAL_UART_INT_Switch_TransmitHoldingRegEmpty(&g_huart1, 0);
hw->Hardware.isSending = false;
}
else
{
*ch = fifo_pop(&hw->serial->txfifo);
HAL_UART_WriteOneChar(g_huart1.Instance, &tx_char);
}
}
//recieve data callback in ISR mode.
static void uart1_RecvDataIrqCallback(uint8_t *ch)
{
struct ARTSerial *hw = (struct ARTSerial *)&UARTDescs[SER_PORT_UART1];
if (fifo_isfull_locked(&hw->serial->rxfifo)){
serial_purgeRx(hw->serial);
}
fifo_push(&hw->serial->rxfifo, (unsigned char)*ch);
if(*ch == '\n'){
hw->serial->callback();
}
}
/*
* High-level interface data structures.
*/
static const struct SerialHardwareVT uart0_vtable =
{
.init = hw_uart0_init,
.cleanup = hw_uart_cleanup,
.txStart = hw_uart_txStartPolling,//hw_uart_txStartPolling,hw_uart_txStartIsr
.txSending = hw_uart_txIsSending,
.setBaudrate = hw_uart_setBaudrate,
};
static const struct SerialHardwareVT uart1_vtable =
{
.init = hw_uart1_init,
.cleanup = hw_uart_cleanup,
.txStart = hw_uart_txStartPolling,//hw_uart_txStartPolling,hw_uart_txStartIsr
.txSending = hw_uart_txIsSending,
.setBaudrate = hw_uart_setBaudrate,
};
struct ARTSerial UARTDescs[SER_PORT_NUM] =
{
{
.Hardware =
{
.table = &uart0_vtable,
.txbuffer = uart0_txbuffer,
.rxbuffer = uart0_rxbuffer,
.txbuffer_size = sizeof(uart0_txbuffer),
.rxbuffer_size = sizeof(uart0_rxbuffer),
.hw_device = (void *)&g_huart0,
.isSending = false,
},
.serial = NULL,
},
{
.Hardware =
{
.table = &uart1_vtable,
.txbuffer = uart1_txbuffer,
.rxbuffer = uart1_rxbuffer,
.txbuffer_size = sizeof(uart1_txbuffer),
.rxbuffer_size = sizeof(uart1_rxbuffer),
.hw_device = (void *)&g_huart1,
.isSending = false,
},
.serial = NULL,
},
};
struct SerialHardware *serial_hw_getdesc(SerialPortID port_id)
{
ART_ASSERT(port_id < SER_PORT_NUM);
return (struct SerialHardware *)&UARTDescs[port_id].Hardware;
}

File diff suppressed because it is too large Load Diff

View File

@@ -10,8 +10,7 @@
<TargetName>TencentOS_tiny</TargetName>
<ToolsetNumber>0x4</ToolsetNumber>
<ToolsetName>ARM-ADS</ToolsetName>
<pCCUsed>5060750::V5.06 update 6 (build 750)::ARMCC</pCCUsed>
<uAC6>0</uAC6>
<pCCUsed>5060061::V5.06 update 1 (build 61)::ARMCC</pCCUsed>
<TargetOption>
<TargetCommonOption>
<Device>ARMCM4_FP</Device>
@@ -70,9 +69,9 @@
<nStopU2X>0</nStopU2X>
</BeforeCompile>
<BeforeMake>
<RunUserProg1>0</RunUserProg1>
<RunUserProg1>1</RunUserProg1>
<RunUserProg2>0</RunUserProg2>
<UserProg1Name></UserProg1Name>
<UserProg1Name>python ..\..\..\..\platform\vendor_bsp\LN\ln882x\tools\user_cmd\before_build.py flash_partition_cfg.json flash_partition_table.h</UserProg1Name>
<UserProg2Name></UserProg2Name>
<UserProg1Dos16Mode>0</UserProg1Dos16Mode>
<UserProg2Dos16Mode>0</UserProg2Dos16Mode>
@@ -81,9 +80,9 @@
</BeforeMake>
<AfterMake>
<RunUserProg1>1</RunUserProg1>
<RunUserProg2>0</RunUserProg2>
<UserProg1Name>.\after_build_ln882x.bat</UserProg1Name>
<UserProg2Name></UserProg2Name>
<RunUserProg2>1</RunUserProg2>
<UserProg1Name>python ..\..\..\..\platform\vendor_bsp\LN\ln882x\tools\user_cmd\after_build_soc.py @L</UserProg1Name>
<UserProg2Name>..\..\..\..\platform\vendor_bsp\LN\ln882x\tools\bin\mkimage.exe cmd_app ..\..\..\..\platform\vendor_bsp\LN\ln882x\lib\boot_ln882x.bin @L.bin @L.asm flashimage.bin flash_partition_cfg.json ver=1.1</UserProg2Name>
<UserProg1Dos16Mode>0</UserProg1Dos16Mode>
<UserProg2Dos16Mode>0</UserProg2Dos16Mode>
<nStopA1X>0</nStopA1X>
@@ -184,7 +183,6 @@
<hadXRAM>0</hadXRAM>
<uocXRam>0</uocXRam>
<RvdsVP>2</RvdsVP>
<RvdsMve>0</RvdsMve>
<hadIRAM2>0</hadIRAM2>
<hadIROM2>0</hadIROM2>
<StupSel>8</StupSel>
@@ -325,20 +323,16 @@
<uThumb>0</uThumb>
<uSurpInc>0</uSurpInc>
<uC99>1</uC99>
<uGnu>0</uGnu>
<useXO>0</useXO>
<v6Lang>1</v6Lang>
<v6LangP>1</v6LangP>
<vShortEn>1</vShortEn>
<vShortWch>1</vShortWch>
<v6Lto>0</v6Lto>
<v6WtE>0</v6WtE>
<v6Rtti>0</v6Rtti>
<VariousControls>
<MiscControls></MiscControls>
<Define>LN882x,ARM_MATH_CM4</Define>
<Undefine></Undefine>
<IncludePath>..\..\BSP\Inc;..\..\TOS-CONFIG;..\..\..\..\kernel\pm\include;..\..\..\..\kernel\core\include;..\..\..\..\arch\arm\arm-v7m\common\include;..\..\..\..\arch\arm\arm-v7m\cortex-m4\armcc;..\..\..\..\osal\cmsis_os;..\..\..\..\examples\helloworld;..\hello_world;..\..\..\..\platform\vendor_bsp\LN\ln882x\include\driver_ln882x;..\..\..\..\platform\vendor_bsp\LN\ln882x\src\driver_ln882x\ll\include;..\..\..\..\components\fs\kv\include;..\..\..\..\platform\vendor_bsp\LN\ln882x\include;..\..\..\..\platform\vendor_bsp\LN\ln882x\include\cpu\ARM_CM4F\ln88xx;..\..\..\..\platform\vendor_bsp\LN\ln882x\include\kernel;..\..\..\..\platform\vendor_bsp\LN\ln882x\include\cpu\ARM_CM4F\CMSIS_5.3.0;..\..\..\..\platform\vendor_bsp\LN\ln882x\include\wifi_manager;..\..\..\..\platform\vendor_bsp\LN\ln882x\include\net;..\..\..\..\platform\vendor_bsp\LN\ln882x\src\net\lwip-2.0.3\src\include;..\..\..\..\platform\vendor_bsp\LN\ln882x\src\net\lwip-2.0.3\src\port;..\..\..\..\platform\vendor_bsp\LN\ln882x\src\net\lwip-2.0.3\src\port\arch;..\..\..\..\components\connectivity\mqttclient\common;..\..\..\..\components\connectivity\mqttclient\mqtt;..\..\..\..\components\connectivity\mqttclient\mqttclient;..\..\..\..\components\connectivity\mqttclient\network;..\..\..\..\components\connectivity\mqttclient\platform\TencentOS-tiny</IncludePath>
<IncludePath>..\..\BSP\Inc;..\..\TOS-CONFIG;..\..\..\..\kernel\pm\include;..\..\..\..\kernel\core\include;..\..\..\..\arch\arm\arm-v7m\common\include;..\..\..\..\arch\arm\arm-v7m\cortex-m4\armcc;..\..\..\..\osal\cmsis_os;..\..\..\..\examples\helloworld;..\hello_world;..\..\..\..\platform\vendor_bsp\LN\ln882x\include\driver_ln882x;..\..\..\..\platform\vendor_bsp\LN\ln882x\src\driver_ln882x\ll\include;..\..\..\..\components\fs\kv\include;..\..\..\..\platform\vendor_bsp\LN\ln882x\include;..\..\..\..\platform\vendor_bsp\LN\ln882x\include\cpu\ARM_CM4F\ln88xx;..\..\..\..\platform\vendor_bsp\LN\ln882x\include\kernel;..\..\..\..\platform\vendor_bsp\LN\ln882x\include\cpu\ARM_CM4F\CMSIS_5.3.0;..\..\..\..\platform\vendor_bsp\LN\ln882x\include\wifi_manager;..\..\..\..\platform\vendor_bsp\LN\ln882x\include\net;..\..\..\..\platform\vendor_bsp\LN\ln882x\src\net\lwip-2.0.3\src\include;..\..\..\..\platform\vendor_bsp\LN\ln882x\src\net\lwip-2.0.3\src\port;..\..\..\..\platform\vendor_bsp\LN\ln882x\src\net\lwip-2.0.3\src\port\arch;..\..\..\..\components\connectivity\mqttclient\common;..\..\..\..\components\connectivity\mqttclient\mqtt;..\..\..\..\components\connectivity\mqttclient\mqttclient;..\..\..\..\components\connectivity\mqttclient\network;..\..\..\..\components\connectivity\mqttclient\platform\TencentOS-tiny;..\..\..\..\platform\vendor_bsp\LN\ln882x\src\wifi\wifi_port;..\..\..\..\platform\vendor_bsp\LN\ln882x\src\fs\kv\kv_port;..\..\..\..\platform\vendor_bsp\LN\ln882x\src\fs\kv\kv;..\..\..\..\platform\vendor_bsp\LN\ln882x\src\fs\nvds;..\..\..\..\platform\vendor_bsp\LN\ln882x\src\fs\partition_mgr;..\mqtt_client</IncludePath>
</VariousControls>
</Cads>
<Aads>
@@ -351,7 +345,6 @@
<NoWarn>0</NoWarn>
<uSurpInc>0</uSurpInc>
<useXO>0</useXO>
<uClangAs>0</uClangAs>
<VariousControls>
<MiscControls></MiscControls>
<Define></Define>
@@ -369,10 +362,10 @@
<TextAddressRange>0x08000000</TextAddressRange>
<DataAddressRange>0x20000000</DataAddressRange>
<pXoBase></pXoBase>
<ScatterFile>.\firmware_XIP_ln882x.sct</ScatterFile>
<ScatterFile>.\ln882x.sct</ScatterFile>
<IncludeLibs></IncludeLibs>
<IncludeLibsPath></IncludeLibsPath>
<Misc>--no_autoat --keep=main.o(no_init_data)</Misc>
<Misc>--no_autoat --keep=*.o(no_init_data)</Misc>
<LinkerInputFile></LinkerInputFile>
<DisabledWarnings></DisabledWarnings>
</LDads>
@@ -419,16 +412,6 @@
</File>
</Files>
</Group>
<Group>
<GroupName>Drivers/Drv</GroupName>
<Files>
<File>
<FileName>drv_adc_measure.c</FileName>
<FileType>1</FileType>
<FilePath>..\..\..\..\platform\vendor_bsp\LN\ln882x\src\driver_ln882x\drv\drv_adc_measure.c</FilePath>
</File>
</Files>
</Group>
<Group>
<GroupName>Drivers/HAL</GroupName>
<Files>
@@ -514,15 +497,11 @@
<uThumb>2</uThumb>
<uSurpInc>2</uSurpInc>
<uC99>2</uC99>
<uGnu>2</uGnu>
<useXO>2</useXO>
<v6Lang>0</v6Lang>
<v6LangP>0</v6LangP>
<vShortEn>2</vShortEn>
<vShortWch>2</vShortWch>
<v6Lto>2</v6Lto>
<v6WtE>2</v6WtE>
<v6Rtti>2</v6Rtti>
<VariousControls>
<MiscControls></MiscControls>
<Define></Define>
@@ -728,6 +707,16 @@
<FileType>1</FileType>
<FilePath>..\..\BSP\Src\mcu_init.c</FilePath>
</File>
<File>
<FileName>serial_hw.c</FileName>
<FileType>1</FileType>
<FilePath>..\..\BSP\Src\serial_hw.c</FilePath>
</File>
<File>
<FileName>drv_adc_measure.c</FileName>
<FileType>1</FileType>
<FilePath>..\..\BSP\Src\drv_adc_measure.c</FilePath>
</File>
</Files>
</Group>
<Group>
@@ -738,11 +727,6 @@
<FileType>1</FileType>
<FilePath>..\..\..\..\platform\vendor_bsp\LN\ln882x\src\serial\serial.c</FilePath>
</File>
<File>
<FileName>serial_hw.c</FileName>
<FileType>1</FileType>
<FilePath>..\..\..\..\platform\vendor_bsp\LN\ln882x\src\serial\serial_hw.c</FilePath>
</File>
</Files>
</Group>
<Group>
@@ -924,9 +908,9 @@
<FilePath>..\..\..\..\platform\vendor_bsp\LN\ln882x\lib\wifi_mac.lib</FilePath>
</File>
<File>
<FileName>wifi_driver.lib</FileName>
<FileName>soc_driver.lib</FileName>
<FileType>4</FileType>
<FilePath>..\..\..\..\platform\vendor_bsp\LN\ln882x\lib\wifi_driver.lib</FilePath>
<FilePath>..\..\..\..\platform\vendor_bsp\LN\ln882x\lib\soc_driver.lib</FilePath>
</File>
</Files>
</Group>
@@ -938,6 +922,11 @@
<FileType>1</FileType>
<FilePath>..\..\..\..\platform\vendor_bsp\LN\ln882x\src\wifi\wifi_manager\wifi_manager.c</FilePath>
</File>
<File>
<FileName>wifi_port.c</FileName>
<FileType>1</FileType>
<FilePath>..\..\..\..\platform\vendor_bsp\LN\ln882x\src\wifi\wifi_port\wifi_port.c</FilePath>
</File>
</Files>
</Group>
<Group>
@@ -1005,15 +994,11 @@
<uThumb>2</uThumb>
<uSurpInc>2</uSurpInc>
<uC99>2</uC99>
<uGnu>2</uGnu>
<useXO>2</useXO>
<v6Lang>0</v6Lang>
<v6LangP>0</v6LangP>
<vShortEn>2</vShortEn>
<vShortWch>2</vShortWch>
<v6Lto>2</v6Lto>
<v6WtE>2</v6WtE>
<v6Rtti>2</v6Rtti>
<VariousControls>
<MiscControls></MiscControls>
<Define></Define>
@@ -1232,22 +1217,27 @@
</Files>
</Group>
<Group>
<GroupName>tos_components</GroupName>
<GroupName>fs</GroupName>
<Files>
<File>
<FileName>tos_kv.c</FileName>
<FileName>ln_kv.c</FileName>
<FileType>1</FileType>
<FilePath>..\..\..\..\components\fs\kv\tos_kv.c</FilePath>
<FilePath>..\..\..\..\platform\vendor_bsp\LN\ln882x\src\fs\kv\kv\ln_kv.c</FilePath>
</File>
<File>
<FileName>ln_kv_port.c</FileName>
<FileType>1</FileType>
<FilePath>..\..\..\..\platform\vendor_bsp\LN\ln882x\src\fs\kv\kv_port\ln_kv_port.c</FilePath>
</File>
<File>
<FileName>flash_partition_mgr.c</FileName>
<FileType>1</FileType>
<FilePath>..\..\..\..\platform\vendor_bsp\LN\ln882x\src\fs\partition_mgr\flash_partition_mgr.c</FilePath>
</File>
</Files>
</Group>
<Group>
<GroupName>nvds</GroupName>
<Files>
<File>
<FileName>nvds.c</FileName>
<FileType>1</FileType>
<FilePath>..\..\..\..\platform\vendor_bsp\LN\ln882x\src\nvds\nvds.c</FilePath>
<FilePath>..\..\..\..\platform\vendor_bsp\LN\ln882x\src\fs\nvds\nvds.c</FilePath>
</File>
</Files>
</Group>

View File

@@ -1,8 +1,4 @@
python ..\..\..\..\platform\vendor_bsp\LN\ln882x\tools\user_cmd\after_build_soc.py firmware_XIP
..\..\..\..\platform\vendor_bsp\LN\ln882x\tools\bin\mkimage.exe ln882x flashimage ..\..\..\..\platform\vendor_bsp\LN\ln882x\lib\boot_ram_ln882x.bin firmware_XIP.bin flashimage.bin release=1 crp_enable=0 app_version=10 hw_version=0
..\..\..\..\platform\vendor_bsp\LN\ln882x\tools\bin\fpu_patch.exe .\firmware_XIP.asm .\flashimage.bin
python ..\..\..\..\platform\vendor_bsp\LN\ln882x\tools\user_cmd\after_build_soc.py @L
..\..\..\..\platform\vendor_bsp\LN\ln882x\tools\bin\mkimage.exe cmd_app ..\..\..\..\platform\vendor_bsp\LN\ln882x\lib\boot_ln882x.bin @L.bin @L.asm flashimage.bin flash_partition_cfg.json ver=1.1

View File

@@ -0,0 +1,22 @@
{
"Warning1":"警告,系统定义用户不可修改!!!",
"vendor_define":
[
{"partition_type": "BOOT", "start_addr": "0x00000000", "size_KB": 36 },
{"partition_type": "PART_TAB", "start_addr": "0x00009000", "size_KB": 4 }
],
"Warning2":"以下数据,用户根据SOC flash容量以及具体需求修改仅可以修改start_addr值和size值且必须4KB对齐!!!",
"user_define":
[
{"partition_type": "KV", "start_addr": "0x0000A000", "size_KB": 8 },
{"partition_type": "SIMU_EEPROM", "start_addr": "0x0000C000", "size_KB": 8 },
{"partition_type": "APP", "start_addr": "0x0000E000", "size_KB": 800 },
{"partition_type": "OTA", "start_addr": "0x000D6000", "size_KB": 800 },
{"partition_type": "NVDS", "start_addr": "0x0019E000", "size_KB": 12 },
{"partition_type": "USER", "start_addr": "0x001A1000", "size_KB": 12 }
]
}

View File

@@ -1,32 +1,56 @@
#ifndef __FLASH_PARTITION_TABLE_H__
#define __FLASH_PARTITION_TABLE_H__
#ifndef __FLASH_PARTITION_TABLE__
#define __FLASH_PARTITION_TABLE__
//#define RETENTION_MEM_BASE 0x20028000
//#define RETENTION_MEM_SIZE 0x2000
#ifndef FLASH_BASE
#define FLASH_BASE (0x10000000)
//flash partition map,it's generated by the script based on the json file <flash_partition_table.json>
#define BOOT_SPACE_OFFSET (0x00000000)
#define BOOT_SPACE_SIZE (1024*36)
#define PART_TAB_SPACE_OFFSET (0x00009000)
#define PART_TAB_SPACE_SIZE (1024*4)
#if (PART_TAB_SPACE_OFFSET < (BOOT_SPACE_OFFSET + BOOT_SPACE_SIZE))
#error "flash partition overlap,please check <flash_partition_table.json>!!!"
#endif
#ifndef FLASH_SIZE
#define FLASH_SIZE (0x00200000)
#define KV_SPACE_OFFSET (0x0000A000)
#define KV_SPACE_SIZE (1024*8)
#if (KV_SPACE_OFFSET < (PART_TAB_SPACE_OFFSET + PART_TAB_SPACE_SIZE))
#error "flash partition overlap,please check <flash_partition_table.json>!!!"
#endif
#ifndef PRIMARY_PARTITION_OFFSET
#define PRIMARY_PARTITION_OFFSET (0x0000F000)
#define SIMU_EEPROM_SPACE_OFFSET (0x0000C000)
#define SIMU_EEPROM_SPACE_SIZE (1024*8)
#if (SIMU_EEPROM_SPACE_OFFSET < (KV_SPACE_OFFSET + KV_SPACE_SIZE))
#error "flash partition overlap,please check <flash_partition_table.json>!!!"
#endif
#define PRIMARY_PATTITION_START 0x0000F000
#define PRIMARY_PATTITION_SIZE 0xE1000
//#define USERAPP_SRAM_BASE 0x1FFF0000
#define BACKUP_PATTITION_START 0x000F0000
#define BACKUP_PATTITION_SIZE 0xE1000
#define USERDATA_PATTITION_START 0x001D1000
#define USERDATA_PATTITION_SIZE 0x23000
//memory offset check
#if ((PRIMARY_PATTITION_START < PRIMARY_PARTITION_OFFSET) || (BACKUP_PATTITION_START < PRIMARY_PATTITION_START) || (USERDATA_PATTITION_START < BACKUP_PATTITION_START) || (PRIMARY_PATTITION_START + PRIMARY_PATTITION_SIZE > BACKUP_PATTITION_START) || (BACKUP_PATTITION_START + BACKUP_PATTITION_SIZE > USERDATA_PATTITION_START) || (USERDATA_PATTITION_START + USERDATA_PATTITION_SIZE > FLASH_SIZE))
#error "flash partition define error!"
#define APP_SPACE_OFFSET (0x0000E000)
#define APP_SPACE_SIZE (1024*800)
#if (APP_SPACE_OFFSET < (SIMU_EEPROM_SPACE_OFFSET + SIMU_EEPROM_SPACE_SIZE))
#error "flash partition overlap,please check <flash_partition_table.json>!!!"
#endif
#endif /* __FLASH_PARTITION_TABLE_H__ */
#define OTA_SPACE_OFFSET (0x000D6000)
#define OTA_SPACE_SIZE (1024*800)
#if (OTA_SPACE_OFFSET < (APP_SPACE_OFFSET + APP_SPACE_SIZE))
#error "flash partition overlap,please check <flash_partition_table.json>!!!"
#endif
#define NVDS_SPACE_OFFSET (0x0019E000)
#define NVDS_SPACE_SIZE (1024*12)
#if (NVDS_SPACE_OFFSET < (OTA_SPACE_OFFSET + OTA_SPACE_SIZE))
#error "flash partition overlap,please check <flash_partition_table.json>!!!"
#endif
#define USER_SPACE_OFFSET (0x001A1000)
#define USER_SPACE_SIZE (1024*12)
#if (USER_SPACE_OFFSET < (NVDS_SPACE_OFFSET + NVDS_SPACE_SIZE))
#error "flash partition overlap,please check <flash_partition_table.json>!!!"
#endif
#define IMAGE_HEADER_SIZE (0x100)
#endif /* __FLASH_PARTITION_TABLE__ */

View File

@@ -1,9 +1,9 @@
#! armcc -E
#include ".\flash_partition_table.h"
#include "flash_partition_table.h"
#include ".\..\..\..\..\platform\vendor_bsp\LN\ln882x\include\cpu\ARM_CM4F\ln88xx\mem_map_ln882x.h"
LR_FLASH FLASH_BASE+PRIMARY_PARTITION_OFFSET PRIMARY_PATTITION_SIZE
LR_FLASH CACHE_FLASH_BASE+APP_SPACE_OFFSET+IMAGE_HEADER_SIZE APP_SPACE_SIZE
{; load region size_region
ISR_VECTOR RAM_BASE ALIGN 0x100
@@ -11,7 +11,7 @@ LR_FLASH FLASH_BASE+PRIMARY_PARTITION_OFFSET PRIMARY_PATTITION_SIZE
startup_*.o (RESET, +First)
}
ER_FLASH FLASH_BASE+PRIMARY_PARTITION_OFFSET + ImageLength(ISR_VECTOR) PRIMARY_PATTITION_SIZE
ER_FLASH CACHE_FLASH_BASE+APP_SPACE_OFFSET+IMAGE_HEADER_SIZE + ImageLength(ISR_VECTOR) APP_SPACE_SIZE
{; load address = execution address
*(InRoot$$Sections)
.ANY (+RO)
@@ -24,15 +24,15 @@ LR_FLASH FLASH_BASE+PRIMARY_PARTITION_OFFSET PRIMARY_PATTITION_SIZE
ll_cache.o(+RO)
ll_dma.o(+RO)
ll_syscon.o(+RO)
ll_sleep.o(+RO)
ll_rtc.o(+RO)
;ll_sleep.o(+RO)
;ll_rtc.o(+RO)
cache.o(+RO)
qspi.o(+RO)
flash.o(+RO)
hal_dma.o(+RO)
hal_syscon.o(+RO)
hal_sleep.o(+RO)
hal_rtc.o(+RO)
;hal_sleep.o(+RO)
;hal_rtc.o(+RO)
;port.o(XIR)
;optional item
@@ -49,16 +49,32 @@ LR_FLASH FLASH_BASE+PRIMARY_PARTITION_OFFSET PRIMARY_PATTITION_SIZE
startup_ln*(+RW +ZI)
}
ER_DATA +0
ER_DATA_IN_B0 +0 RAM_BLOCK0_SIZE-ImageLength(ISR_VECTOR)-ImageLength(ER_CODE)-ImageLength(ER_STACK)
{
*(.ARM.__at_0x1FFFFFFC)
.ANY (+RW +ZI)
memp.o(+RW +ZI)
imem.o(+RW +ZI)
imem_if.o(+RW +ZI)
;cglobals_sta.o(+RW +ZI)
;event_manager.o(+RW +ZI)
iconfig.o(+RW +ZI)
common.o(+RW +ZI)
}
HEAP_SPACE0 +0 EMPTY RAM_BLOCK1_BASE-ImageLimit(ER_DATA_IN_B0)
{; Heap region
}
ER_DATA_IN_B1 RAM_BLOCK1_BASE RAM_BLOCK1_SIZE
{
*(wlan_mem_pkt)
*(wlan_mem_dscr)
.ANY (+RW +ZI)
}
;IQ Data area cannot be used by ER_DATA region
;ScatterAssert(ImageLimit(ER_DATA) < (0x20020300))
HEAP_SPACE +0 EMPTY RETENTION_MEM_BASE-ImageLimit(ER_DATA)
HEAP_SPACE1 +0 EMPTY RETENTION_MEM_BASE-ImageLimit(ER_DATA_IN_B1)
{; Heap region
}

File diff suppressed because it is too large Load Diff

View File

@@ -70,9 +70,9 @@
<nStopU2X>0</nStopU2X>
</BeforeCompile>
<BeforeMake>
<RunUserProg1>0</RunUserProg1>
<RunUserProg1>1</RunUserProg1>
<RunUserProg2>0</RunUserProg2>
<UserProg1Name></UserProg1Name>
<UserProg1Name>python ..\..\..\..\platform\vendor_bsp\LN\ln882x\tools\user_cmd\before_build.py flash_partition_cfg.json flash_partition_table.h</UserProg1Name>
<UserProg2Name></UserProg2Name>
<UserProg1Dos16Mode>0</UserProg1Dos16Mode>
<UserProg2Dos16Mode>0</UserProg2Dos16Mode>
@@ -81,9 +81,9 @@
</BeforeMake>
<AfterMake>
<RunUserProg1>1</RunUserProg1>
<RunUserProg2>0</RunUserProg2>
<UserProg1Name>.\after_build_ln882x.bat</UserProg1Name>
<UserProg2Name></UserProg2Name>
<RunUserProg2>1</RunUserProg2>
<UserProg1Name>python ..\..\..\..\platform\vendor_bsp\LN\ln882x\tools\user_cmd\after_build_soc.py @L</UserProg1Name>
<UserProg2Name>..\..\..\..\platform\vendor_bsp\LN\ln882x\tools\bin\mkimage.exe cmd_app ..\..\..\..\platform\vendor_bsp\LN\ln882x\lib\boot_ln882x.bin @L.bin @L.asm flashimage.bin flash_partition_cfg.json ver=1.1</UserProg2Name>
<UserProg1Dos16Mode>0</UserProg1Dos16Mode>
<UserProg2Dos16Mode>0</UserProg2Dos16Mode>
<nStopA1X>0</nStopA1X>
@@ -338,7 +338,7 @@
<MiscControls></MiscControls>
<Define>LN882x,ARM_MATH_CM4,MBEDTLS_CONFIG_FILE=&lt;qcloud/tls_psk_config.h&gt;</Define>
<Undefine></Undefine>
<IncludePath>..\..\BSP\Inc;..\..\TOS-CONFIG;..\..\..\..\kernel\pm\include;..\..\..\..\kernel\core\include;..\..\..\..\arch\arm\arm-v7m\common\include;..\..\..\..\arch\arm\arm-v7m\cortex-m4\armcc;..\..\..\..\osal\cmsis_os;..\..\..\..\examples\helloworld;..\..\..\..\platform\vendor_bsp\LN\ln882x\include\driver_ln882x;..\..\..\..\platform\vendor_bsp\LN\ln882x\src\driver_ln882x\ll\include;..\..\..\..\components\fs\kv\include;..\..\..\..\platform\vendor_bsp\LN\ln882x\include;..\..\..\..\platform\vendor_bsp\LN\ln882x\include\cpu\ARM_CM4F\ln88xx;..\..\..\..\platform\vendor_bsp\LN\ln882x\include\kernel;..\..\..\..\platform\vendor_bsp\LN\ln882x\include\cpu\ARM_CM4F\CMSIS_5.3.0;..\..\..\..\platform\vendor_bsp\LN\ln882x\include\wifi_manager;..\..\..\..\platform\vendor_bsp\LN\ln882x\include\net;..\..\..\..\platform\vendor_bsp\LN\ln882x\src\net\lwip-2.0.3\src\include;..\..\..\..\platform\vendor_bsp\LN\ln882x\src\net\lwip-2.0.3\src\port;..\..\..\..\platform\vendor_bsp\LN\ln882x\src\net\lwip-2.0.3\src\port\arch;..\..\..\..\components\connectivity\qcloud-iot-explorer-sdk\3rdparty\include;..\..\..\..\components\connectivity\qcloud-iot-explorer-sdk\3rdparty\include\exports;..\..\..\..\components\connectivity\qcloud-iot-explorer-sdk\3rdparty\sdk_src\internal_inc;..\..\..\..\components\security\mbedtls\3rdparty\include;..\..\..\..\components\security\mbedtls\wrapper\include</IncludePath>
<IncludePath>..\..\BSP\Inc;..\..\TOS-CONFIG;..\..\..\..\kernel\pm\include;..\..\..\..\kernel\core\include;..\..\..\..\arch\arm\arm-v7m\common\include;..\..\..\..\arch\arm\arm-v7m\cortex-m4\armcc;..\..\..\..\osal\cmsis_os;..\..\..\..\examples\helloworld;..\..\..\..\platform\vendor_bsp\LN\ln882x\include\driver_ln882x;..\..\..\..\platform\vendor_bsp\LN\ln882x\src\driver_ln882x\ll\include;..\..\..\..\components\fs\kv\include;..\..\..\..\platform\vendor_bsp\LN\ln882x\include;..\..\..\..\platform\vendor_bsp\LN\ln882x\include\cpu\ARM_CM4F\ln88xx;..\..\..\..\platform\vendor_bsp\LN\ln882x\include\kernel;..\..\..\..\platform\vendor_bsp\LN\ln882x\include\cpu\ARM_CM4F\CMSIS_5.3.0;..\..\..\..\platform\vendor_bsp\LN\ln882x\include\wifi_manager;..\..\..\..\platform\vendor_bsp\LN\ln882x\include\net;..\..\..\..\platform\vendor_bsp\LN\ln882x\src\net\lwip-2.0.3\src\include;..\..\..\..\platform\vendor_bsp\LN\ln882x\src\net\lwip-2.0.3\src\port;..\..\..\..\platform\vendor_bsp\LN\ln882x\src\net\lwip-2.0.3\src\port\arch;..\..\..\..\components\connectivity\qcloud-iot-explorer-sdk\3rdparty\include;..\..\..\..\components\connectivity\qcloud-iot-explorer-sdk\3rdparty\include\exports;..\..\..\..\components\connectivity\qcloud-iot-explorer-sdk\3rdparty\sdk_src\internal_inc;..\..\..\..\components\security\mbedtls\3rdparty\include;..\..\..\..\components\security\mbedtls\wrapper\include;..\qcloud_iot_explorer;..\..\..\..\platform\vendor_bsp\LN\ln882x\src\wifi\wifi_port;..\..\..\..\platform\vendor_bsp\LN\ln882x\src\fs\kv\kv_port;..\..\..\..\platform\vendor_bsp\LN\ln882x\src\fs\kv\kv;..\..\..\..\platform\vendor_bsp\LN\ln882x\src\fs\nvds;..\..\..\..\platform\vendor_bsp\LN\ln882x\src\fs\partition_mgr</IncludePath>
</VariousControls>
</Cads>
<Aads>
@@ -369,10 +369,10 @@
<TextAddressRange>0x08000000</TextAddressRange>
<DataAddressRange>0x20000000</DataAddressRange>
<pXoBase></pXoBase>
<ScatterFile>.\firmware_XIP_ln882x.sct</ScatterFile>
<ScatterFile>.\ln882x.sct</ScatterFile>
<IncludeLibs></IncludeLibs>
<IncludeLibsPath></IncludeLibsPath>
<Misc>--no_autoat --keep=main.o(no_init_data)</Misc>
<Misc>--no_autoat --keep=*.o(no_init_data)</Misc>
<LinkerInputFile></LinkerInputFile>
<DisabledWarnings></DisabledWarnings>
</LDads>
@@ -429,16 +429,6 @@
</File>
</Files>
</Group>
<Group>
<GroupName>Drivers/Drv</GroupName>
<Files>
<File>
<FileName>drv_adc_measure.c</FileName>
<FileType>1</FileType>
<FilePath>..\..\..\..\platform\vendor_bsp\LN\ln882x\src\driver_ln882x\drv\drv_adc_measure.c</FilePath>
</File>
</Files>
</Group>
<Group>
<GroupName>Drivers/HAL</GroupName>
<Files>
@@ -738,6 +728,16 @@
<FileType>1</FileType>
<FilePath>..\..\BSP\Src\mcu_init.c</FilePath>
</File>
<File>
<FileName>serial_hw.c</FileName>
<FileType>1</FileType>
<FilePath>..\..\BSP\Src\serial_hw.c</FilePath>
</File>
<File>
<FileName>drv_adc_measure.c</FileName>
<FileType>1</FileType>
<FilePath>..\..\BSP\Src\drv_adc_measure.c</FilePath>
</File>
</Files>
</Group>
<Group>
@@ -748,11 +748,6 @@
<FileType>1</FileType>
<FilePath>..\..\..\..\platform\vendor_bsp\LN\ln882x\src\serial\serial.c</FilePath>
</File>
<File>
<FileName>serial_hw.c</FileName>
<FileType>1</FileType>
<FilePath>..\..\..\..\platform\vendor_bsp\LN\ln882x\src\serial\serial_hw.c</FilePath>
</File>
</Files>
</Group>
<Group>
@@ -934,9 +929,9 @@
<FilePath>..\..\..\..\platform\vendor_bsp\LN\ln882x\lib\wifi_mac.lib</FilePath>
</File>
<File>
<FileName>wifi_driver.lib</FileName>
<FileName>soc_driver.lib</FileName>
<FileType>4</FileType>
<FilePath>..\..\..\..\platform\vendor_bsp\LN\ln882x\lib\wifi_driver.lib</FilePath>
<FilePath>..\..\..\..\platform\vendor_bsp\LN\ln882x\lib\soc_driver.lib</FilePath>
</File>
</Files>
</Group>
@@ -948,6 +943,11 @@
<FileType>1</FileType>
<FilePath>..\..\..\..\platform\vendor_bsp\LN\ln882x\src\wifi\wifi_manager\wifi_manager.c</FilePath>
</File>
<File>
<FileName>wifi_port.c</FileName>
<FileType>1</FileType>
<FilePath>..\..\..\..\platform\vendor_bsp\LN\ln882x\src\wifi\wifi_port\wifi_port.c</FilePath>
</File>
</Files>
</Group>
<Group>
@@ -1242,22 +1242,27 @@
</Files>
</Group>
<Group>
<GroupName>tos_components</GroupName>
<GroupName>fs</GroupName>
<Files>
<File>
<FileName>tos_kv.c</FileName>
<FileName>ln_kv.c</FileName>
<FileType>1</FileType>
<FilePath>..\..\..\..\components\fs\kv\tos_kv.c</FilePath>
<FilePath>..\..\..\..\platform\vendor_bsp\LN\ln882x\src\fs\kv\kv\ln_kv.c</FilePath>
</File>
<File>
<FileName>ln_kv_port.c</FileName>
<FileType>1</FileType>
<FilePath>..\..\..\..\platform\vendor_bsp\LN\ln882x\src\fs\kv\kv_port\ln_kv_port.c</FilePath>
</File>
</Files>
</Group>
<Group>
<GroupName>nvds</GroupName>
<Files>
<File>
<FileName>nvds.c</FileName>
<FileType>1</FileType>
<FilePath>..\..\..\..\platform\vendor_bsp\LN\ln882x\src\nvds\nvds.c</FilePath>
<FilePath>..\..\..\..\platform\vendor_bsp\LN\ln882x\src\fs\nvds\nvds.c</FilePath>
</File>
<File>
<FileName>flash_partition_mgr.c</FileName>
<FileType>1</FileType>
<FilePath>..\..\..\..\platform\vendor_bsp\LN\ln882x\src\fs\partition_mgr\flash_partition_mgr.c</FilePath>
</File>
</Files>
</Group>

View File

@@ -1,8 +1,4 @@
python ..\..\..\..\platform\vendor_bsp\LN\ln882x\tools\user_cmd\after_build_soc.py firmware_XIP
..\..\..\..\platform\vendor_bsp\LN\ln882x\tools\bin\mkimage.exe ln882x flashimage ..\..\..\..\platform\vendor_bsp\LN\ln882x\lib\boot_ram_ln882x.bin firmware_XIP.bin flashimage.bin release=1 crp_enable=0 app_version=10 hw_version=0
..\..\..\..\platform\vendor_bsp\LN\ln882x\tools\bin\fpu_patch.exe .\firmware_XIP.asm .\flashimage.bin
python ..\..\..\..\platform\vendor_bsp\LN\ln882x\tools\user_cmd\after_build_soc.py @L
..\..\..\..\platform\vendor_bsp\LN\ln882x\tools\bin\mkimage.exe cmd_app ..\..\..\..\platform\vendor_bsp\LN\ln882x\lib\boot_ln882x.bin @L.bin @L.asm flashimage.bin flash_partition_cfg.json ver=1.1

View File

@@ -0,0 +1,22 @@
{
"Warning1":"警告,系统定义用户不可修改!!!",
"vendor_define":
[
{"partition_type": "BOOT", "start_addr": "0x00000000", "size_KB": 36 },
{"partition_type": "PART_TAB", "start_addr": "0x00009000", "size_KB": 4 }
],
"Warning2":"以下数据,用户根据SOC flash容量以及具体需求修改仅可以修改start_addr值和size值且必须4KB对齐!!!",
"user_define":
[
{"partition_type": "KV", "start_addr": "0x0000A000", "size_KB": 8 },
{"partition_type": "SIMU_EEPROM", "start_addr": "0x0000C000", "size_KB": 8 },
{"partition_type": "APP", "start_addr": "0x0000E000", "size_KB": 800 },
{"partition_type": "OTA", "start_addr": "0x000D6000", "size_KB": 800 },
{"partition_type": "NVDS", "start_addr": "0x0019E000", "size_KB": 12 },
{"partition_type": "USER", "start_addr": "0x001A1000", "size_KB": 12 }
]
}

View File

@@ -1,32 +1,56 @@
#ifndef __FLASH_PARTITION_TABLE_H__
#define __FLASH_PARTITION_TABLE_H__
#ifndef __FLASH_PARTITION_TABLE__
#define __FLASH_PARTITION_TABLE__
//#define RETENTION_MEM_BASE 0x20028000
//#define RETENTION_MEM_SIZE 0x2000
#ifndef FLASH_BASE
#define FLASH_BASE (0x10000000)
//flash partition map,it's generated by the script based on the json file <flash_partition_table.json>
#define BOOT_SPACE_OFFSET (0x00000000)
#define BOOT_SPACE_SIZE (1024*36)
#define PART_TAB_SPACE_OFFSET (0x00009000)
#define PART_TAB_SPACE_SIZE (1024*4)
#if (PART_TAB_SPACE_OFFSET < (BOOT_SPACE_OFFSET + BOOT_SPACE_SIZE))
#error "flash partition overlap,please check <flash_partition_table.json>!!!"
#endif
#ifndef FLASH_SIZE
#define FLASH_SIZE (0x00200000)
#define KV_SPACE_OFFSET (0x0000A000)
#define KV_SPACE_SIZE (1024*8)
#if (KV_SPACE_OFFSET < (PART_TAB_SPACE_OFFSET + PART_TAB_SPACE_SIZE))
#error "flash partition overlap,please check <flash_partition_table.json>!!!"
#endif
#ifndef PRIMARY_PARTITION_OFFSET
#define PRIMARY_PARTITION_OFFSET (0x0000F000)
#define SIMU_EEPROM_SPACE_OFFSET (0x0000C000)
#define SIMU_EEPROM_SPACE_SIZE (1024*8)
#if (SIMU_EEPROM_SPACE_OFFSET < (KV_SPACE_OFFSET + KV_SPACE_SIZE))
#error "flash partition overlap,please check <flash_partition_table.json>!!!"
#endif
#define PRIMARY_PATTITION_START 0x0000F000
#define PRIMARY_PATTITION_SIZE 0xE1000
//#define USERAPP_SRAM_BASE 0x1FFF0000
#define BACKUP_PATTITION_START 0x000F0000
#define BACKUP_PATTITION_SIZE 0xE1000
#define USERDATA_PATTITION_START 0x001D1000
#define USERDATA_PATTITION_SIZE 0x23000
//memory offset check
#if ((PRIMARY_PATTITION_START < PRIMARY_PARTITION_OFFSET) || (BACKUP_PATTITION_START < PRIMARY_PATTITION_START) || (USERDATA_PATTITION_START < BACKUP_PATTITION_START) || (PRIMARY_PATTITION_START + PRIMARY_PATTITION_SIZE > BACKUP_PATTITION_START) || (BACKUP_PATTITION_START + BACKUP_PATTITION_SIZE > USERDATA_PATTITION_START) || (USERDATA_PATTITION_START + USERDATA_PATTITION_SIZE > FLASH_SIZE))
#error "flash partition define error!"
#define APP_SPACE_OFFSET (0x0000E000)
#define APP_SPACE_SIZE (1024*800)
#if (APP_SPACE_OFFSET < (SIMU_EEPROM_SPACE_OFFSET + SIMU_EEPROM_SPACE_SIZE))
#error "flash partition overlap,please check <flash_partition_table.json>!!!"
#endif
#endif /* __FLASH_PARTITION_TABLE_H__ */
#define OTA_SPACE_OFFSET (0x000D6000)
#define OTA_SPACE_SIZE (1024*800)
#if (OTA_SPACE_OFFSET < (APP_SPACE_OFFSET + APP_SPACE_SIZE))
#error "flash partition overlap,please check <flash_partition_table.json>!!!"
#endif
#define NVDS_SPACE_OFFSET (0x0019E000)
#define NVDS_SPACE_SIZE (1024*12)
#if (NVDS_SPACE_OFFSET < (OTA_SPACE_OFFSET + OTA_SPACE_SIZE))
#error "flash partition overlap,please check <flash_partition_table.json>!!!"
#endif
#define USER_SPACE_OFFSET (0x001A1000)
#define USER_SPACE_SIZE (1024*12)
#if (USER_SPACE_OFFSET < (NVDS_SPACE_OFFSET + NVDS_SPACE_SIZE))
#error "flash partition overlap,please check <flash_partition_table.json>!!!"
#endif
#define IMAGE_HEADER_SIZE (0x100)
#endif /* __FLASH_PARTITION_TABLE__ */

View File

@@ -1,9 +1,9 @@
#! armcc -E
#include ".\flash_partition_table.h"
#include "flash_partition_table.h"
#include ".\..\..\..\..\platform\vendor_bsp\LN\ln882x\include\cpu\ARM_CM4F\ln88xx\mem_map_ln882x.h"
LR_FLASH FLASH_BASE+PRIMARY_PARTITION_OFFSET PRIMARY_PATTITION_SIZE
LR_FLASH CACHE_FLASH_BASE+APP_SPACE_OFFSET+IMAGE_HEADER_SIZE APP_SPACE_SIZE
{; load region size_region
ISR_VECTOR RAM_BASE ALIGN 0x100
@@ -11,7 +11,7 @@ LR_FLASH FLASH_BASE+PRIMARY_PARTITION_OFFSET PRIMARY_PATTITION_SIZE
startup_*.o (RESET, +First)
}
ER_FLASH FLASH_BASE+PRIMARY_PARTITION_OFFSET + ImageLength(ISR_VECTOR) PRIMARY_PATTITION_SIZE
ER_FLASH CACHE_FLASH_BASE+APP_SPACE_OFFSET+IMAGE_HEADER_SIZE + ImageLength(ISR_VECTOR) APP_SPACE_SIZE
{; load address = execution address
*(InRoot$$Sections)
.ANY (+RO)
@@ -24,15 +24,15 @@ LR_FLASH FLASH_BASE+PRIMARY_PARTITION_OFFSET PRIMARY_PATTITION_SIZE
ll_cache.o(+RO)
ll_dma.o(+RO)
ll_syscon.o(+RO)
ll_sleep.o(+RO)
ll_rtc.o(+RO)
;ll_sleep.o(+RO)
;ll_rtc.o(+RO)
cache.o(+RO)
qspi.o(+RO)
flash.o(+RO)
hal_dma.o(+RO)
hal_syscon.o(+RO)
hal_sleep.o(+RO)
hal_rtc.o(+RO)
;hal_sleep.o(+RO)
;hal_rtc.o(+RO)
;port.o(XIR)
;optional item
@@ -49,16 +49,32 @@ LR_FLASH FLASH_BASE+PRIMARY_PARTITION_OFFSET PRIMARY_PATTITION_SIZE
startup_ln*(+RW +ZI)
}
ER_DATA +0
ER_DATA_IN_B0 +0 RAM_BLOCK0_SIZE-ImageLength(ISR_VECTOR)-ImageLength(ER_CODE)-ImageLength(ER_STACK)
{
*(.ARM.__at_0x1FFFFFFC)
.ANY (+RW +ZI)
memp.o(+RW +ZI)
imem.o(+RW +ZI)
imem_if.o(+RW +ZI)
;cglobals_sta.o(+RW +ZI)
;event_manager.o(+RW +ZI)
iconfig.o(+RW +ZI)
common.o(+RW +ZI)
}
HEAP_SPACE0 +0 EMPTY RAM_BLOCK1_BASE-ImageLimit(ER_DATA_IN_B0)
{; Heap region
}
ER_DATA_IN_B1 RAM_BLOCK1_BASE RAM_BLOCK1_SIZE
{
*(wlan_mem_pkt)
*(wlan_mem_dscr)
.ANY (+RW +ZI)
}
;IQ Data area cannot be used by ER_DATA region
;ScatterAssert(ImageLimit(ER_DATA) < (0x20020300))
HEAP_SPACE +0 EMPTY RETENTION_MEM_BASE-ImageLimit(ER_DATA)
HEAP_SPACE1 +0 EMPTY RETENTION_MEM_BASE-ImageLimit(ER_DATA_IN_B1)
{; Heap region
}

View File

@@ -0,0 +1,6 @@
/Listings/
/Objects/
*.uvguix.*
JLinkLog.txt
*.bin
*.asm

File diff suppressed because it is too large Load Diff

View File

@@ -69,9 +69,9 @@
<nStopU2X>0</nStopU2X>
</BeforeCompile>
<BeforeMake>
<RunUserProg1>0</RunUserProg1>
<RunUserProg1>1</RunUserProg1>
<RunUserProg2>0</RunUserProg2>
<UserProg1Name></UserProg1Name>
<UserProg1Name>python ..\..\..\..\platform\vendor_bsp\LN\ln882x\tools\user_cmd\before_build.py flash_partition_cfg.json flash_partition_table.h</UserProg1Name>
<UserProg2Name></UserProg2Name>
<UserProg1Dos16Mode>0</UserProg1Dos16Mode>
<UserProg2Dos16Mode>0</UserProg2Dos16Mode>
@@ -80,9 +80,9 @@
</BeforeMake>
<AfterMake>
<RunUserProg1>1</RunUserProg1>
<RunUserProg2>0</RunUserProg2>
<UserProg1Name>.\after_build_ln882x.bat</UserProg1Name>
<UserProg2Name></UserProg2Name>
<RunUserProg2>1</RunUserProg2>
<UserProg1Name>python ..\..\..\..\platform\vendor_bsp\LN\ln882x\tools\user_cmd\after_build_soc.py @L</UserProg1Name>
<UserProg2Name>..\..\..\..\platform\vendor_bsp\LN\ln882x\tools\bin\mkimage.exe cmd_app ..\..\..\..\platform\vendor_bsp\LN\ln882x\lib\boot_ln882x.bin @L.bin @L.asm flashimage.bin flash_partition_cfg.json ver=1.1</UserProg2Name>
<UserProg1Dos16Mode>0</UserProg1Dos16Mode>
<UserProg2Dos16Mode>0</UserProg2Dos16Mode>
<nStopA1X>0</nStopA1X>
@@ -332,7 +332,7 @@
<MiscControls></MiscControls>
<Define>LN882x,ARM_MATH_CM4</Define>
<Undefine></Undefine>
<IncludePath>..\..\BSP\Inc;..\..\TOS-CONFIG;..\..\..\..\kernel\pm\include;..\..\..\..\kernel\core\include;..\..\..\..\arch\arm\arm-v7m\common\include;..\..\..\..\arch\arm\arm-v7m\cortex-m4\armcc;..\..\..\..\osal\cmsis_os;..\..\..\..\examples\helloworld;..\hello_world;..\..\..\..\platform\vendor_bsp\LN\ln882x\include\driver_ln882x;..\..\..\..\platform\vendor_bsp\LN\ln882x\src\driver_ln882x\ll\include;..\..\..\..\components\fs\kv\include;..\..\..\..\platform\vendor_bsp\LN\ln882x\include;..\..\..\..\platform\vendor_bsp\LN\ln882x\include\cpu\ARM_CM4F\ln88xx;..\..\..\..\platform\vendor_bsp\LN\ln882x\include\kernel;..\..\..\..\platform\vendor_bsp\LN\ln882x\include\cpu\ARM_CM4F\CMSIS_5.3.0;..\..\..\..\platform\vendor_bsp\LN\ln882x\include\wifi_manager;..\..\..\..\platform\vendor_bsp\LN\ln882x\include\net;..\..\..\..\platform\vendor_bsp\LN\ln882x\src\net\lwip-2.0.3\src\include;..\..\..\..\platform\vendor_bsp\LN\ln882x\src\net\lwip-2.0.3\src\port;..\..\..\..\platform\vendor_bsp\LN\ln882x\src\net\lwip-2.0.3\src\port\arch;..\..\..\..\examples\wifi_ln882x</IncludePath>
<IncludePath>..\..\BSP\Inc;..\..\TOS-CONFIG;..\..\..\..\kernel\pm\include;..\..\..\..\kernel\core\include;..\..\..\..\arch\arm\arm-v7m\common\include;..\..\..\..\arch\arm\arm-v7m\cortex-m4\armcc;..\..\..\..\osal\cmsis_os;..\..\..\..\examples\helloworld;..\hello_world;..\..\..\..\platform\vendor_bsp\LN\ln882x\include\driver_ln882x;..\..\..\..\platform\vendor_bsp\LN\ln882x\src\driver_ln882x\ll\include;..\..\..\..\components\fs\kv\include;..\..\..\..\platform\vendor_bsp\LN\ln882x\include;..\..\..\..\platform\vendor_bsp\LN\ln882x\include\cpu\ARM_CM4F\ln88xx;..\..\..\..\platform\vendor_bsp\LN\ln882x\include\kernel;..\..\..\..\platform\vendor_bsp\LN\ln882x\include\cpu\ARM_CM4F\CMSIS_5.3.0;..\..\..\..\platform\vendor_bsp\LN\ln882x\include\wifi_manager;..\..\..\..\platform\vendor_bsp\LN\ln882x\include\net;..\..\..\..\platform\vendor_bsp\LN\ln882x\src\net\lwip-2.0.3\src\include;..\..\..\..\platform\vendor_bsp\LN\ln882x\src\net\lwip-2.0.3\src\port;..\..\..\..\platform\vendor_bsp\LN\ln882x\src\net\lwip-2.0.3\src\port\arch;..\..\..\..\examples\wifi_ln882x;..\wifi_demo;..\..\..\..\platform\vendor_bsp\LN\ln882x\src\fs\kv\kv_port;..\..\..\..\platform\vendor_bsp\LN\ln882x\src\fs\kv\kv;..\..\..\..\platform\vendor_bsp\LN\ln882x\src\fs\nvds;..\..\..\..\platform\vendor_bsp\LN\ln882x\src\fs\partition_mgr;..\..\..\..\platform\vendor_bsp\LN\ln882x\src\driver_ln882x\ll\include;..\..\..\..\platform\vendor_bsp\LN\ln882x\src\wifi\wifi_mac\include;..\..\..\..\platform\vendor_bsp\LN\ln882x\src\wifi\wifi_mac\Common;..\..\..\..\platform\vendor_bsp\LN\ln882x\src\wifi\wifi_mac\Controller\AP;..\..\..\..\platform\vendor_bsp\LN\ln882x\src\wifi\wifi_mac\Controller\AP-STA;..\..\..\..\platform\vendor_bsp\LN\ln882x\src\wifi\wifi_mac\Controller\ModeIF;..\..\..\..\platform\vendor_bsp\LN\ln882x\src\wifi\wifi_mac\Controller\STA;..\..\..\..\platform\vendor_bsp\LN\ln882x\src\wifi\wifi_mac\Controller\STA\ProtIF;..\..\..\..\platform\vendor_bsp\LN\ln882x\src\wifi\wifi_mac\Core\AP-STA;..\..\..\..\platform\vendor_bsp\LN\ln882x\src\wifi\wifi_mac\Core\AP-STA\M802_11e;..\..\..\..\platform\vendor_bsp\LN\ln882x\src\wifi\wifi_mac\Core\AP-STA\M802_11i;..\..\..\..\platform\vendor_bsp\LN\ln882x\src\wifi\wifi_mac\Core\AP-STA\M802_11n;..\..\..\..\platform\vendor_bsp\LN\ln882x\src\wifi\wifi_mac\Core\AP-STA\ProtIF;..\..\..\..\platform\vendor_bsp\LN\ln882x\src\wifi\wifi_mac\Core\AP-STA\M802_11e;..\..\..\..\platform\vendor_bsp\LN\ln882x\src\wifi\wifi_mac\Core\AP;..\..\..\..\platform\vendor_bsp\LN\ln882x\src\wifi\wifi_mac\Core\AP\M802_11e;..\..\..\..\platform\vendor_bsp\LN\ln882x\src\wifi\wifi_mac\Core\AP\M802_11i;..\..\..\..\platform\vendor_bsp\LN\ln882x\src\wifi\wifi_mac\Core\AP\M802_11n;..\..\..\..\platform\vendor_bsp\LN\ln882x\src\wifi\wifi_mac\Core\AP\M802_1x;..\..\..\..\platform\vendor_bsp\LN\ln882x\src\wifi\wifi_mac\Core\AP\ProtIF;..\..\..\..\platform\vendor_bsp\LN\ln882x\src\wifi\wifi_mac\Core\STA;..\..\..\..\platform\vendor_bsp\LN\ln882x\src\wifi\wifi_mac\Core\STA\M802_11e;..\..\..\..\platform\vendor_bsp\LN\ln882x\src\wifi\wifi_mac\Core\STA\M802_11i;..\..\..\..\platform\vendor_bsp\LN\ln882x\src\wifi\wifi_mac\Core\STA\M802_11n;..\..\..\..\platform\vendor_bsp\LN\ln882x\src\wifi\wifi_mac\Core\STA\M802_1x;..\..\..\..\platform\vendor_bsp\LN\ln882x\src\wifi\wifi_mac\Core\STA\ProtIF;..\..\..\..\platform\vendor_bsp\LN\ln882x\src\wifi\wifi_mac\Core\ModeIF;..\..\..\..\platform\vendor_bsp\LN\ln882x\src\wifi\wifi_mac\Edge\Host;..\..\..\..\platform\vendor_bsp\LN\ln882x\src\wifi\wifi_mac\Edge\IF;..\..\..\..\platform\vendor_bsp\LN\ln882x\src\wifi\wifi_mac\Edge\MACHW;..\..\..\..\platform\vendor_bsp\LN\ln882x\src\wifi\wifi_mac\Edge\RF\ART2000;..\..\..\..\platform\vendor_bsp\LN\ln882x\src\wifi\wifi_mac\Edge\PHY\PHYHW\LN;..\..\..\..\platform\vendor_bsp\LN\ln882x\src\wifi\wifi_mac\Edge\PHY\PHYProt\P802_11n;..\..\..\..\platform\vendor_bsp\LN\ln882x\src\wifi\wifi_mac\Edge\TEMP_CAL;..\..\..\..\platform\vendor_bsp\LN\ln882x\src\wifi\wifi_mac\Edge\RF_HW;..\..\..\..\platform\vendor_bsp\LN\ln882x\src\wifi\wifi_mac\Edge\RF_IMG_CAL\hw_img_cal;..\..\..\..\platform\vendor_bsp\LN\ln882x\src\wifi\wifi_mac\Edge\RF_IMG_CAL\image_cal;..\..\..\..\platform\vendor_bsp\LN\ln882x\src\wifi\wifi_mac\CSL;..\..\..\..\platform\vendor_bsp\LN\ln882x\src\wifi\wifi_mac\Test\MacSwTest;..\..\..\..\platform\vendor_bsp\LN\ln882x\src\wifi\wifi_mac\Utils\MM;..\..\..\..\platform\vendor_bsp\LN\ln882x\src\wifi\wifi_mac\Utils\QM;..\..\..\..\platform\vendor_bsp\LN\ln882x\src\wifi\wifi_port;..\..\..\..\platform\vendor_bsp\LN\ln882x\src\wifi\wifi_if;..\..\..\..\platform\vendor_bsp\LN\ln882x\src\wifi\wifi_cfg\include</IncludePath>
</VariousControls>
</Cads>
<Aads>
@@ -362,10 +362,10 @@
<TextAddressRange>0x08000000</TextAddressRange>
<DataAddressRange>0x20000000</DataAddressRange>
<pXoBase></pXoBase>
<ScatterFile>.\firmware_XIP_ln882x.sct</ScatterFile>
<ScatterFile>.\ln882x.sct</ScatterFile>
<IncludeLibs></IncludeLibs>
<IncludeLibsPath></IncludeLibsPath>
<Misc>--no_autoat --keep=main.o(no_init_data)</Misc>
<Misc>--no_autoat --keep=*.o(no_init_data)</Misc>
<LinkerInputFile></LinkerInputFile>
<DisabledWarnings></DisabledWarnings>
</LDads>
@@ -417,16 +417,6 @@
</File>
</Files>
</Group>
<Group>
<GroupName>Drivers/Drv</GroupName>
<Files>
<File>
<FileName>drv_adc_measure.c</FileName>
<FileType>1</FileType>
<FilePath>..\..\..\..\platform\vendor_bsp\LN\ln882x\src\driver_ln882x\drv\drv_adc_measure.c</FilePath>
</File>
</Files>
</Group>
<Group>
<GroupName>Drivers/HAL</GroupName>
<Files>
@@ -689,6 +679,16 @@
</File>
</Files>
</Group>
<Group>
<GroupName>cmsis</GroupName>
<Files>
<File>
<FileName>cmsis_os.c</FileName>
<FileType>1</FileType>
<FilePath>..\..\..\..\osal\cmsis_os\cmsis_os.c</FilePath>
</File>
</Files>
</Group>
<Group>
<GroupName>config</GroupName>
<Files>
@@ -704,16 +704,6 @@
</File>
</Files>
</Group>
<Group>
<GroupName>cmsis</GroupName>
<Files>
<File>
<FileName>cmsis_os.c</FileName>
<FileType>1</FileType>
<FilePath>..\..\..\..\osal\cmsis_os\cmsis_os.c</FilePath>
</File>
</Files>
</Group>
<Group>
<GroupName>bsp</GroupName>
<Files>
@@ -722,6 +712,16 @@
<FileType>1</FileType>
<FilePath>..\..\BSP\Src\mcu_init.c</FilePath>
</File>
<File>
<FileName>serial_hw.c</FileName>
<FileType>1</FileType>
<FilePath>..\..\BSP\Src\serial_hw.c</FilePath>
</File>
<File>
<FileName>drv_adc_measure.c</FileName>
<FileType>1</FileType>
<FilePath>..\..\BSP\Src\drv_adc_measure.c</FilePath>
</File>
</Files>
</Group>
<Group>
@@ -732,11 +732,6 @@
<FileType>1</FileType>
<FilePath>..\..\..\..\platform\vendor_bsp\LN\ln882x\src\serial\serial.c</FilePath>
</File>
<File>
<FileName>serial_hw.c</FileName>
<FileType>1</FileType>
<FilePath>..\..\..\..\platform\vendor_bsp\LN\ln882x\src\serial\serial_hw.c</FilePath>
</File>
</Files>
</Group>
<Group>
@@ -912,16 +907,16 @@
<FileType>4</FileType>
<FilePath>..\..\..\..\platform\vendor_bsp\LN\ln882x\lib\arm_cortexM4lf_math.lib</FilePath>
</File>
<File>
<FileName>soc_driver.lib</FileName>
<FileType>4</FileType>
<FilePath>..\..\..\..\platform\vendor_bsp\LN\ln882x\lib\soc_driver.lib</FilePath>
</File>
<File>
<FileName>wifi_mac.lib</FileName>
<FileType>4</FileType>
<FilePath>..\..\..\..\platform\vendor_bsp\LN\ln882x\lib\wifi_mac.lib</FilePath>
</File>
<File>
<FileName>wifi_driver.lib</FileName>
<FileType>4</FileType>
<FilePath>..\..\..\..\platform\vendor_bsp\LN\ln882x\lib\wifi_driver.lib</FilePath>
</File>
</Files>
</Group>
<Group>
@@ -932,6 +927,11 @@
<FileType>1</FileType>
<FilePath>..\..\..\..\platform\vendor_bsp\LN\ln882x\src\wifi\wifi_manager\wifi_manager.c</FilePath>
</File>
<File>
<FileName>wifi_port.c</FileName>
<FileType>1</FileType>
<FilePath>..\..\..\..\platform\vendor_bsp\LN\ln882x\src\wifi\wifi_port\wifi_port.c</FilePath>
</File>
</Files>
</Group>
<Group>
@@ -1222,22 +1222,27 @@
</Files>
</Group>
<Group>
<GroupName>tos_components</GroupName>
<Files>
<File>
<FileName>tos_kv.c</FileName>
<FileType>1</FileType>
<FilePath>..\..\..\..\components\fs\kv\tos_kv.c</FilePath>
</File>
</Files>
</Group>
<Group>
<GroupName>nvds</GroupName>
<GroupName>fs</GroupName>
<Files>
<File>
<FileName>nvds.c</FileName>
<FileType>1</FileType>
<FilePath>..\..\..\..\platform\vendor_bsp\LN\ln882x\src\nvds\nvds.c</FilePath>
<FilePath>..\..\..\..\platform\vendor_bsp\LN\ln882x\src\fs\nvds\nvds.c</FilePath>
</File>
<File>
<FileName>flash_partition_mgr.c</FileName>
<FileType>1</FileType>
<FilePath>..\..\..\..\platform\vendor_bsp\LN\ln882x\src\fs\partition_mgr\flash_partition_mgr.c</FilePath>
</File>
<File>
<FileName>ln_kv.c</FileName>
<FileType>1</FileType>
<FilePath>..\..\..\..\platform\vendor_bsp\LN\ln882x\src\fs\kv\kv\ln_kv.c</FilePath>
</File>
<File>
<FileName>ln_kv_port.c</FileName>
<FileType>1</FileType>
<FilePath>..\..\..\..\platform\vendor_bsp\LN\ln882x\src\fs\kv\kv_port\ln_kv_port.c</FilePath>
</File>
</Files>
</Group>

View File

@@ -1,8 +1,4 @@
python ..\..\..\..\platform\vendor_bsp\LN\ln882x\tools\user_cmd\after_build_soc.py firmware_XIP
..\..\..\..\platform\vendor_bsp\LN\ln882x\tools\bin\mkimage.exe ln882x flashimage ..\..\..\..\platform\vendor_bsp\LN\ln882x\lib\boot_ram_ln882x.bin firmware_XIP.bin flashimage.bin release=1 crp_enable=0 app_version=10 hw_version=0
..\..\..\..\platform\vendor_bsp\LN\ln882x\tools\bin\fpu_patch.exe .\firmware_XIP.asm .\flashimage.bin
python ..\..\..\..\platform\vendor_bsp\LN\ln882x\tools\user_cmd\after_build_soc.py @L
..\..\..\..\platform\vendor_bsp\LN\ln882x\tools\bin\mkimage.exe cmd_app ..\..\..\..\platform\vendor_bsp\LN\ln882x\lib\boot_ln882x.bin @L.bin @L.asm flashimage.bin flash_partition_cfg.json ver=1.1

View File

@@ -0,0 +1,22 @@
{
"Warning1":"警告,系统定义用户不可修改!!!",
"vendor_define":
[
{"partition_type": "BOOT", "start_addr": "0x00000000", "size_KB": 36 },
{"partition_type": "PART_TAB", "start_addr": "0x00009000", "size_KB": 4 }
],
"Warning2":"以下数据,用户根据SOC flash容量以及具体需求修改仅可以修改start_addr值和size值且必须4KB对齐!!!",
"user_define":
[
{"partition_type": "KV", "start_addr": "0x0000A000", "size_KB": 8 },
{"partition_type": "SIMU_EEPROM", "start_addr": "0x0000C000", "size_KB": 8 },
{"partition_type": "APP", "start_addr": "0x0000E000", "size_KB": 800 },
{"partition_type": "OTA", "start_addr": "0x000D6000", "size_KB": 800 },
{"partition_type": "NVDS", "start_addr": "0x0019E000", "size_KB": 12 },
{"partition_type": "USER", "start_addr": "0x001A1000", "size_KB": 12 }
]
}

View File

@@ -1,32 +1,56 @@
#ifndef __FLASH_PARTITION_TABLE_H__
#define __FLASH_PARTITION_TABLE_H__
#ifndef __FLASH_PARTITION_TABLE__
#define __FLASH_PARTITION_TABLE__
//#define RETENTION_MEM_BASE 0x20028000
//#define RETENTION_MEM_SIZE 0x2000
#ifndef FLASH_BASE
#define FLASH_BASE (0x10000000)
//flash partition map,it's generated by the script based on the json file <flash_partition_table.json>
#define BOOT_SPACE_OFFSET (0x00000000)
#define BOOT_SPACE_SIZE (1024*36)
#define PART_TAB_SPACE_OFFSET (0x00009000)
#define PART_TAB_SPACE_SIZE (1024*4)
#if (PART_TAB_SPACE_OFFSET < (BOOT_SPACE_OFFSET + BOOT_SPACE_SIZE))
#error "flash partition overlap,please check <flash_partition_table.json>!!!"
#endif
#ifndef FLASH_SIZE
#define FLASH_SIZE (0x00200000)
#define KV_SPACE_OFFSET (0x0000A000)
#define KV_SPACE_SIZE (1024*8)
#if (KV_SPACE_OFFSET < (PART_TAB_SPACE_OFFSET + PART_TAB_SPACE_SIZE))
#error "flash partition overlap,please check <flash_partition_table.json>!!!"
#endif
#ifndef PRIMARY_PARTITION_OFFSET
#define PRIMARY_PARTITION_OFFSET (0x0000F000)
#define SIMU_EEPROM_SPACE_OFFSET (0x0000C000)
#define SIMU_EEPROM_SPACE_SIZE (1024*8)
#if (SIMU_EEPROM_SPACE_OFFSET < (KV_SPACE_OFFSET + KV_SPACE_SIZE))
#error "flash partition overlap,please check <flash_partition_table.json>!!!"
#endif
#define PRIMARY_PATTITION_START 0x0000F000
#define PRIMARY_PATTITION_SIZE 0xE1000
//#define USERAPP_SRAM_BASE 0x1FFF0000
#define BACKUP_PATTITION_START 0x000F0000
#define BACKUP_PATTITION_SIZE 0xE1000
#define USERDATA_PATTITION_START 0x001D1000
#define USERDATA_PATTITION_SIZE 0x23000
//memory offset check
#if ((PRIMARY_PATTITION_START < PRIMARY_PARTITION_OFFSET) || (BACKUP_PATTITION_START < PRIMARY_PATTITION_START) || (USERDATA_PATTITION_START < BACKUP_PATTITION_START) || (PRIMARY_PATTITION_START + PRIMARY_PATTITION_SIZE > BACKUP_PATTITION_START) || (BACKUP_PATTITION_START + BACKUP_PATTITION_SIZE > USERDATA_PATTITION_START) || (USERDATA_PATTITION_START + USERDATA_PATTITION_SIZE > FLASH_SIZE))
#error "flash partition define error!"
#define APP_SPACE_OFFSET (0x0000E000)
#define APP_SPACE_SIZE (1024*800)
#if (APP_SPACE_OFFSET < (SIMU_EEPROM_SPACE_OFFSET + SIMU_EEPROM_SPACE_SIZE))
#error "flash partition overlap,please check <flash_partition_table.json>!!!"
#endif
#endif /* __FLASH_PARTITION_TABLE_H__ */
#define OTA_SPACE_OFFSET (0x000D6000)
#define OTA_SPACE_SIZE (1024*800)
#if (OTA_SPACE_OFFSET < (APP_SPACE_OFFSET + APP_SPACE_SIZE))
#error "flash partition overlap,please check <flash_partition_table.json>!!!"
#endif
#define NVDS_SPACE_OFFSET (0x0019E000)
#define NVDS_SPACE_SIZE (1024*12)
#if (NVDS_SPACE_OFFSET < (OTA_SPACE_OFFSET + OTA_SPACE_SIZE))
#error "flash partition overlap,please check <flash_partition_table.json>!!!"
#endif
#define USER_SPACE_OFFSET (0x001A1000)
#define USER_SPACE_SIZE (1024*12)
#if (USER_SPACE_OFFSET < (NVDS_SPACE_OFFSET + NVDS_SPACE_SIZE))
#error "flash partition overlap,please check <flash_partition_table.json>!!!"
#endif
#define IMAGE_HEADER_SIZE (0x100)
#endif /* __FLASH_PARTITION_TABLE__ */

View File

@@ -1,9 +1,9 @@
#! armcc -E
#include ".\flash_partition_table.h"
#include "flash_partition_table.h"
#include ".\..\..\..\..\platform\vendor_bsp\LN\ln882x\include\cpu\ARM_CM4F\ln88xx\mem_map_ln882x.h"
LR_FLASH FLASH_BASE+PRIMARY_PARTITION_OFFSET PRIMARY_PATTITION_SIZE
LR_FLASH CACHE_FLASH_BASE+APP_SPACE_OFFSET+IMAGE_HEADER_SIZE APP_SPACE_SIZE
{; load region size_region
ISR_VECTOR RAM_BASE ALIGN 0x100
@@ -11,7 +11,7 @@ LR_FLASH FLASH_BASE+PRIMARY_PARTITION_OFFSET PRIMARY_PATTITION_SIZE
startup_*.o (RESET, +First)
}
ER_FLASH FLASH_BASE+PRIMARY_PARTITION_OFFSET + ImageLength(ISR_VECTOR) PRIMARY_PATTITION_SIZE
ER_FLASH CACHE_FLASH_BASE+APP_SPACE_OFFSET+IMAGE_HEADER_SIZE + ImageLength(ISR_VECTOR) APP_SPACE_SIZE
{; load address = execution address
*(InRoot$$Sections)
.ANY (+RO)
@@ -24,15 +24,15 @@ LR_FLASH FLASH_BASE+PRIMARY_PARTITION_OFFSET PRIMARY_PATTITION_SIZE
ll_cache.o(+RO)
ll_dma.o(+RO)
ll_syscon.o(+RO)
ll_sleep.o(+RO)
ll_rtc.o(+RO)
;ll_sleep.o(+RO)
;ll_rtc.o(+RO)
cache.o(+RO)
qspi.o(+RO)
flash.o(+RO)
hal_dma.o(+RO)
hal_syscon.o(+RO)
hal_sleep.o(+RO)
hal_rtc.o(+RO)
;hal_sleep.o(+RO)
;hal_rtc.o(+RO)
;port.o(XIR)
;optional item
@@ -49,16 +49,32 @@ LR_FLASH FLASH_BASE+PRIMARY_PARTITION_OFFSET PRIMARY_PATTITION_SIZE
startup_ln*(+RW +ZI)
}
ER_DATA +0
ER_DATA_IN_B0 +0 RAM_BLOCK0_SIZE-ImageLength(ISR_VECTOR)-ImageLength(ER_CODE)-ImageLength(ER_STACK)
{
*(.ARM.__at_0x1FFFFFFC)
.ANY (+RW +ZI)
memp.o(+RW +ZI)
imem.o(+RW +ZI)
imem_if.o(+RW +ZI)
;cglobals_sta.o(+RW +ZI)
;event_manager.o(+RW +ZI)
iconfig.o(+RW +ZI)
common.o(+RW +ZI)
}
HEAP_SPACE0 +0 EMPTY RAM_BLOCK1_BASE-ImageLimit(ER_DATA_IN_B0)
{; Heap region
}
ER_DATA_IN_B1 RAM_BLOCK1_BASE RAM_BLOCK1_SIZE
{
*(wlan_mem_pkt)
*(wlan_mem_dscr)
.ANY (+RW +ZI)
}
;IQ Data area cannot be used by ER_DATA region
;ScatterAssert(ImageLimit(ER_DATA) < (0x20020300))
HEAP_SPACE +0 EMPTY RETENTION_MEM_BASE-ImageLimit(ER_DATA)
HEAP_SPACE1 +0 EMPTY RETENTION_MEM_BASE-ImageLimit(ER_DATA_IN_B1)
{; Heap region
}

View File

@@ -0,0 +1,290 @@
;/**************************************************************************//**
; * @file startup_ARMCM4.s
; * @brief CMSIS Core Device Startup File for
; * ARMCM4 Device Series
; * @version V5.00
; * @date 02. March 2016
; ******************************************************************************/
;/*
; * Copyright (c) 2009-2016 ARM Limited. All rights reserved.
; *
; * SPDX-License-Identifier: Apache-2.0
; *
; * Licensed under the Apache License, Version 2.0 (the License); you may
; * not use this file except in compliance with the License.
; * You may obtain a copy of the License at
; *
; * www.apache.org/licenses/LICENSE-2.0
; *
; * Unless required by applicable law or agreed to in writing, software
; * distributed under the License is distributed on an AS IS BASIS, WITHOUT
; * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
; * See the License for the specific language governing permissions and
; * limitations under the License.
; */
;/*
;//-------- <<< Use Configuration Wizard in Context Menu >>> ------------------
;*/
; <h> Stack Configuration
; <o> Stack Size (in Bytes) <0x0-0xFFFFFFFF:8>
; </h>
Stack_Size EQU 0x00001800
AREA STACK, NOINIT, READWRITE, ALIGN=3
Stack_Mem SPACE Stack_Size
__initial_sp
; <h> Heap Configuration
; <o> Heap Size (in Bytes) <0x0-0xFFFFFFFF:8>
; </h>
Heap_Size EQU 0x00000000
AREA HEAP, NOINIT, READWRITE, ALIGN=3
__heap_base
Heap_Mem SPACE Heap_Size
__heap_limit
PRESERVE8
THUMB
; Vector Table Mapped to Address 0 at Reset
AREA RESET, DATA, READONLY
EXPORT __Vectors
EXPORT __Vectors_End
EXPORT __Vectors_Size
__Vectors DCD __initial_sp ;(0x00)Top of Stack
DCD Reset_Handler ;(0x04)IRQ -15 Reset Handler
DCD NMI_Handler ;(0x08)IRQ -14 NMI Handler
DCD HardFault_Handler ;(0x0C)IRQ -13 Hard Fault Handler
DCD MemManage_Handler ;(0x10)IRQ -12 MPU Fault Handler
DCD BusFault_Handler ;(0x14)IRQ -11 Bus Fault Handler
DCD UsageFault_Handler ;(0x18)IRQ -10 Usage Fault Handler
DCD 0 ;(0x1C)IRQ -9 Reserved
DCD 0 ;(0x20)IRQ -8 Reserved
DCD 0 ;(0x24)IRQ -7 Reserved
DCD 0 ;(0x28)IRQ -6 Reserved
DCD SVC_Handler ;(0x2C)IRQ -5 SVCall Handler
DCD DebugMon_Handler ;(0x30)IRQ -4 Debug Monitor Handler
DCD 0 ;(0x34)IRQ -3 Reserved
DCD PendSV_Handler ;(0x38)IRQ -2 PendSV Handler
DCD SysTick_Handler ;(0x3C)IRQ -1 SysTick Handler
; External Interrupts
DCD WDT_IRQHandler ;(0x40)IRQ0
DCD EXTERNAL_IRQHandler ;(0x44)IRQ1
DCD RTC_IRQHandler ;(0x48)IRQ2
DCD SLEEP_IRQHandler ;(0x4C)IRQ3
DCD MAC_IRQHandler ;(0x50)IRQ4
DCD DMA_IRQHandler ;(0x54)IRQ5
DCD QSPI_IRQHandler ;(0x58)IRQ6
DCD SDIO_FUN1_IRQHandler ;(0x5C)IRQ7
DCD SDIO_FUN2_IRQHandler ;(0x60)IRQ8
DCD SDIO_FUN3_IRQHandler ;(0x64)IRQ9
DCD SDIO_FUN4_IRQHandler ;(0x68)IRQ10
DCD SDIO_FUN5_IRQHandler ;(0x6C)IRQ11
DCD SDIO_FUN6_IRQHandler ;(0x70)IRQ12
DCD SDIO_FUN7_IRQHandler ;(0x74)IRQ13
DCD SDIO_ASYNC_HOST_IRQHandler ;(0x78)IRQ14
DCD SDIO_M2S_IRQHandler ;(0x7C)IRQ15
DCD CM4_INTR0_IRQHandler ;(0x80)IRQ16
DCD CM4_INTR1_IRQHandler ;(0x84)IRQ17
DCD CM4_INTR2_IRQHandler ;(0x88)IRQ18
DCD CM4_INTR3_IRQHandler ;(0x8C)IRQ19
DCD CM4_INTR4_IRQHandler ;(0x90)IRQ20
DCD CM4_INTR5_IRQHandler ;(0x94)IRQ21
DCD ADC_IRQHandler ;(0x98)IRQ22
DCD TIMER_IRQHandler ;(0x9C)IRQ23
DCD I2C0_IRQHandler ;(0xA0)IRQ24
DCD I2C1_IRQHandler ;(0xA4)IRQ25
DCD SPI0_IRQHandler ;(0xA8)IRQ26
DCD SPI2_IRQHandler ;(0xAC)IRQ27
DCD UART0_IRQHandler ;(0xB0)IRQ28
DCD UART1_IRQHandler ;(0xB4)IRQ29
DCD SPI1_IRQHandler ;(0xB8)IRQ30
DCD GPIO_IRQHandler ;(0xBC)IRQ31
DCD I2S_IRQHandler ;(0xC0)IRQ32
DCD PAOTD_IRQHandler ;(0xC4)IRQ33
DCD PWM_IRQHandler ;(0xC8)IRQ34
DCD TRNG_IRQHandler ;(0xCC)IRQ35
DCD AES_IRQHandler ;(0xD0)IRQ36
__Vectors_End
__Vectors_Size EQU __Vectors_End - __Vectors
AREA |.text|, CODE, READONLY
; Reset Handler
Reset_Handler PROC
EXPORT Reset_Handler [WEAK]
IMPORT SystemInit
IMPORT __main
LDR R4, =SystemInit
BLX R4
LDR R4, =__main
BX R4
ENDP
; Dummy Exception Handlers (infinite loops which can be modified)
NMI_Handler PROC
EXPORT NMI_Handler [WEAK]
B .
ENDP
HardFault_Handler\
PROC
EXPORT HardFault_Handler [WEAK]
B .
ENDP
MemManage_Handler\
PROC
EXPORT MemManage_Handler [WEAK]
B .
ENDP
BusFault_Handler\
PROC
EXPORT BusFault_Handler [WEAK]
B .
ENDP
UsageFault_Handler\
PROC
EXPORT UsageFault_Handler [WEAK]
B .
ENDP
SVC_Handler PROC
EXPORT SVC_Handler [WEAK]
B .
ENDP
DebugMon_Handler\
PROC
EXPORT DebugMon_Handler [WEAK]
B .
ENDP
PendSV_Handler PROC
EXPORT PendSV_Handler [WEAK]
B .
ENDP
SysTick_Handler PROC
EXPORT SysTick_Handler [WEAK]
B .
ENDP
Default_Handler PROC
EXPORT WDT_IRQHandler [WEAK]
EXPORT EXTERNAL_IRQHandler [WEAK]
EXPORT RTC_IRQHandler [WEAK]
EXPORT SLEEP_IRQHandler [WEAK]
EXPORT MAC_IRQHandler [WEAK]
EXPORT DMA_IRQHandler [WEAK]
EXPORT QSPI_IRQHandler [WEAK]
EXPORT SDIO_FUN1_IRQHandler [WEAK]
EXPORT SDIO_FUN2_IRQHandler [WEAK]
EXPORT SDIO_FUN3_IRQHandler [WEAK]
EXPORT SDIO_FUN4_IRQHandler [WEAK]
EXPORT SDIO_FUN5_IRQHandler [WEAK]
EXPORT SDIO_FUN6_IRQHandler [WEAK]
EXPORT SDIO_FUN7_IRQHandler [WEAK]
EXPORT SDIO_ASYNC_HOST_IRQHandler [WEAK]
EXPORT SDIO_M2S_IRQHandler [WEAK]
EXPORT CM4_INTR0_IRQHandler [WEAK]
EXPORT CM4_INTR1_IRQHandler [WEAK]
EXPORT CM4_INTR2_IRQHandler [WEAK]
EXPORT CM4_INTR3_IRQHandler [WEAK]
EXPORT CM4_INTR4_IRQHandler [WEAK]
EXPORT CM4_INTR5_IRQHandler [WEAK]
EXPORT ADC_IRQHandler [WEAK]
EXPORT TIMER_IRQHandler [WEAK]
EXPORT I2C0_IRQHandler [WEAK]
EXPORT I2C1_IRQHandler [WEAK]
EXPORT SPI0_IRQHandler [WEAK]
EXPORT SPI2_IRQHandler [WEAK]
EXPORT UART0_IRQHandler [WEAK]
EXPORT UART1_IRQHandler [WEAK]
EXPORT SPI1_IRQHandler [WEAK]
EXPORT GPIO_IRQHandler [WEAK]
EXPORT I2S_IRQHandler [WEAK]
EXPORT PAOTD_IRQHandler [WEAK]
EXPORT PWM_IRQHandler [WEAK]
EXPORT TRNG_IRQHandler [WEAK]
EXPORT AES_IRQHandler [WEAK]
WDT_IRQHandler
EXTERNAL_IRQHandler
RTC_IRQHandler
SLEEP_IRQHandler
MAC_IRQHandler
DMA_IRQHandler
QSPI_IRQHandler
SDIO_FUN1_IRQHandler
SDIO_FUN2_IRQHandler
SDIO_FUN3_IRQHandler
SDIO_FUN4_IRQHandler
SDIO_FUN5_IRQHandler
SDIO_FUN6_IRQHandler
SDIO_FUN7_IRQHandler
SDIO_ASYNC_HOST_IRQHandler
SDIO_M2S_IRQHandler
CM4_INTR0_IRQHandler
CM4_INTR1_IRQHandler
CM4_INTR2_IRQHandler
CM4_INTR3_IRQHandler
CM4_INTR4_IRQHandler
CM4_INTR5_IRQHandler
ADC_IRQHandler
TIMER_IRQHandler
I2C0_IRQHandler
I2C1_IRQHandler
SPI0_IRQHandler
SPI2_IRQHandler
UART0_IRQHandler
UART1_IRQHandler
SPI1_IRQHandler
GPIO_IRQHandler
I2S_IRQHandler
PAOTD_IRQHandler
PWM_IRQHandler
TRNG_IRQHandler
AES_IRQHandler
B .
ENDP
ALIGN
; User Initial Stack & Heap
IF :DEF:__MICROLIB
EXPORT __initial_sp
EXPORT __heap_base
EXPORT __heap_limit
ELSE
IMPORT __use_two_region_memory
EXPORT __user_initial_stackheap
__user_initial_stackheap PROC
LDR R0, = Heap_Mem
LDR R1, =(Stack_Mem + Stack_Size)
LDR R2, = (Heap_Mem + Heap_Size)
LDR R3, = Stack_Mem
BX LR
ENDP
ALIGN
ENDIF
END