提交 27a8ff8d 编写于 作者: R Rbb666

完善ART-PI BSP

上级 173913b9
......@@ -24,7 +24,7 @@ static struct rt_memheap system_heap;
#endif
/**
* @brief Perform the SDRAM exernal memory inialization sequence
* @brief
* @param hsdram: SDRAM handle
* @param Command: Pointer to SDRAM command structure
* @retval None
......@@ -51,7 +51,7 @@ static void SDRAM_Initialization_Sequence(SDRAM_HandleTypeDef *hsdram, FMC_SDRAM
/* Insert 100 ms delay */
/* interrupt is not enable, just to delay some time. */
for (tmpmrd = 0; tmpmrd < 0xffffff; tmpmrd ++)
for (tmpmrd = 0; tmpmrd < 0xffff; tmpmrd ++)
;
/* Configure a PALL (precharge all) command */
......
......@@ -56,7 +56,7 @@ if GetDepend(['RT_USING_HWTIMER']) or GetDepend(['RT_USING_PWM']):
src += ['STM32H7xx_HAL_Driver/Src/stm32h7xx_hal_tim_ex.c']
src += ['STM32H7xx_HAL_Driver/Src/stm32h7xx_hal_lptim.c']
if GetDepend(['BSP_USING_ETH']):
if GetDepend(['BSP_USING_ETH']) or GetDepend(['BSP_USING_ETH_H750']):
src += ['STM32H7xx_HAL_Driver/Src/stm32h7xx_hal_eth.c']
src += ['STM32H7xx_HAL_Driver/Src/stm32h7xx_hal_eth_ex.c']
......
......@@ -15,10 +15,20 @@
/* defined the LED0 pin: PI8 */
#define LED0_PIN GET_PIN(I, 8)
#ifdef RT_USING_WIFI
extern void wlan_autoconnect_init(void);
#endif
int main(void)
{
/* set LED0 pin mode to output */
rt_pin_mode(LED0_PIN, PIN_MODE_OUTPUT);
#ifdef RT_USING_WIFI
/* init Wi-Fi auto connect feature */
wlan_autoconnect_init();
/* enable auto reconnect on WLAN device */
rt_wlan_config_autoreconnect(RT_TRUE);
#endif
while (1)
{
......
......@@ -51,7 +51,7 @@ extern "C" {
/* USER CODE END EM */
/* Exported functions prototypes ---------------------------------------------*/
void Error_Handler(void);
/* USER CODE BEGIN EFP */
......
......@@ -45,12 +45,12 @@
/* #define HAL_DAC_MODULE_ENABLED */
/* #define HAL_DCMI_MODULE_ENABLED */
/* #define HAL_DMA2D_MODULE_ENABLED */
/* #define HAL_ETH_MODULE_ENABLED */
#define HAL_ETH_MODULE_ENABLED
/* #define HAL_NAND_MODULE_ENABLED */
/* #define HAL_NOR_MODULE_ENABLED */
/* #define HAL_OTFDEC_MODULE_ENABLED */
/* #define HAL_SRAM_MODULE_ENABLED */
/* #define HAL_SDRAM_MODULE_ENABLED */
#define HAL_SDRAM_MODULE_ENABLED
/* #define HAL_HASH_MODULE_ENABLED */
/* #define HAL_HRTIM_MODULE_ENABLED */
/* #define HAL_HSEM_MODULE_ENABLED */
......@@ -61,17 +61,17 @@
/* #define HAL_OSPI_MODULE_ENABLED */
/* #define HAL_I2S_MODULE_ENABLED */
/* #define HAL_SMBUS_MODULE_ENABLED */
/* #define HAL_IWDG_MODULE_ENABLED */
#define HAL_IWDG_MODULE_ENABLED
/* #define HAL_LPTIM_MODULE_ENABLED */
/* #define HAL_LTDC_MODULE_ENABLED */
#define HAL_LTDC_MODULE_ENABLED
/* #define HAL_QSPI_MODULE_ENABLED */
/* #define HAL_RNG_MODULE_ENABLED */
/* #define HAL_RTC_MODULE_ENABLED */
/* #define HAL_SAI_MODULE_ENABLED */
/* #define HAL_SD_MODULE_ENABLED */
#define HAL_SD_MODULE_ENABLED
/* #define HAL_MMC_MODULE_ENABLED */
/* #define HAL_SPDIFRX_MODULE_ENABLED */
/* #define HAL_SPI_MODULE_ENABLED */
#define HAL_SPI_MODULE_ENABLED
/* #define HAL_SWPMI_MODULE_ENABLED */
/* #define HAL_TIM_MODULE_ENABLED */
#define HAL_UART_MODULE_ENABLED
......@@ -79,7 +79,7 @@
/* #define HAL_IRDA_MODULE_ENABLED */
/* #define HAL_SMARTCARD_MODULE_ENABLED */
/* #define HAL_WWDG_MODULE_ENABLED */
/* #define HAL_PCD_MODULE_ENABLED */
#define HAL_PCD_MODULE_ENABLED
/* #define HAL_HCD_MODULE_ENABLED */
/* #define HAL_DFSDM_MODULE_ENABLED */
/* #define HAL_DSI_MODULE_ENABLED */
......@@ -105,11 +105,11 @@
* (when HSE is used as system clock source, directly or through the PLL).
*/
#if !defined (HSE_VALUE)
#define HSE_VALUE ((uint32_t)25000000) /*!< Value of the External oscillator in Hz : FPGA case fixed to 60MHZ */
#define HSE_VALUE (25000000UL) /*!< Value of the External oscillator in Hz : FPGA case fixed to 60MHZ */
#endif /* HSE_VALUE */
#if !defined (HSE_STARTUP_TIMEOUT)
#define HSE_STARTUP_TIMEOUT ((uint32_t)100U) /*!< Time out for HSE start up, in ms */
#define HSE_STARTUP_TIMEOUT (100UL) /*!< Time out for HSE start up, in ms */
#endif /* HSE_STARTUP_TIMEOUT */
/**
......@@ -117,7 +117,7 @@
* This value is the default CSI value after Reset.
*/
#if !defined (CSI_VALUE)
#define CSI_VALUE ((uint32_t)4000000) /*!< Value of the Internal oscillator in Hz*/
#define CSI_VALUE (4000000UL) /*!< Value of the Internal oscillator in Hz*/
#endif /* CSI_VALUE */
/**
......@@ -126,7 +126,7 @@
* (when HSI is used as system clock source, directly or through the PLL).
*/
#if !defined (HSI_VALUE)
#define HSI_VALUE ((uint32_t)64000000) /*!< Value of the Internal oscillator in Hz*/
#define HSI_VALUE (64000000UL) /*!< Value of the Internal oscillator in Hz*/
#endif /* HSI_VALUE */
/**
......@@ -134,11 +134,11 @@
* This value is used by the UART, RTC HAL module to compute the system frequency
*/
#if !defined (LSE_VALUE)
#define LSE_VALUE ((uint32_t)32768U) /*!< Value of the External oscillator in Hz*/
#define LSE_VALUE (32768UL) /*!< Value of the External oscillator in Hz*/
#endif /* LSE_VALUE */
#if !defined (LSE_STARTUP_TIMEOUT)
#define LSE_STARTUP_TIMEOUT ((uint32_t)5000U) /*!< Time out for LSE start up, in ms */
#define LSE_STARTUP_TIMEOUT (5000UL) /*!< Time out for LSE start up, in ms */
#endif /* LSE_STARTUP_TIMEOUT */
#if !defined (LSI_VALUE)
......@@ -153,7 +153,7 @@
* frequency, this source is inserted directly through I2S_CKIN pad.
*/
#if !defined (EXTERNAL_CLOCK_VALUE)
#define EXTERNAL_CLOCK_VALUE 12288000U /*!< Value of the External clock in Hz*/
#define EXTERNAL_CLOCK_VALUE 12288000UL /*!< Value of the External clock in Hz*/
#endif /* EXTERNAL_CLOCK_VALUE */
/* Tip: To avoid modifying this file each time you need to use different HSE,
......@@ -163,9 +163,9 @@
/**
* @brief This is the HAL system configuration section
*/
#define VDD_VALUE ((uint32_t)3300U) /*!< Value of VDD in mv */
#define TICK_INT_PRIORITY ((uint32_t)0U) /*!< tick interrupt priority */
#define USE_RTOS 0U
#define VDD_VALUE (3300UL) /*!< Value of VDD in mv */
#define TICK_INT_PRIORITY (0UL) /*!< tick interrupt priority */
#define USE_RTOS 0
#define USE_SD_TRANSCEIVER 0U /*!< use uSD Transceiver */
#define USE_SPI_CRC 0U /*!< use CRC in SPI */
......@@ -222,12 +222,12 @@
#define ETH_TX_DESC_CNT 4 /* number of Ethernet Tx DMA descriptors */
#define ETH_RX_DESC_CNT 4 /* number of Ethernet Rx DMA descriptors */
#define ETH_MAC_ADDR0 ((uint8_t)0x02)
#define ETH_MAC_ADDR1 ((uint8_t)0x00)
#define ETH_MAC_ADDR2 ((uint8_t)0x00)
#define ETH_MAC_ADDR3 ((uint8_t)0x00)
#define ETH_MAC_ADDR4 ((uint8_t)0x00)
#define ETH_MAC_ADDR5 ((uint8_t)0x00)
#define ETH_MAC_ADDR0 (0x02UL)
#define ETH_MAC_ADDR1 (0x00UL)
#define ETH_MAC_ADDR2 (0x00UL)
#define ETH_MAC_ADDR3 (0x00UL)
#define ETH_MAC_ADDR4 (0x00UL)
#define ETH_MAC_ADDR5 (0x00UL)
/* ########################## Assert Selection ############################## */
/**
......@@ -277,6 +277,10 @@
#include "stm32h7xx_hal_dfsdm.h"
#endif /* HAL_DFSDM_MODULE_ENABLED */
#ifdef HAL_DTS_MODULE_ENABLED
#include "stm32h7xx_hal_dts.h"
#endif /* HAL_DTS_MODULE_ENABLED */
#ifdef HAL_ETH_MODULE_ENABLED
#include "stm32h7xx_hal_eth.h"
#endif /* HAL_ETH_MODULE_ENABLED */
......@@ -306,7 +310,7 @@
#endif /* HAL_COMP_MODULE_ENABLED */
#ifdef HAL_CORDIC_MODULE_ENABLED
#include "stm32h7xx_hal_cordic.h"
#include "stm32h7xx_hal_cordic.h"
#endif /* HAL_CORDIC_MODULE_ENABLED */
#ifdef HAL_CRC_MODULE_ENABLED
......@@ -325,14 +329,14 @@
#include "stm32h7xx_hal_flash.h"
#endif /* HAL_FLASH_MODULE_ENABLED */
#ifdef HAL_FMAC_MODULE_ENABLED
#include "stm32h7xx_hal_fmac.h"
#endif /* HAL_FMAC_MODULE_ENABLED */
#ifdef HAL_GFXMMU_MODULE_ENABLED
#include "stm32h7xx_hal_gfxmmu.h"
#endif /* HAL_GFXMMU_MODULE_ENABLED */
#ifdef HAL_FMAC_MODULE_ENABLED
#include "stm32h7xx_hal_fmac.h"
#endif /* HAL_FMAC_MODULE_ENABLED */
#ifdef HAL_HRTIM_MODULE_ENABLED
#include "stm32h7xx_hal_hrtim.h"
#endif /* HAL_HRTIM_MODULE_ENABLED */
......@@ -390,13 +394,17 @@
#endif /* HAL_OPAMP_MODULE_ENABLED */
#ifdef HAL_OSPI_MODULE_ENABLED
#include "stm32h7xx_hal_ospi.h"
#include "stm32h7xx_hal_ospi.h"
#endif /* HAL_OSPI_MODULE_ENABLED */
#ifdef HAL_OTFDEC_MODULE_ENABLED
#include "stm32h7xx_hal_otfdec.h"
#endif /* HAL_OTFDEC_MODULE_ENABLED */
#ifdef HAL_PSSI_MODULE_ENABLED
#include "stm32h7xx_hal_pssi.h"
#endif /* HAL_PSSI_MODULE_ENABLED */
#ifdef HAL_PWR_MODULE_ENABLED
#include "stm32h7xx_hal_pwr.h"
#endif /* HAL_PWR_MODULE_ENABLED */
......@@ -407,7 +415,7 @@
#ifdef HAL_RAMECC_MODULE_ENABLED
#include "stm32h7xx_hal_ramecc.h"
#endif /* HAL_HCD_MODULE_ENABLED */
#endif /* HAL_RAMECC_MODULE_ENABLED */
#ifdef HAL_RNG_MODULE_ENABLED
#include "stm32h7xx_hal_rng.h"
......@@ -477,14 +485,6 @@
#include "stm32h7xx_hal_hcd.h"
#endif /* HAL_HCD_MODULE_ENABLED */
#ifdef HAL_PSSI_MODULE_ENABLED
#include "stm32h7xx_hal_pssi.h"
#endif /* HAL_PSSI_MODULE_ENABLED */
#ifdef HAL_DTS_MODULE_ENABLED
#include "stm32h7xx_hal_dts.h"
#endif /* HAL_DTS_MODULE_ENABLED */
/* Exported macro ------------------------------------------------------------*/
#ifdef USE_FULL_ASSERT
/**
......@@ -497,7 +497,7 @@
*/
#define assert_param(expr) ((expr) ? (void)0U : assert_failed((uint8_t *)__FILE__, __LINE__))
/* Exported functions ------------------------------------------------------- */
void assert_failed(uint8_t* file, uint32_t line);
void assert_failed(uint8_t *file, uint32_t line);
#else
#define assert_param(expr) ((void)0U)
#endif /* USE_FULL_ASSERT */
......@@ -506,6 +506,6 @@
}
#endif
#endif /* __STM32H7xx_HAL_CONF_H */
#endif /* STM32H7xx_HAL_CONF_H */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
......@@ -15,6 +15,51 @@ menu "Onboard Peripheral Drivers"
select BSP_USING_UART4
default n
config BSP_USING_SPI_FLASH
bool "Enable SPI FLASH (spi1)"
select BSP_USING_SPI
select BSP_USING_SPI1
select PKG_USING_FAL
select FAL_USING_SFUD_PORT
select RT_USING_SFUD
default n
config BSP_USING_QSPI_FLASH
bool "Enable QSPI FLASH (w25q64 qspi)"
select BSP_USING_QSPI
select FAL_USING_SFUD_PORT
select RT_USING_SFUD
select RT_SFUD_USING_QSPI
default n
menuconfig BSP_USING_FS
bool "Enable filesystem"
select RT_USING_DFS
select RT_USING_DFS_ROMFS
default n
if BSP_USING_FS
config BSP_USING_SDCARD_FS
bool "Enable SDCARD filesystem"
select BSP_USING_SDIO_ARTPI
select BSP_USING_SDIO1
select RT_USING_DFS_ELMFAT
default n
config BSP_USING_SPI_FLASH_FS
bool "Enable SPI FLASH filesystem"
select BSP_USING_SPI_FLASH
select RT_USING_MTD_NOR
select PKG_USING_LITTLEFS
default n
endif
config BSP_USING_WIFI
bool "Enable wifi (AP6212)"
select ART_PI_USING_WIFI_6212_LIB
select BSP_USING_SPI_FLASH
select RT_USING_WIFI
select RT_USING_SAL
default n
endmenu
menu "On-chip Peripheral Drivers"
......@@ -116,11 +161,110 @@ menu "On-chip Peripheral Drivers"
endif
endif
menuconfig BSP_USING_SPI
bool "Enable SPI"
default n
select RT_USING_SPI
if BSP_USING_SPI
config BSP_USING_SPI1
bool "Enable SPI1"
default n
endif
config BSP_USING_QSPI
bool "Enable QSPI BUS"
select RT_USING_QSPI
select RT_USING_SPI
default n
config BSP_USING_SDRAM
bool "Enable SDRAM"
default n
config BSP_USING_WDT
bool "Enable Watchdog Timer"
select RT_USING_WDT
default n
config BSP_USING_LCD
bool "Enable LCD"
select BSP_USING_LTDC
select BSP_USING_GPIO
select BSP_USING_SDRAM
select RT_USING_MEMHEAP
default n
menuconfig BSP_USING_SDIO_ARTPI
bool "Enable SDIO"
default n
select RT_USING_SDIO
if BSP_USING_SDIO_ARTPI
config BSP_USING_SDIO1
bool "Enable SDIO1"
default n
config BSP_USING_SDIO2
bool "Enable SDIO2"
default n
endif
config BSP_USING_USBD
bool "Enable USB Device"
select RT_USING_USB_DEVICE
default n
menuconfig BSP_USING_USBH
bool "Enable USB Host"
select RT_USING_USB_HOST
default n
if BSP_USING_USBH
menuconfig RT_USBH_MSTORAGE
bool "Enable Udisk Drivers"
select RT_USING_DFS
select RT_USING_DFS_ELMFAT
default n
if RT_USBH_MSTORAGE
config UDISK_MOUNTPOINT
string "Udisk mount dir"
default "/"
endif
endif
menuconfig BSP_USING_ETH_H750
bool "Enable Ethernet"
default n
select RT_USING_LWIP
if BSP_USING_ETH_H750
config ETH_RESET_PIN
string "ETH RESET PIN"
default "PA.3"
endif
if BSP_USING_ETH_H750
choice
prompt "Choose ETH PHY"
default PHY_USING_LAN8720A
config PHY_USING_LAN8720A
bool "USING LAN8720A"
default n
endchoice
endif
config BSP_USING_LTDC
bool
default n
source "../libraries/HAL_Drivers/Kconfig"
endmenu
menu "Board extended module Drivers"
menu "External Libraries"
config ART_PI_USING_WIFI_6212_LIB
bool "Using Wifi(AP6212) Library"
select PKG_USING_EASYFLASH
select BSP_USING_SDIO_ARTPI
select BSP_USING_SDIO2
select RT_USING_LWIP
select RT_USING_WIFI
default n
endmenu
......
import os
import rtconfig
from building import *
objs = []
cwd = GetCurrentDir()
list = os.listdir(cwd)
# add the general drivers.
src = Glob('board.c')
src += Glob('CubeMX_Config/Core/Src/stm32h7xx_hal_msp.c')
if GetDepend(['BSP_USING_QSPI_FLASH']):
src += Glob('ports/drv_qspi_flash.c')
src += Glob('port/drv_qspi_flash.c')
if GetDepend('BSP_USING_SPI_LCD'):
src = src + ['ports/drv_lcd.c']
if GetDepend(['BSP_USING_SPI_LCD_ILI9488']):
src += Glob('drv_spi_ili9488.c')
if GetDepend(['BSP_USING_SPI_FLASH']):
src += Glob('port/spi_flash_init.c')
if GetDepend(['BSP_USING_FS']):
src += Glob('port/filesystem.c')
if GetDepend(['BSP_USING_SDIO_ARTPI']):
src += Glob('port/drv_sdio.c')
if GetDepend(['BSP_USING_WIFI']):
src += Glob('port/wifi_config.c')
src += Glob('port/drv_wlan.c')
if GetDepend(['BSP_USING_ETH_H750']):
src += Glob('port/drv_eth.c')
if GetDepend(['PKG_USING_EASYFLASH']):
src += Glob('port/ef_fal_port.c')
for item in list:
if os.path.isfile(os.path.join(cwd, item, 'SConscript')):
objs = objs + SConscript(os.path.join(item, 'SConscript'))
path = [cwd]
path += [cwd + '/CubeMX_Config/Core/Inc']
path += [cwd + '/port']
if rtconfig.CROSS_TOOL == 'gcc':
src += [cwd + '/../../libraries/STM32H7xx_HAL/CMSIS/Device/ST/STM32H7xx/Source/Templates/gcc/startup_stm32h750xx.s']
......@@ -22,7 +49,7 @@ elif rtconfig.CROSS_TOOL == 'keil':
src += [cwd + '/../../libraries/STM32H7xx_HAL/CMSIS/Device/ST/STM32H7xx/Source/Templates/arm/startup_stm32h750xx.s']
elif rtconfig.CROSS_TOOL == 'iar':
src += [cwd + '/../../libraries/STM32H7xx_HAL/CMSIS/Device/ST/STM32H7xx/Source/Templates/iar/startup_stm32h750xx.s']
# STM32H743xx || STM32H750xx || STM32F753xx
# You can select chips from the list above
CPPDEFINES = ['STM32H750xx']
......
/*
* linker script for STM32F4xx with GNU ld
* bernard.xiong 2009-10-14
* linker script for STM32H750XBHx with GNU ld
*/
/* Program Entry, set to mark it as "used" and avoid gc */
MEMORY
{
ROM (rx) : ORIGIN = 0x08000000, LENGTH = 128k /* 128KB flash */
RAM (rw) : ORIGIN = 0x20000000, LENGTH = 128k /* 128K DTCM */
ROM (rx) : ORIGIN =0x90000000,LENGTH =8192k
RAM (rw) : ORIGIN =0x24000000,LENGTH =512k
RxDecripSection (rw) : ORIGIN =0x30040000,LENGTH =32k
TxDecripSection (rw) : ORIGIN =0x30040060,LENGTH =32k
RxArraySection (rw) : ORIGIN =0x30040200,LENGTH =32k
}
ENTRY(Reset_Handler)
_system_stack_size = 0x200;
......@@ -40,6 +42,25 @@ SECTIONS
KEEP(*(VSymTab))
__vsymtab_end = .;
/* section information for utest */
. = ALIGN(4);
__rt_utest_tc_tab_start = .;
KEEP(*(UtestTcTab))
__rt_utest_tc_tab_end = .;
/* section information for at server */
. = ALIGN(4);
__rtatcmdtab_start = .;
KEEP(*(RtAtCmdTab))
__rtatcmdtab_end = .;
. = ALIGN(4);
/* section information for modules */
. = ALIGN(4);
__rtmsymtab_start = .;
KEEP(*(RTMSymTab))
__rtmsymtab_end = .;
/* section information for initial. */
. = ALIGN(4);
__rt_init_start = .;
......@@ -81,6 +102,7 @@ SECTIONS
*(.data.*)
*(.gnu.linkonce.d*)
PROVIDE(__dtors_start__ = .);
KEEP(*(SORT(.dtors.*)))
KEEP(*(.dtors))
......@@ -119,6 +141,33 @@ SECTIONS
} > RAM
__bss_end = .;
.RxDecripSection (NOLOAD) : ALIGN(4)
{
. = ALIGN(4);
*(.RxDecripSection)
*(.RxDecripSection.*)
. = ALIGN(4);
__RxDecripSection_free__ = .;
} > RxDecripSection
.TxDecripSection (NOLOAD) : ALIGN(4)
{
. = ALIGN(4);
*(.TxDecripSection)
*(.TxDecripSection.*)
. = ALIGN(4);
__TxDecripSection_free__ = .;
} > TxDecripSection
.RxArraySection (NOLOAD) : ALIGN(4)
{
. = ALIGN(4);
*(.RxArraySection)
*(.RxArraySection.*)
. = ALIGN(4);
__RxArraySection_free__ = .;
} > RxArraySection
_end = .;
/* Stabs debugging sections. */
......
import os
from building import *
objs = []
cwd = GetCurrentDir()
list = os.listdir(cwd)
for item in list:
if os.path.isfile(os.path.join(cwd, item, 'SConscript')):
objs = objs + SConscript(os.path.join(item, 'SConscript'))
Return('objs')
/*
* Copyright (c) 2006-2018, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
* Change Logs:
* Date Author Notes
* 2018-11-19 SummerGift first version
* 2018-12-25 zylx fix some bugs
* 2019-06-10 SummerGift optimize PHY state detection process
* 2019-09-03 xiaofan optimize link change detection process
* 2020-07-17 wanghaijing support h7
* 2020-11-30 wanghaijing add phy reset
*/
#include<rtthread.h>
#include<rtdevice.h>
#include "board.h"
#include "drv_config.h"
#ifdef BSP_USING_ETH_ARTPI
#include <netif/ethernetif.h>
#include "lwipopts.h"
#include "drv_eth.h"
/*
* Emac driver uses CubeMX tool to generate emac and phy's configuration,
* the configuration files can be found in CubeMX_Config folder.
*/
/* debug option */
#define LOG_TAG "drv.emac"
#include <drv_log.h>
#define MAX_ADDR_LEN 6
struct rt_stm32_eth
{
/* inherit from ethernet device */
struct eth_device parent;
#ifndef PHY_USING_INTERRUPT_MODE
rt_timer_t poll_link_timer;
#endif
/* interface address info, hw address */
rt_uint8_t dev_addr[MAX_ADDR_LEN];
/* ETH_Speed */
uint32_t ETH_Speed;
/* ETH_Duplex_Mode */
uint32_t ETH_Mode;
};
static ETH_HandleTypeDef EthHandle;
static ETH_TxPacketConfig TxConfig;
static struct rt_stm32_eth stm32_eth_device;
static uint8_t PHY_ADDR = 0x1F;
static rt_uint32_t reset_pin = 0;
#if defined ( __ICCARM__ ) /*!< IAR Compiler */
#pragma location=0x30040000
ETH_DMADescTypeDef DMARxDscrTab[ETH_RX_DESC_CNT]; /* Ethernet Rx DMA Descriptors */
#pragma location=0x30040060
ETH_DMADescTypeDef DMATxDscrTab[ETH_TX_DESC_CNT]; /* Ethernet Tx DMA Descriptors */
#pragma location=0x30040200
uint8_t Rx_Buff[ETH_RX_DESC_CNT][ETH_MAX_PACKET_SIZE]; /* Ethernet Receive Buffers */
#elif defined ( __CC_ARM ) /* MDK ARM Compiler */
__attribute__((at(0x30040000))) ETH_DMADescTypeDef DMARxDscrTab[ETH_RX_DESC_CNT]; /* Ethernet Rx DMA Descriptors */
__attribute__((at(0x30040060))) ETH_DMADescTypeDef DMATxDscrTab[ETH_TX_DESC_CNT]; /* Ethernet Tx DMA Descriptors */
__attribute__((at(0x30040200))) uint8_t Rx_Buff[ETH_RX_DESC_CNT][ETH_MAX_PACKET_SIZE]; /* Ethernet Receive Buffer */
#elif defined ( __GNUC__ ) /* GNU Compiler */
ETH_DMADescTypeDef DMARxDscrTab[ETH_RX_DESC_CNT] __attribute__((section(".RxDecripSection"))); /* Ethernet Rx DMA Descriptors */
ETH_DMADescTypeDef DMATxDscrTab[ETH_TX_DESC_CNT] __attribute__((section(".TxDecripSection"))); /* Ethernet Tx DMA Descriptors */
uint8_t Rx_Buff[ETH_RX_DESC_CNT][ETH_MAX_PACKET_SIZE] __attribute__((section(".RxArraySection"))); /* Ethernet Receive Buffers */
#endif
#if defined(ETH_RX_DUMP) || defined(ETH_TX_DUMP)
#define __is_print(ch) ((unsigned int)((ch) - ' ') < 127u - ' ')
static void dump_hex(const rt_uint8_t *ptr, rt_size_t buflen)
{
unsigned char *buf = (unsigned char *)ptr;
int i, j;
for (i = 0; i < buflen; i += 16)
{
rt_kprintf("%08X: ", i);
for (j = 0; j < 16; j++)
if (i + j < buflen)
rt_kprintf("%02X ", buf[i + j]);
else
rt_kprintf(" ");
rt_kprintf(" ");
for (j = 0; j < 16; j++)
if (i + j < buflen)
rt_kprintf("%c", __is_print(buf[i + j]) ? buf[i + j] : '.');
rt_kprintf("\n");
}
}
#endif
static void phy_reset(void)
{
rt_pin_write(reset_pin, PIN_LOW);
rt_thread_mdelay(50);
rt_pin_write(reset_pin, PIN_HIGH);
}
/* EMAC initialization function */
static rt_err_t rt_stm32_eth_init(rt_device_t dev)
{
ETH_MACConfigTypeDef MACConf;
uint32_t regvalue = 0;
uint8_t status = RT_EOK;
__HAL_RCC_D2SRAM3_CLK_ENABLE();
phy_reset();
/* ETHERNET Configuration */
EthHandle.Instance = ETH;
EthHandle.Init.MACAddr = (rt_uint8_t *)&stm32_eth_device.dev_addr[0];
EthHandle.Init.MediaInterface = HAL_ETH_RMII_MODE;
EthHandle.Init.TxDesc = DMATxDscrTab;
EthHandle.Init.RxDesc = DMARxDscrTab;
EthHandle.Init.RxBuffLen = ETH_MAX_PACKET_SIZE;
SCB_InvalidateDCache();
HAL_ETH_DeInit(&EthHandle);
/* configure ethernet peripheral (GPIOs, clocks, MAC, DMA) */
if (HAL_ETH_Init(&EthHandle) != HAL_OK)
{
LOG_E("eth hardware init failed");
}
else
{
LOG_D("eth hardware init success");
}
rt_memset(&TxConfig, 0, sizeof(ETH_TxPacketConfig));
TxConfig.Attributes = ETH_TX_PACKETS_FEATURES_CSUM | ETH_TX_PACKETS_FEATURES_CRCPAD;
TxConfig.ChecksumCtrl = ETH_CHECKSUM_IPHDR_PAYLOAD_INSERT_PHDR_CALC;
TxConfig.CRCPadCtrl = ETH_CRC_PAD_INSERT;
for (int idx = 0; idx < ETH_RX_DESC_CNT; idx++)
{
HAL_ETH_DescAssignMemory(&EthHandle, idx, &Rx_Buff[idx][0], NULL);
}
HAL_ETH_SetMDIOClockRange(&EthHandle);
for(int i = 0; i <= PHY_ADDR; i ++)
{
if(HAL_ETH_ReadPHYRegister(&EthHandle, i, PHY_SPECIAL_MODES_REG, &regvalue) != HAL_OK)
{
status = RT_ERROR;
/* Can't read from this device address continue with next address */
continue;
}
if((regvalue & PHY_BASIC_STATUS_REG) == i)
{
PHY_ADDR = i;
status = RT_EOK;
LOG_D("Found a phy, address:0x%02X", PHY_ADDR);
break;
}
}
if(HAL_ETH_WritePHYRegister(&EthHandle, PHY_ADDR, PHY_BASIC_CONTROL_REG, PHY_RESET_MASK) == HAL_OK)
{
HAL_ETH_ReadPHYRegister(&EthHandle, PHY_ADDR, PHY_SPECIAL_MODES_REG, &regvalue);
uint32_t tickstart = rt_tick_get();
/* wait until software reset is done or timeout occured */
while(regvalue & PHY_RESET_MASK)
{
if((rt_tick_get() - tickstart) <= 500)
{
if(HAL_ETH_ReadPHYRegister(&EthHandle, PHY_ADDR, PHY_BASIC_CONTROL_REG, &regvalue) != HAL_OK)
{
status = RT_ERROR;
break;
}
}
else
{
status = RT_ETIMEOUT;
}
}
}
rt_thread_delay(2000);
if(HAL_ETH_ReadPHYRegister(&EthHandle, PHY_ADDR, PHY_BASIC_CONTROL_REG, &regvalue) == HAL_OK)
{
regvalue |= PHY_AUTO_NEGOTIATION_MASK;
HAL_ETH_WritePHYRegister(&EthHandle, PHY_ADDR, PHY_BASIC_CONTROL_REG, regvalue);
eth_device_linkchange(&stm32_eth_device.parent, RT_TRUE);
HAL_ETH_GetMACConfig(&EthHandle, &MACConf);
MACConf.DuplexMode = ETH_FULLDUPLEX_MODE;
MACConf.Speed = ETH_SPEED_100M;
HAL_ETH_SetMACConfig(&EthHandle, &MACConf);
HAL_ETH_Start_IT(&EthHandle);
}
else
{
status = RT_ERROR;
}
return status;
}
static rt_err_t rt_stm32_eth_open(rt_device_t dev, rt_uint16_t oflag)
{
LOG_D("emac open");
return RT_EOK;
}
static rt_err_t rt_stm32_eth_close(rt_device_t dev)
{
LOG_D("emac close");
return RT_EOK;
}
static rt_size_t rt_stm32_eth_read(rt_device_t dev, rt_off_t pos, void *buffer, rt_size_t size)
{
LOG_D("emac read");
rt_set_errno(-RT_ENOSYS);
return 0;
}
static rt_size_t rt_stm32_eth_write(rt_device_t dev, rt_off_t pos, const void *buffer, rt_size_t size)
{
LOG_D("emac write");
rt_set_errno(-RT_ENOSYS);
return 0;
}
static rt_err_t rt_stm32_eth_control(rt_device_t dev, int cmd, void *args)
{
switch (cmd)
{
case NIOCTL_GADDR:
/* get mac address */
if (args) rt_memcpy(args, stm32_eth_device.dev_addr, 6);
else return -RT_ERROR;
break;
default :
break;
}
return RT_EOK;
}
/* ethernet device interface */
/* transmit data*/
rt_err_t rt_stm32_eth_tx(rt_device_t dev, struct pbuf *p)
{
rt_err_t ret = RT_ERROR;
HAL_StatusTypeDef state;
uint32_t i = 0, framelen = 0;
struct pbuf *q;
ETH_BufferTypeDef Txbuffer[ETH_TX_DESC_CNT];
rt_memset(Txbuffer, 0, ETH_TX_DESC_CNT * sizeof(ETH_BufferTypeDef));
for (q = p; q != NULL; q = q->next)
{
if (i >= ETH_TX_DESC_CNT)
return ERR_IF;
Txbuffer[i].buffer = q->payload;
Txbuffer[i].len = q->len;
framelen += q->len;
if (i > 0)
{
Txbuffer[i - 1].next = &Txbuffer[i];
}
if (q->next == NULL)
{
Txbuffer[i].next = NULL;
}
i++;
}
TxConfig.Length = framelen;
TxConfig.TxBuffer = Txbuffer;
#ifdef ETH_TX_DUMP
rt_kprintf("Tx dump, len= %d\r\n", framelen);
dump_hex(&Txbuffer[0]);
#endif
if (stm32_eth_device.parent.link_status)
{
SCB_CleanInvalidateDCache();
state = HAL_ETH_Transmit(&EthHandle, &TxConfig, 1000);
if (state != HAL_OK)
{
LOG_W("eth transmit frame faild: %d", EthHandle.ErrorCode);
EthHandle.ErrorCode = HAL_ETH_STATE_READY;
EthHandle.gState = HAL_ETH_STATE_READY;
}
}
else
{
LOG_E("eth transmit frame faild, netif not up");
}
ret = ERR_OK;
return ret;
}
/* receive data*/
struct pbuf *rt_stm32_eth_rx(rt_device_t dev)
{
uint32_t framelength = 0;
rt_uint16_t l;
struct pbuf *p = RT_NULL, *q;
ETH_BufferTypeDef RxBuff;
uint32_t alignedAddr;
if(HAL_ETH_GetRxDataBuffer(&EthHandle, &RxBuff) == HAL_OK)
{
HAL_ETH_GetRxDataLength(&EthHandle, &framelength);
/* Build Rx descriptor to be ready for next data reception */
HAL_ETH_BuildRxDescriptors(&EthHandle);
/* Invalidate data cache for ETH Rx Buffers */
alignedAddr = (uint32_t)RxBuff.buffer & ~0x1F;
SCB_InvalidateDCache_by_Addr((uint32_t *)alignedAddr, (uint32_t)RxBuff.buffer - alignedAddr + framelength);
p = pbuf_alloc(PBUF_RAW, framelength, PBUF_RAM);
if (p != NULL)
{
for (q = p, l = 0; q != NULL; q = q->next)
{
memcpy((rt_uint8_t *)q->payload, (rt_uint8_t *)&RxBuff.buffer[l], q->len);
l = l + q->len;
}
}
}
return p;
}
/* interrupt service routine */
void ETH_IRQHandler(void)
{
/* enter interrupt */
rt_interrupt_enter();
HAL_ETH_IRQHandler(&EthHandle);
/* leave interrupt */
rt_interrupt_leave();
}
void HAL_ETH_RxCpltCallback(ETH_HandleTypeDef *heth)
{
rt_err_t result;
result = eth_device_ready(&(stm32_eth_device.parent));
if (result != RT_EOK)
LOG_I("RxCpltCallback err = %d", result);
}
void HAL_ETH_ErrorCallback(ETH_HandleTypeDef *heth)
{
LOG_E("eth err");
}
enum
{
PHY_LINK = (1 << 0),
PHY_100M = (1 << 1),
PHY_FULL_DUPLEX = (1 << 2),
};
static void phy_linkchange()
{
static rt_uint8_t phy_speed = 0;
rt_uint8_t phy_speed_new = 0;
rt_uint32_t status;
HAL_ETH_ReadPHYRegister(&EthHandle, PHY_ADDR, PHY_BASIC_STATUS_REG, (uint32_t *)&status);
LOG_D("phy basic status reg is 0x%X", status);
if (status & (PHY_AUTONEGO_COMPLETE_MASK | PHY_LINKED_STATUS_MASK))
{
rt_uint32_t SR = 0;
phy_speed_new |= PHY_LINK;
HAL_ETH_ReadPHYRegister(&EthHandle, PHY_ADDR, PHY_Status_REG, (uint32_t *)&SR);
LOG_D("phy control status reg is 0x%X", SR);
if (PHY_Status_SPEED_100M(SR))
{
phy_speed_new |= PHY_100M;
}
if (PHY_Status_FULL_DUPLEX(SR))
{
phy_speed_new |= PHY_FULL_DUPLEX;
}
}
if (phy_speed != phy_speed_new)
{
phy_speed = phy_speed_new;
if (phy_speed & PHY_LINK)
{
LOG_D("link up");
if (phy_speed & PHY_100M)
{
LOG_D("100Mbps");
stm32_eth_device.ETH_Speed = ETH_SPEED_100M;
}
else
{
stm32_eth_device.ETH_Speed = ETH_SPEED_10M;
LOG_D("10Mbps");
}
if (phy_speed & PHY_FULL_DUPLEX)
{
LOG_D("full-duplex");
stm32_eth_device.ETH_Mode = ETH_FULLDUPLEX_MODE;
}
else
{
LOG_D("half-duplex");
stm32_eth_device.ETH_Mode = ETH_HALFDUPLEX_MODE;
}
/* send link up. */
eth_device_linkchange(&stm32_eth_device.parent, RT_TRUE);
}
else
{
LOG_I("link down");
eth_device_linkchange(&stm32_eth_device.parent, RT_FALSE);
}
}
}
#ifdef PHY_USING_INTERRUPT_MODE
static void eth_phy_isr(void *args)
{
rt_uint32_t status = 0;
HAL_ETH_ReadPHYRegister(&EthHandle, PHY_ADDR, PHY_INTERRUPT_FLAG_REG, (uint32_t *)&status);
LOG_D("phy interrupt status reg is 0x%X", status);
phy_linkchange();
}
#endif /* PHY_USING_INTERRUPT_MODE */
static void phy_monitor_thread_entry(void *parameter)
{
phy_linkchange();
#ifdef PHY_USING_INTERRUPT_MODE
/* configuration intterrupt pin */
rt_pin_mode(PHY_INT_PIN, PIN_MODE_INPUT_PULLUP);
rt_pin_attach_irq(PHY_INT_PIN, PIN_IRQ_MODE_FALLING, eth_phy_isr, (void *)"callbackargs");
rt_pin_irq_enable(PHY_INT_PIN, PIN_IRQ_ENABLE);
/* enable phy interrupt */
HAL_ETH_WritePHYRegister(&EthHandle, PHY_ADDR, PHY_INTERRUPT_MASK_REG, PHY_INT_MASK);
#if defined(PHY_INTERRUPT_CTRL_REG)
HAL_ETH_WritePHYRegister(&EthHandle, PHY_ADDR, PHY_INTERRUPT_CTRL_REG, PHY_INTERRUPT_EN);
#endif
#else /* PHY_USING_INTERRUPT_MODE */
stm32_eth_device.poll_link_timer = rt_timer_create("phylnk", (void (*)(void*))phy_linkchange,
NULL, RT_TICK_PER_SECOND, RT_TIMER_FLAG_PERIODIC);
if (!stm32_eth_device.poll_link_timer || rt_timer_start(stm32_eth_device.poll_link_timer) != RT_EOK)
{
LOG_E("Start link change detection timer failed");
}
#endif /* PHY_USING_INTERRUPT_MODE */
}
/* Register the EMAC device */
static int rt_hw_stm32_eth_init(void)
{
rt_err_t state = RT_EOK;
reset_pin = rt_pin_get(ETH_RESET_PIN);
rt_pin_mode(reset_pin, PIN_MODE_OUTPUT);
rt_pin_write(reset_pin, PIN_HIGH);
stm32_eth_device.ETH_Speed = ETH_SPEED_100M;
stm32_eth_device.ETH_Mode = ETH_FULLDUPLEX_MODE;
/* OUI 00-80-E1 STMICROELECTRONICS. */
stm32_eth_device.dev_addr[0] = 0x00;
stm32_eth_device.dev_addr[1] = 0x80;
stm32_eth_device.dev_addr[2] = 0xE1;
/* generate MAC addr from 96bit unique ID (only for test). */
stm32_eth_device.dev_addr[3] = *(rt_uint8_t *)(UID_BASE + 4);
stm32_eth_device.dev_addr[4] = *(rt_uint8_t *)(UID_BASE + 2);
stm32_eth_device.dev_addr[5] = *(rt_uint8_t *)(UID_BASE + 0);
stm32_eth_device.parent.parent.init = rt_stm32_eth_init;
stm32_eth_device.parent.parent.open = rt_stm32_eth_open;
stm32_eth_device.parent.parent.close = rt_stm32_eth_close;
stm32_eth_device.parent.parent.read = rt_stm32_eth_read;
stm32_eth_device.parent.parent.write = rt_stm32_eth_write;
stm32_eth_device.parent.parent.control = rt_stm32_eth_control;
stm32_eth_device.parent.parent.user_data = RT_NULL;
stm32_eth_device.parent.eth_rx = rt_stm32_eth_rx;
stm32_eth_device.parent.eth_tx = rt_stm32_eth_tx;
/* register eth device */
state = eth_device_init(&(stm32_eth_device.parent), "e0");
if (RT_EOK == state)
{
LOG_D("emac device init success");
}
else
{
LOG_E("emac device init faild: %d", state);
state = -RT_ERROR;
}
/* start phy monitor */
rt_thread_t tid;
tid = rt_thread_create("phy",
phy_monitor_thread_entry,
RT_NULL,
1024,
RT_THREAD_PRIORITY_MAX - 2,
2);
if (tid != RT_NULL)
{
rt_thread_startup(tid);
}
else
{
state = -RT_ERROR;
}
return state;
}
INIT_DEVICE_EXPORT(rt_hw_stm32_eth_init);
#endif /* BSP_USING_ETH_ARTPI */
/*
* Copyright (c) 2006-2018, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
* Change Logs:
* Date Author Notes
* 2018-12-25 zylx first version
* 2020-07-18 wanghaijing add SPECIAL_MODES_REG
*/
#ifndef __DRV_ETH_H__
#define __DRV_ETH_H__
#include <rtthread.h>
#include <rthw.h>
#include <rtdevice.h>
#include <board.h>
/* The PHY basic control register */
#define PHY_BASIC_CONTROL_REG 0x00U
#define PHY_RESET_MASK (1<<15)
#define PHY_AUTO_NEGOTIATION_MASK (1<<12)
/* The PHY basic status register */
#define PHY_BASIC_STATUS_REG 0x01U
#define PHY_LINKED_STATUS_MASK (1<<2)
#define PHY_AUTONEGO_COMPLETE_MASK (1<<5)
/* The PHY ID one register */
#define PHY_ID1_REG 0x02U
/* The PHY ID two register */
#define PHY_ID2_REG 0x03U
/* The PHY SPECIAL MODES REGISTER */
#define PHY_SPECIAL_MODES_REG 0x12U
/* The PHY auto-negotiate advertise register */
#define PHY_AUTONEG_ADVERTISE_REG 0x04U
#define PHY_Status_REG 0x1FU
#define PHY_FULL_DUPLEX_MASK (1<<4)
#define PHY_Status_SPEED_10M(sr) ((sr) & PHY_10M_MASK)
#define PHY_Status_SPEED_100M(sr) ((sr) & PHY_100M_MASK)
#define PHY_Status_FULL_DUPLEX(sr) ((sr) & PHY_FULL_DUPLEX_MASK)
#ifdef PHY_USING_LAN8720A
/* The PHY interrupt source flag register. */
#define PHY_INTERRUPT_FLAG_REG 0x1DU
/* The PHY interrupt mask register. */
#define PHY_INTERRUPT_MASK_REG 0x1EU
#define PHY_LINK_DOWN_MASK (1<<4)
#define PHY_AUTO_NEGO_COMPLETE_MASK (1<<6)
/* The PHY status register. */
#define PHY_Status_REG 0x1FU
#define PHY_10M_MASK (1<<2)
#define PHY_100M_MASK (1<<3)
#define PHY_FULL_DUPLEX_MASK (1<<4)
#endif /* PHY_USING_LAN8720A */
#ifdef PHY_USING_DM9161CEP
#define PHY_Status_REG 0x11U
#define PHY_10M_MASK ((1<<12) || (1<<13))
#define PHY_100M_MASK ((1<<14) || (1<<15))
#define PHY_FULL_DUPLEX_MASK ((1<<15) || (1<<13))
/* The PHY interrupt source flag register. */
#define PHY_INTERRUPT_FLAG_REG 0x15U
/* The PHY interrupt mask register. */
#define PHY_INTERRUPT_MASK_REG 0x15U
#define PHY_LINK_CHANGE_FLAG (1<<2)
#define PHY_LINK_CHANGE_MASK (1<<9)
#define PHY_INT_MASK 0
#endif /* PHY_USING_DM9161CEP */
#ifdef PHY_USING_DP83848C
#define PHY_Status_REG 0x10U
#define PHY_10M_MASK (1<<1)
#define PHY_FULL_DUPLEX_MASK (1<<2)
#define PHY_Status_SPEED_10M(sr) ((sr) & PHY_10M_MASK)
#define PHY_Status_SPEED_100M(sr) (!PHY_Status_SPEED_10M(sr))
#define PHY_Status_FULL_DUPLEX(sr) ((sr) & PHY_FULL_DUPLEX_MASK)
#define PHY_INTERRUPT_FLAG_REG 0x12U
#define PHY_LINK_CHANGE_FLAG (1<<13)
#define PHY_INTERRUPT_CTRL_REG 0x11U
#define PHY_INTERRUPT_EN ((1<<0)|(1<<1))
#define PHY_INTERRUPT_MASK_REG 0x12U
#define PHY_INT_MASK (1<<5)
#endif /* PHY_USING_DP83848C */
#endif /* __DRV_ETH_H__ */
/*
* Copyright (c) 2006-2020, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
* Change Logs:
* Date Author Notes
* 2020-05-23 liuduanfei first version
*/
#include "board.h"
#ifdef RT_USING_SDIO
#if !defined(BSP_USING_SDIO1) && !defined(BSP_USING_SDIO2)
#error "Please define at least one BSP_USING_SDIOx"
#endif
#include "drv_sdio.h"
#define DBG_TAG "drv.sdio"
#ifdef DRV_DEBUG
#define DBG_LVL DBG_LOG
#else
#define DBG_LVL DBG_INFO
#endif /* DRV_DEBUG */
#include <rtdbg.h>
static struct rt_mmcsd_host *host1;
static struct rt_mmcsd_host *host2;
static rt_mutex_t mmcsd_mutex = RT_NULL;
#define SDIO_TX_RX_COMPLETE_TIMEOUT_LOOPS (1000000)
struct sdio_pkg
{
struct rt_mmcsd_cmd *cmd;
void *buff;
rt_uint32_t flag;
};
struct rthw_sdio
{
struct rt_mmcsd_host *host;
struct stm32_sdio_des sdio_des;
struct rt_event event;
struct sdio_pkg *pkg;
};
ALIGN(SDIO_ALIGN_LEN)
static rt_uint8_t cache_buf[SDIO_BUFF_SIZE];
/**
* @brief This function get order from sdio.
* @param data
* @retval sdio order
*/
static int get_order(rt_uint32_t data)
{
int order = 0;
switch (data)
{
case 1:
order = 0;
break;
case 2:
order = 1;
break;
case 4:
order = 2;
break;
case 8:
order = 3;
break;
case 16:
order = 4;
break;
case 32:
order = 5;
break;
case 64:
order = 6;
break;
case 128:
order = 7;
break;
case 256:
order = 8;
break;
case 512:
order = 9;
break;
case 1024:
order = 10;
break;
case 2048:
order = 11;
break;
case 4096:
order = 12;
break;
case 8192:
order = 13;
break;
case 16384:
order = 14;
break;
default :
order = 0;
break;
}
return order;
}
/**
* @brief This function wait sdio cmd completed.
* @param sdio rthw_sdio
* @retval None
*/
static void rthw_sdio_wait_completed(struct rthw_sdio *sdio)
{
rt_uint32_t status;
struct rt_mmcsd_cmd *cmd = sdio->pkg->cmd;
struct stm32_sdio *hw_sdio = sdio->sdio_des.hw_sdio;
if (rt_event_recv(&sdio->event, 0xffffffff, RT_EVENT_FLAG_OR | RT_EVENT_FLAG_CLEAR,
rt_tick_from_millisecond(5000), &status) != RT_EOK)
{
LOG_E("wait cmd completed timeout");
cmd->err = -RT_ETIMEOUT;
return;
}
cmd->resp[0] = hw_sdio->resp1;
if (resp_type(cmd) == RESP_R2)
{
cmd->resp[1] = hw_sdio->resp2;
cmd->resp[2] = hw_sdio->resp3;
cmd->resp[3] = hw_sdio->resp4;
}
if (status & SDIO_ERRORS)
{
if ((status & SDMMC_STA_CCRCFAIL) && (resp_type(cmd) & (RESP_R3 | RESP_R4)))
{
cmd->err = RT_EOK;
}
else
{
cmd->err = -RT_ERROR;
}
}
else
{
cmd->err = RT_EOK;
}
if (cmd->err == RT_EOK)
{
LOG_D("sta:0x%08X [%08X %08X %08X %08X]", status, cmd->resp[0], cmd->resp[1], cmd->resp[2], cmd->resp[3]);
}
else
{
LOG_D("send command error = %d", cmd->err);
}
}
/**
* @brief This function send command.
* @param sdio rthw_sdio
* @param pkg sdio package
* @retval None
*/
static void rthw_sdio_send_command(struct rthw_sdio *sdio, struct sdio_pkg *pkg)
{
struct rt_mmcsd_cmd *cmd = pkg->cmd;
struct rt_mmcsd_data *data = cmd->data;
struct stm32_sdio *hw_sdio = sdio->sdio_des.hw_sdio;
rt_uint32_t reg_cmd;
rt_event_control(&sdio->event, RT_IPC_CMD_RESET, RT_NULL);
/* save pkg */
sdio->pkg = pkg;
LOG_D("CMD:%d ARG:0x%08x RES:%s%s%s%s%s%s%s%s%s rw:%c len:%d blksize:%d\n",
cmd->cmd_code,
cmd->arg,
resp_type(cmd) == RESP_NONE ? "NONE" : "",
resp_type(cmd) == RESP_R1 ? "R1" : "",
resp_type(cmd) == RESP_R1B ? "R1B" : "",
resp_type(cmd) == RESP_R2 ? "R2" : "",
resp_type(cmd) == RESP_R3 ? "R3" : "",
resp_type(cmd) == RESP_R4 ? "R4" : "",
resp_type(cmd) == RESP_R5 ? "R5" : "",
resp_type(cmd) == RESP_R6 ? "R6" : "",
resp_type(cmd) == RESP_R7 ? "R7" : "",
data ? (data->flags & DATA_DIR_WRITE ? 'w' : 'r') : '-',
data ? data->blks * data->blksize : 0,
data ? data->blksize : 0
);
hw_sdio->mask |= SDIO_MASKR_ALL;
reg_cmd = cmd->cmd_code | SDMMC_CMD_CPSMEN;
/* data pre configuration */
if (data != RT_NULL)
{
SCB_CleanInvalidateDCache();
reg_cmd |= SDMMC_CMD_CMDTRANS;
hw_sdio->mask &= ~(SDMMC_MASK_CMDRENDIE | SDMMC_MASK_CMDSENTIE);
hw_sdio->dtimer = HW_SDIO_DATATIMEOUT;
hw_sdio->dlen = data->blks * data->blksize;
hw_sdio->dctrl = (get_order(data->blksize) << 4) | (data->flags & DATA_DIR_READ ? SDMMC_DCTRL_DTDIR : 0);
hw_sdio->idmabase0r = (rt_uint32_t)cache_buf;
hw_sdio->idmatrlr = SDMMC_IDMA_IDMAEN;
}
if (resp_type(cmd) == RESP_R2)
reg_cmd |= SDMMC_CMD_WAITRESP;
else if(resp_type(cmd) != RESP_NONE)
reg_cmd |= SDMMC_CMD_WAITRESP_0;
hw_sdio->arg = cmd->arg;
hw_sdio->cmd = reg_cmd;
/* wait completed */
rthw_sdio_wait_completed(sdio);
/* Waiting for data to be sent to completion */
if (data != RT_NULL)
{
volatile rt_uint32_t count = SDIO_TX_RX_COMPLETE_TIMEOUT_LOOPS;
while (count && (hw_sdio->sta & SDMMC_STA_DPSMACT))
{
count--;
}
if ((count == 0) || (hw_sdio->sta & SDIO_ERRORS))
{
cmd->err = -RT_ERROR;
}
}
/* data post configuration */
if (data != RT_NULL)
{
if (data->flags & DATA_DIR_READ)
{
rt_memcpy(data->buf, cache_buf, data->blks * data->blksize);
SCB_CleanInvalidateDCache();
}
}
}
/**
* @brief This function send sdio request.
* @param sdio rthw_sdio
* @param req request
* @retval None
*/
static void rthw_sdio_request(struct rt_mmcsd_host *host, struct rt_mmcsd_req *req)
{
struct sdio_pkg pkg;
struct rthw_sdio *sdio = host->private_data;
struct rt_mmcsd_data *data;
rt_mutex_take(mmcsd_mutex, RT_WAITING_FOREVER);
if (req->cmd != RT_NULL)
{
rt_memset(&pkg, 0, sizeof(pkg));
data = req->cmd->data;
pkg.cmd = req->cmd;
if (data != RT_NULL)
{
rt_uint32_t size = data->blks * data->blksize;
RT_ASSERT(size <= SDIO_BUFF_SIZE);
if (data->flags & DATA_DIR_WRITE)
{
rt_memcpy(cache_buf, data->buf, size);
}
}
rthw_sdio_send_command(sdio, &pkg);
}
if (req->stop != RT_NULL)
{
rt_memset(&pkg, 0, sizeof(pkg));
pkg.cmd = req->stop;
rthw_sdio_send_command(sdio, &pkg);
}
mmcsd_req_complete(sdio->host);
rt_mutex_release(mmcsd_mutex);
}
/**
* @brief This function interrupt process function.
* @param host rt_mmcsd_host
* @retval None
*/
void rthw_sdio_irq_process(struct rt_mmcsd_host *host)
{
struct rthw_sdio *sdio = host->private_data;
struct stm32_sdio *hw_sdio = sdio->sdio_des.hw_sdio;
rt_uint32_t intstatus = hw_sdio->sta;
/* clear irq flag*/
hw_sdio->icr = intstatus;
rt_event_send(&sdio->event, intstatus);
}
/**
* @brief This function config sdio.
* @param host rt_mmcsd_host
* @param io_cfg rt_mmcsd_io_cfg
* @retval None
*/
static void rthw_sdio_iocfg(struct rt_mmcsd_host *host, struct rt_mmcsd_io_cfg *io_cfg)
{
rt_uint32_t temp, clk_src;
rt_uint32_t clk = io_cfg->clock;
struct rthw_sdio *sdio = host->private_data;
struct stm32_sdio *hw_sdio = sdio->sdio_des.hw_sdio;
LOG_D("clk:%dK width:%s%s%s power:%s%s%s",
clk / 1000,
io_cfg->bus_width == MMCSD_BUS_WIDTH_8 ? "8" : "",
io_cfg->bus_width == MMCSD_BUS_WIDTH_4 ? "4" : "",
io_cfg->bus_width == MMCSD_BUS_WIDTH_1 ? "1" : "",
io_cfg->power_mode == MMCSD_POWER_OFF ? "OFF" : "",
io_cfg->power_mode == MMCSD_POWER_UP ? "UP" : "",
io_cfg->power_mode == MMCSD_POWER_ON ? "ON" : ""
);
clk_src = SDIO_CLOCK_FREQ;
if (clk > 0)
{
if (clk > host->freq_max)
clk = host->freq_max;
temp = DIV_ROUND_UP(clk_src, 2 * clk);
if (temp > 0x3FF)
temp = 0x3FF;
}
if (io_cfg->bus_width == MMCSD_BUS_WIDTH_4)
temp |= SDMMC_CLKCR_WIDBUS_0;
else if (io_cfg->bus_width == MMCSD_BUS_WIDTH_8)
temp |= SDMMC_CLKCR_WIDBUS_1;
hw_sdio->clkcr = temp;
if (io_cfg->power_mode == MMCSD_POWER_ON)
hw_sdio->power |= SDMMC_POWER_PWRCTRL;
}
static const struct rt_mmcsd_host_ops ops =
{
rthw_sdio_request,
rthw_sdio_iocfg,
RT_NULL,
RT_NULL,
};
/**
* @brief This function create mmcsd host.
* @param sdio_des stm32_sdio_des
* @retval rt_mmcsd_host
*/
struct rt_mmcsd_host *sdio_host_create(struct stm32_sdio_des *sdio_des)
{
struct rt_mmcsd_host *host;
struct rthw_sdio *sdio = RT_NULL;
if (sdio_des == RT_NULL)
{
return RT_NULL;
}
sdio = rt_malloc(sizeof(struct rthw_sdio));
if (sdio == RT_NULL)
{
LOG_E("malloc rthw_sdio fail");
return RT_NULL;
}
rt_memset(sdio, 0, sizeof(struct rthw_sdio));
host = mmcsd_alloc_host();
if (host == RT_NULL)
{
LOG_E("alloc host fail");
goto err;
}
rt_memcpy(&sdio->sdio_des, sdio_des, sizeof(struct stm32_sdio_des));
if(sdio_des->hsd.Instance == SDMMC1)
{
sdio->sdio_des.hw_sdio = (struct stm32_sdio *)SDIO1_BASE_ADDRESS;
rt_event_init(&sdio->event, "sdio", RT_IPC_FLAG_FIFO);
}
if(sdio_des->hsd.Instance == SDMMC2)
{
sdio->sdio_des.hw_sdio = (struct stm32_sdio *)SDIO2_BASE_ADDRESS;
rt_event_init(&sdio->event, "sdio2", RT_IPC_FLAG_FIFO);
}
/* set host default attributes */
host->ops = &ops;
host->freq_min = 400 * 1000;
host->freq_max = SDIO_MAX_FREQ;
host->valid_ocr = VDD_32_33 | VDD_33_34;/* The voltage range supported is 3.2v-3.4v */
host->flags = MMCSD_BUSWIDTH_4 | MMCSD_MUTBLKWRITE | MMCSD_SUP_HIGHSPEED;
host->max_seg_size = SDIO_BUFF_SIZE;
host->max_dma_segs = 1;
host->max_blk_size = 512;
host->max_blk_count = 512;
/* link up host and sdio */
sdio->host = host;
host->private_data = sdio;
return host;
err:
if (sdio) rt_free(sdio);
return RT_NULL;
}
void SDMMC1_IRQHandler(void)
{
/* enter interrupt */
rt_interrupt_enter();
/* Process All SDIO Interrupt Sources */
rthw_sdio_irq_process(host1);
/* leave interrupt */
rt_interrupt_leave();
}
void SDMMC2_IRQHandler(void)
{
/* enter interrupt */
rt_interrupt_enter();
/* Process All SDIO Interrupt Sources */
rthw_sdio_irq_process(host2);
/* leave interrupt */
rt_interrupt_leave();
}
int rt_hw_sdio_init(void)
{
#ifdef BSP_USING_SDIO1
struct stm32_sdio_des sdio_des1;
sdio_des1.hsd.Instance = SDMMC1;
HAL_SD_MspInit(&sdio_des1.hsd);
host1 = sdio_host_create(&sdio_des1);
if (host1 == RT_NULL)
{
LOG_E("host create fail");
return RT_NULL;
}
#endif
#ifdef BSP_USING_SDIO2
//sdmmc2 wifi
struct stm32_sdio_des sdio_des2;
sdio_des2.hsd.Instance = SDMMC2;
HAL_SD_MspInit(&sdio_des2.hsd);
host2 = sdio_host_create(&sdio_des2);
if (host2 == RT_NULL)
{
LOG_E("host2 create fail");
return RT_NULL;
}
/* wifi auto change */
mmcsd_change(host2);
#endif
mmcsd_mutex = rt_mutex_create("mmutex", RT_IPC_FLAG_FIFO);
if (mmcsd_mutex == RT_NULL)
{
rt_kprintf("create mmcsd mutex failed.\n");
return -1;
}
return 0;
}
INIT_DEVICE_EXPORT(rt_hw_sdio_init);
void sdcard_change(void)
{
mmcsd_change(host1);
}
#endif /* RT_USING_SDIO */
\ No newline at end of file
/*
* Copyright (c) 2006-2020, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
* Change Logs:
* Date Author Notes
* 2020-05-23 liuduanfei first version
* 2020-08-25 wanghaijing add sdmmmc2
*/
#ifndef __DRV_SDIO_H__
#define __DRV_SDIO_H__
#include <rtthread.h>
#include "rtdevice.h"
#include <rthw.h>
#include <drv_common.h>
#include <string.h>
#include <drivers/mmcsd_core.h>
#include <drivers/sdio.h>
#define SDIO_BUFF_SIZE 4096
#define SDIO_ALIGN_LEN 32
#ifndef SDIO1_BASE_ADDRESS
#define SDIO1_BASE_ADDRESS (0x52007000)
#endif
#ifndef SDIO2_BASE_ADDRESS
#define SDIO2_BASE_ADDRESS (0x48022400)
#endif
#ifndef SDIO_CLOCK_FREQ
#define SDIO_CLOCK_FREQ (200U * 1000 * 1000)
#endif
#ifndef SDIO_BUFF_SIZE
#define SDIO_BUFF_SIZE (4096)
#endif
#ifndef SDIO_ALIGN_LEN
#define SDIO_ALIGN_LEN (32)
#endif
#ifndef SDIO_MAX_FREQ
#define SDIO_MAX_FREQ (25 * 1000 * 1000)
#endif
#define DIV_ROUND_UP(n,d) (((n) + (d) - 1) / (d))
#define SDIO_ERRORS \
(SDMMC_STA_IDMATE | SDMMC_STA_ACKTIMEOUT | \
SDMMC_STA_RXOVERR | SDMMC_STA_TXUNDERR | \
SDMMC_STA_DTIMEOUT | SDMMC_STA_CTIMEOUT | \
SDMMC_STA_DCRCFAIL | SDMMC_STA_CCRCFAIL)
#define SDIO_MASKR_ALL \
(SDMMC_MASK_CCRCFAILIE | SDMMC_MASK_DCRCFAILIE | SDMMC_MASK_CTIMEOUTIE | \
SDMMC_MASK_TXUNDERRIE | SDMMC_MASK_RXOVERRIE | SDMMC_MASK_CMDRENDIE | \
SDMMC_MASK_CMDSENTIE | SDMMC_MASK_DATAENDIE | SDMMC_MASK_ACKTIMEOUTIE)
#define HW_SDIO_DATATIMEOUT (0xFFFFFFFFU)
struct stm32_sdio
{
volatile rt_uint32_t power; /* offset 0x00 */
volatile rt_uint32_t clkcr; /* offset 0x04 */
volatile rt_uint32_t arg; /* offset 0x08 */
volatile rt_uint32_t cmd; /* offset 0x0C */
volatile rt_uint32_t respcmd; /* offset 0x10 */
volatile rt_uint32_t resp1; /* offset 0x14 */
volatile rt_uint32_t resp2; /* offset 0x18 */
volatile rt_uint32_t resp3; /* offset 0x1C */
volatile rt_uint32_t resp4; /* offset 0x20 */
volatile rt_uint32_t dtimer; /* offset 0x24 */
volatile rt_uint32_t dlen; /* offset 0x28 */
volatile rt_uint32_t dctrl; /* offset 0x2C */
volatile rt_uint32_t dcount; /* offset 0x30 */
volatile rt_uint32_t sta; /* offset 0x34 */
volatile rt_uint32_t icr; /* offset 0x38 */
volatile rt_uint32_t mask; /* offset 0x3C */
volatile rt_uint32_t acktimer; /* offset 0x40 */
volatile rt_uint32_t reserved0[3]; /* offset 0x44 ~ 0x4C */
volatile rt_uint32_t idmatrlr; /* offset 0x50 */
volatile rt_uint32_t idmabsizer; /* offset 0x54 */
volatile rt_uint32_t idmabase0r; /* offset 0x58 */
volatile rt_uint32_t idmabase1r; /* offset 0x5C */
volatile rt_uint32_t reserved1[8]; /* offset 0x60 ~ 7C */
volatile rt_uint32_t fifo; /* offset 0x80 */
};
typedef rt_uint32_t (*sdio_clk_get)(struct stm32_sdio *hw_sdio);
struct stm32_sdio_des
{
struct stm32_sdio *hw_sdio;
sdio_clk_get clk_get;
SD_HandleTypeDef hsd;
};
/* stm32 sdio dirver class */
struct stm32_sdio_class
{
struct stm32_sdio_des *des;
const struct stm32_sdio_config *cfg;
struct rt_mmcsd_host host;
};
extern void sdcard_change(void);
#endif /* __DRV_SDIO_H__ */
/*
* File : drv_wlan.c
* This file is part of RT-Thread RTOS
* COPYRIGHT (C) 2015, RT-Thread Development Team
*
* The license and distribution terms for this file may be
* found in the file LICENSE in this distribution or at
* http://www.rt-thread.org/license/LICENSE
*
* Change Logs:
* Date Author Notes
* 2018-08-30 ZeroFree the first version
*/
#include <rtthread.h>
#include <rtdevice.h>
#ifdef RT_USING_WIFI
#include <drv_common.h>
#include <wlan_mgnt.h>
#include <wlan_prot.h>
#include <wlan_cfg.h>
#include <string.h>
#include <fal.h>
#define DBG_ENABLE
#define DBG_SECTION_NAME "WLAN"
#define DBG_COLOR
#define DBG_LEVEL DBG_LOG
#include <rtdbg.h>
#define NVRAM_GENERATED_MAC_ADDRESS "macaddr=02:0A:F7:fe:86:1c"
#define WIFI_IMAGE_PARTITION_NAME "wifi_image"
#define WIFI_INIT_THREAD_STACK_SIZE (1024 * 4)
#define WIFI_INIT_THREAD_PRIORITY (RT_THREAD_PRIORITY_MAX/2)
#define WIFI_INIT_WAIT_TIME (rt_tick_from_millisecond(1000))
extern int wifi_hw_init(void);
static rt_bool_t init_flag = 0;
static const struct fal_partition *partition = RT_NULL;
ALIGN(64)
static const char wifi_nvram_image[] =
// # The following parameter values are just placeholders, need to be updated.
"manfid=0x2d0" "\x00"
"prodid=0x0726" "\x00"
"vendid=0x14e4" "\x00"
"devid=0x43e2" "\x00"
"boardtype=0x0726" "\x00"
"boardrev=0x1101" "\x00"
"boardnum=22" "\x00"
"xtalfreq=26000" "\x00"
"sromrev=11" "\x00"
"boardflags=0x00404201" "\x00"
"boardflags3=0x08000000" "\x00"
NVRAM_GENERATED_MAC_ADDRESS "\x00"
"nocrc=1" "\x00"
"ag0=255" "\x00"
"aa2g=1" "\x00"
"ccode=ALL"
"\x00"
"swdiv_en=1" "\x00"
"swdiv_gpio=2" "\x00"
"pa0itssit=0x20" "\x00"
"extpagain2g=0" "\x00"
"pa2ga0=-215,5267,-656" "\x00"
"AvVmid_c0=0x0,0xc8" "\x00"
"cckpwroffset0=5" "\x00"
"maxp2ga0=80" "\x00"
"txpwrbckof=6" "\x00"
"cckbw202gpo=0x6666" "\x00"
"legofdmbw202gpo=0xaaaaaaaa" "\x00"
"mcsbw202gpo=0xbbbbbbbb" "\x00"
"propbw202gpo=0xdd" "\x00"
"ofdmdigfilttype=18" "\x00"
"ofdmdigfilttypebe=18" "\x00"
"papdmode=1" "\x00"
"papdvalidtest=1" "\x00"
"pacalidx2g=32" "\x00"
"papdepsoffset=-36" "\x00"
"papdendidx=61" "\x00"
"wl0id=0x431b" "\x00"
"deadman_to=0xffffffff" "\x00"
"muxenab=0x11" "\x00"
"spurconfig=0x3" "\x00"
"\x00\x00";
int wiced_platform_resource_size(int resource)
{
int size = 0;
/* Download firmware */
if (resource == 0)
{
size = 355159;
}
else if (resource == 1)
{
size = sizeof(wifi_nvram_image);
}
return size;
}
int wiced_platform_resource_read(int resource, uint32_t offset, void* buffer, uint32_t buffer_size)
{
if (resource == 0)
{
/* read RF firmware from partition */
fal_partition_read(partition, offset, buffer, buffer_size);
}
else if (resource == 1)
{
memcpy(buffer, &wifi_nvram_image[offset], buffer_size);
}
return buffer_size;
}
/**
* wait milliseconds for wifi low level initialize complete
*
* time_ms: timeout in milliseconds
*/
int rt_hw_wlan_wait_init_done(rt_uint32_t time_ms)
{
rt_uint32_t time_cnt = 0;
/* wait wifi low level initialize complete */
while (time_cnt <= (time_ms / 100))
{
time_cnt++;
rt_thread_mdelay(100);
if (init_flag == 1)
{
break;
}
}
if (time_cnt > (time_ms / 100))
{
return -RT_ETIMEOUT;
}
return RT_EOK;
}
static void wifi_init_thread_entry(void *parameter)
{
/* initialize fal */
fal_init();
partition = fal_partition_find(WIFI_IMAGE_PARTITION_NAME);
if (partition == RT_NULL)
{
LOG_E("%s partition is not exist, please check your configuration!", WIFI_IMAGE_PARTITION_NAME);
return;
}
/* initialize low level wifi(ap6212) library */
wifi_hw_init();
/* waiting for sdio bus stability */
rt_thread_delay(WIFI_INIT_WAIT_TIME);
/* set wifi work mode */
rt_wlan_set_mode(RT_WLAN_DEVICE_STA_NAME, RT_WLAN_STATION);
/* NEED TODO !!! */
/* rt_wlan_set_mode(RT_WLAN_DEVICE_AP_NAME, RT_WLAN_AP); */
init_flag = 1;
}
int rt_hw_wlan_init(void)
{
if (init_flag == 1)
{
return RT_EOK;
}
rt_thread_t tid = RT_NULL;
tid = rt_thread_create("wifi_init", wifi_init_thread_entry, RT_NULL, WIFI_INIT_THREAD_STACK_SIZE, WIFI_INIT_THREAD_PRIORITY, 20);
if (tid)
{
rt_thread_startup(tid);
}
else
{
LOG_E("Create wifi initialization thread fail!");
return -RT_ERROR;
}
return RT_EOK;
}
INIT_APP_EXPORT(rt_hw_wlan_init);
static int ap6212_init(void)
{
#define AP6212_WL_REG_ON GET_PIN(C, 13)
/* enable the WLAN REG pin */
rt_pin_mode(AP6212_WL_REG_ON, PIN_MODE_OUTPUT);
rt_pin_write(AP6212_WL_REG_ON, PIN_HIGH);
return 0;
}
INIT_DEVICE_EXPORT(ap6212_init);
#endif /* RT_USING_WIFI */
/*
* This file is part of the EasyFlash Library.
*
* Copyright (c) 2015, Armink, <armink.ztl@gmail.com>
*
* Permission is hereby granted, free of charge, to any person obtaining
* a copy of this software and associated documentation files (the
* 'Software'), to deal in the Software without restriction, including
* without limitation the rights to use, copy, modify, merge, publish,
* distribute, sublicense, and/or sell copies of the Software, and to
* permit persons to whom the Software is furnished to do so, subject to
* the following conditions:
*
* The above copyright notice and this permission notice shall be
* included in all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED 'AS IS', WITHOUT WARRANTY OF ANY KIND,
* EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT.
* IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY
* CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT,
* TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE
* SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
*
* Function: Portable interface for FAL (Flash Abstraction Layer) partition.
* Created on: 2018-05-19
*/
#include <easyflash.h>
#include <stdio.h>
#include <stdlib.h>
#include <stdarg.h>
#include <sfud.h>
#include <rthw.h>
#include <rtthread.h>
#include <fal.h>
/* EasyFlash partition name on FAL partition table */
#define FAL_EF_PART_NAME "easyflash"
/* default ENV set for user */
static const ef_env default_env_set[] = {
{"boot_times", "0"}
};
static char log_buf[RT_CONSOLEBUF_SIZE];
static struct rt_semaphore env_cache_lock;
static const struct fal_partition *part = NULL;
/**
* Flash port for hardware initialize.
*
* @param default_env default ENV set for user
* @param default_env_size default ENV size
*
* @return result
*/
EfErrCode ef_port_init(ef_env const **default_env, size_t *default_env_size) {
EfErrCode result = EF_NO_ERR;
*default_env = default_env_set;
*default_env_size = sizeof(default_env_set) / sizeof(default_env_set[0]);
rt_sem_init(&env_cache_lock, "env lock", 1, RT_IPC_FLAG_PRIO);
part = fal_partition_find(FAL_EF_PART_NAME);
EF_ASSERT(part);
return result;
}
/**
* Read data from flash.
* @note This operation's units is word.
*
* @param addr flash address
* @param buf buffer to store read data
* @param size read bytes size
*
* @return result
*/
EfErrCode ef_port_read(uint32_t addr, uint32_t *buf, size_t size) {
EfErrCode result = EF_NO_ERR;
fal_partition_read(part, addr, (uint8_t *)buf, size);
return result;
}
/**
* Erase data on flash.
* @note This operation is irreversible.
* @note This operation's units is different which on many chips.
*
* @param addr flash address
* @param size erase bytes size
*
* @return result
*/
EfErrCode ef_port_erase(uint32_t addr, size_t size) {
EfErrCode result = EF_NO_ERR;
/* make sure the start address is a multiple of FLASH_ERASE_MIN_SIZE */
EF_ASSERT(addr % EF_ERASE_MIN_SIZE == 0);
if (fal_partition_erase(part, addr, size) < 0)
{
result = EF_ERASE_ERR;
}
return result;
}
/**
* Write data to flash.
* @note This operation's units is word.
* @note This operation must after erase. @see flash_erase.
*
* @param addr flash address
* @param buf the write data buffer
* @param size write bytes size
*
* @return result
*/
EfErrCode ef_port_write(uint32_t addr, const uint32_t *buf, size_t size) {
EfErrCode result = EF_NO_ERR;
if (fal_partition_write(part, addr, (uint8_t *)buf, size) < 0)
{
result = EF_WRITE_ERR;
}
return result;
}
/**
* lock the ENV ram cache
*/
void ef_port_env_lock(void) {
rt_sem_take(&env_cache_lock, RT_WAITING_FOREVER);
}
/**
* unlock the ENV ram cache
*/
void ef_port_env_unlock(void) {
rt_sem_release(&env_cache_lock);
}
/**
* This function is print flash debug info.
*
* @param file the file which has call this function
* @param line the line number which has call this function
* @param format output format
* @param ... args
*
*/
void ef_log_debug(const char *file, const long line, const char *format, ...) {
#ifdef PRINT_DEBUG
va_list args;
/* args point to the first variable parameter */
va_start(args, format);
ef_print("[Flash] (%s:%ld) ", file, line);
/* must use vprintf to print */
rt_vsprintf(log_buf, format, args);
ef_print("%s", log_buf);
va_end(args);
#endif
}
/**
* This function is print flash routine info.
*
* @param format output format
* @param ... args
*/
void ef_log_info(const char *format, ...) {
va_list args;
/* args point to the first variable parameter */
va_start(args, format);
ef_print("[Flash] ");
/* must use vprintf to print */
rt_vsprintf(log_buf, format, args);
ef_print("%s", log_buf);
va_end(args);
}
/**
* This function is print flash non-package info.
*
* @param format output format
* @param ... args
*/
void ef_print(const char *format, ...) {
va_list args;
/* args point to the first variable parameter */
va_start(args, format);
/* must use vprintf to print */
rt_vsprintf(log_buf, format, args);
rt_kprintf("%s", log_buf);
va_end(args);
}
/*
* File : fal_cfg.h
* This file is part of FAL (Flash Abstraction Layer) package
* COPYRIGHT (C) 2006 - 2018, RT-Thread Development Team
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA.
*
* Change Logs:
* Date Author Notes
* 2018-05-17 armink the first version
*/
#ifndef _FAL_CFG_H_
#define _FAL_CFG_H_
#include <rtconfig.h>
#include <board.h>
#define NOR_FLASH_DEV_NAME "norflash0"
/* ===================== Flash device Configuration ========================= */
extern struct fal_flash_dev nor_flash0;
/* flash device table */
#define FAL_FLASH_DEV_TABLE \
{ \
&nor_flash0, \
}
/* ====================== Partition Configuration ========================== */
#ifdef FAL_PART_HAS_TABLE_CFG
/* partition table */
#define FAL_PART_TABLE \
{ \
{FAL_PART_MAGIC_WORD, "wifi_image", NOR_FLASH_DEV_NAME, 0, 512*1024, 0}, \
{FAL_PART_MAGIC_WORD, "bt_image", NOR_FLASH_DEV_NAME, 512*1024, 512*1024, 0}, \
{FAL_PART_MAGIC_WORD, "download", NOR_FLASH_DEV_NAME, 1024*1024, 2*1024*1024, 0}, \
{FAL_PART_MAGIC_WORD, "easyflash", NOR_FLASH_DEV_NAME, 3*1024*1024, 1*1024*1024, 0}, \
{FAL_PART_MAGIC_WORD, "filesystem", NOR_FLASH_DEV_NAME, 4*1024*1024, 12*1024*1024, 0}, \
}
#endif /* FAL_PART_HAS_TABLE_CFG */
#endif /* _FAL_CFG_H_ */
/*
* Copyright (c) 2006-2018, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
* Change Logs:
* Date Author Notes
* 2018-12-13 balanceTWK add sdcard port file
* 2019-06-11 WillianChan Add SD card hot plug detection
*/
#include <rtthread.h>
#ifdef BSP_USING_FS
#if DFS_FILESYSTEMS_MAX < 4
#error "Please define DFS_FILESYSTEMS_MAX more than 4"
#endif
#if DFS_FILESYSTEM_TYPES_MAX < 4
#error "Please define DFS_FILESYSTEM_TYPES_MAX more than 4"
#endif
#include <dfs_fs.h>
#include "dfs_romfs.h"
#ifdef BSP_USING_SDCARD_FS
#include <board.h>
#include "drv_sdio.h"
#endif
#ifdef BSP_USING_SPI_FLASH_FS
#include "fal.h"
#endif
#define DBG_TAG "app.filesystem"
#define DBG_LVL DBG_INFO
#include <rtdbg.h>
static const struct romfs_dirent _romfs_root[] =
{
{ROMFS_DIRENT_DIR, "flash", RT_NULL, 0},
{ROMFS_DIRENT_DIR, "sdcard", RT_NULL, 0}
};
const struct romfs_dirent romfs_root =
{
ROMFS_DIRENT_DIR, "/", (rt_uint8_t *)_romfs_root, sizeof(_romfs_root) / sizeof(_romfs_root[0])
};
#ifdef BSP_USING_SDCARD_FS
/* SD Card hot plug detection pin */
#define SD_CHECK_PIN GET_PIN(D, 5)
static void _sdcard_mount(void)
{
rt_device_t device;
device = rt_device_find("sd0");
if (device == NULL)
{
mmcsd_wait_cd_changed(0);
sdcard_change();
mmcsd_wait_cd_changed(RT_WAITING_FOREVER);
device = rt_device_find("sd0");
}
if (device != RT_NULL)
{
if (dfs_mount("sd0", "/sdcard", "elm", 0, 0) == RT_EOK)
{
LOG_I("sd card mount to '/sdcard'");
}
else
{
LOG_W("sd card mount to '/sdcard' failed!");
}
}
}
static void _sdcard_unmount(void)
{
rt_thread_mdelay(200);
dfs_unmount("/sdcard");
LOG_I("Unmount \"/sdcard\"");
mmcsd_wait_cd_changed(0);
sdcard_change();
mmcsd_wait_cd_changed(RT_WAITING_FOREVER);
}
static void sd_mount(void *parameter)
{
rt_uint8_t re_sd_check_pin = 1;
rt_thread_mdelay(200);
if (rt_pin_read(SD_CHECK_PIN))
{
_sdcard_mount();
}
while (1)
{
rt_thread_mdelay(200);
if (!re_sd_check_pin && (re_sd_check_pin = rt_pin_read(SD_CHECK_PIN)) != 0)
{
_sdcard_mount();
}
if (re_sd_check_pin && (re_sd_check_pin = rt_pin_read(SD_CHECK_PIN)) == 0)
{
_sdcard_unmount();
}
}
}
#endif /* BSP_USING_SDCARD_FS */
int mount_init(void)
{
if (dfs_mount(RT_NULL, "/", "rom", 0, &(romfs_root)) != 0)
{
LOG_E("rom mount to '/' failed!");
}
#ifdef BSP_USING_SPI_FLASH_FS
struct rt_device *flash_dev = RT_NULL;
#ifndef RT_USING_WIFI
fal_init();
#endif
flash_dev = fal_mtd_nor_device_create("filesystem");
if (flash_dev)
{
//mount filesystem
if (dfs_mount(flash_dev->parent.name, "/flash", "lfs", 0, 0) != 0)
{
LOG_W("mount to '/flash' failed! try to mkfs %s", flash_dev->parent.name);
dfs_mkfs("lfs", flash_dev->parent.name);
if (dfs_mount(flash_dev->parent.name, "/flash", "lfs", 0, 0) == 0)
{
LOG_I("mount to '/flash' success!");
}
}
else
{
LOG_I("mount to '/flash' success!");
}
}
else
{
LOG_E("Can't create block device filesystem or bt_image partition.");
}
#endif
#ifdef BSP_USING_SDCARD_FS
rt_thread_t tid;
rt_pin_mode(SD_CHECK_PIN, PIN_MODE_INPUT_PULLUP);
tid = rt_thread_create("sd_mount", sd_mount, RT_NULL,
2048, RT_THREAD_PRIORITY_MAX - 2, 20);
if (tid != RT_NULL)
{
rt_thread_startup(tid);
}
else
{
LOG_E("create sd_mount thread err!");
}
#endif
return RT_EOK;
}
INIT_APP_EXPORT(mount_init);
#endif /* BSP_USING_FS */
/*
* Copyright (c) 2006-2018, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
* Change Logs:
* Date Author Notes
* 2019-01-08 zylx first version
*/
#ifndef __LCD_PORT_H__
#define __LCD_PORT_H__
/* atk 4.3 inch screen, 800 * 480 */
#define LCD_WIDTH 800
#define LCD_HEIGHT 480
#define LCD_BITS_PER_PIXEL 16
#define LCD_BUF_SIZE (LCD_WIDTH * LCD_HEIGHT * LCD_BITS_PER_PIXEL / 8)
#define LCD_PIXEL_FORMAT RTGRAPHIC_PIXEL_FORMAT_RGB565
#define LCD_HSYNC_WIDTH 1
#define LCD_VSYNC_HEIGHT 1
#define LCD_HBP 40
#define LCD_VBP 32
#define LCD_HFP 48
#define LCD_VFP 13
#define LCD_BACKLIGHT_USING_GPIO
#define LCD_BL_GPIO_NUM GET_PIN(D, 4)
#define LCD_DISP_GPIO_NUM GET_PIN(B, 5)
/* atk 4.3 inch screen, 800 * 480 */
#endif /* __LCD_PORT_H__ */
/*
* Copyright (c) 2006-2018, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
* Change Logs:
* Date Author Notes
* 2020-08-10 zylx first version
*/
#ifndef __LCD_PORT_H__
#define __LCD_PORT_H__
/* rt-thread 3.5 inch screen, 320 * 480 */
#define LCD_HOR_SCREEN
#define LCD_FULL_COLOR BLACK
#ifndef LCD_FULL_COLOR
#define LCD_FULL_COLOR WHITE
#endif
#ifndef LCD_HOR_SCREEN
#define LCD_WIDTH 320
#define LCD_HEIGHT 480
#else
#define LCD_WIDTH 480
#define LCD_HEIGHT 320
#endif
#define LCD_BITS_PER_PIXEL 24
#define LCD_BYTES_PER_PIXEL (LCD_BITS_PER_PIXEL / 8)
#define LCD_BUF_SIZE (LCD_WIDTH * LCD_HEIGHT * LCD_BYTES_PER_PIXEL)
#define LCD_PIXEL_FORMAT RTGRAPHIC_PIXEL_FORMAT_RGB888
#define LCD_BACKLIGHT_USING_GPIO
#define LCD_BL_PIN GET_PIN(C, 6)
#define LCD_RES_PIN GET_PIN(A, 3)
/* rt-thread 3.5 inch screen, 320 * 480 */
#endif /* __LCD_PORT_H__ */
/*
* Copyright (c) 2006-2018, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
* Change Logs:
* Date Author Notes
* 2018-12-04 zylx The first version for STM32F4xx
*/
#ifndef __SDRAM_PORT_H__
#define __SDRAM_PORT_H__
/* parameters for sdram peripheral */
/* Bank1 or Bank2 */
#define SDRAM_TARGET_BANK 1
/* stm32h7 Bank1:0XC0000000 Bank2:0XD0000000 */
#define SDRAM_BANK_ADDR ((uint32_t)0XC0000000)
/* data width: 8, 16, 32 */
#define SDRAM_DATA_WIDTH 16
/* column bit numbers: 8, 9, 10, 11 */
#define SDRAM_COLUMN_BITS 9
/* row bit numbers: 11, 12, 13 */
#define SDRAM_ROW_BITS 13
/* cas latency clock number: 1, 2, 3 */
#define SDRAM_CAS_LATENCY 2
/* read pipe delay: 0, 1, 2 */
#define SDRAM_RPIPE_DELAY 0
/* clock divid: 2, 3 */
#define SDCLOCK_PERIOD 2
/* refresh rate counter */
#define SDRAM_REFRESH_COUNT ((uint32_t)0x02A5)
#define SDRAM_SIZE ((uint32_t)0x2000000)
/* Timing configuration for W9825G6KH-6 */
/* 100 MHz of HCKL3 clock frequency (200MHz/2) */
/* TMRD: 2 Clock cycles */
#define LOADTOACTIVEDELAY 2
/* TXSR: 8x10ns */
#define EXITSELFREFRESHDELAY 8
/* TRAS: 5x10ns */
#define SELFREFRESHTIME 6
/* TRC: 7x10ns */
#define ROWCYCLEDELAY 6
/* TWR: 2 Clock cycles */
#define WRITERECOVERYTIME 2
/* TRP: 2x10ns */
#define RPDELAY 2
/* TRCD: 2x10ns */
#define RCDDELAY 2
/* memory mode register */
#define SDRAM_MODEREG_BURST_LENGTH_1 ((uint16_t)0x0000)
#define SDRAM_MODEREG_BURST_LENGTH_2 ((uint16_t)0x0001)
#define SDRAM_MODEREG_BURST_LENGTH_4 ((uint16_t)0x0002)
#define SDRAM_MODEREG_BURST_LENGTH_8 ((uint16_t)0x0004)
#define SDRAM_MODEREG_BURST_TYPE_SEQUENTIAL ((uint16_t)0x0000)
#define SDRAM_MODEREG_BURST_TYPE_INTERLEAVED ((uint16_t)0x0008)
#define SDRAM_MODEREG_CAS_LATENCY_2 ((uint16_t)0x0020)
#define SDRAM_MODEREG_CAS_LATENCY_3 ((uint16_t)0x0030)
#define SDRAM_MODEREG_OPERATING_MODE_STANDARD ((uint16_t)0x0000)
#define SDRAM_MODEREG_WRITEBURST_MODE_PROGRAMMED ((uint16_t)0x0000)
#define SDRAM_MODEREG_WRITEBURST_MODE_SINGLE ((uint16_t)0x0200)
#endif
/*
* Copyright (c) 2006-2018, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
* Change Logs:
* Date Author Notes
* 2020-11-07 wanghaijing the first version
*/
#include <rtthread.h>
#include <rtdevice.h>
#include <spi_flash.h>
#include <drv_spi.h>
static int rt_flash_init(void)
{
extern rt_spi_flash_device_t rt_sfud_flash_probe(const char *spi_flash_dev_name, const char *spi_dev_name);
extern int fal_init(void);
rt_hw_spi_device_attach("spi1", "spi10", GPIOA, GPIO_PIN_4);
/* initialize SPI Flash device */
rt_sfud_flash_probe("norflash0", "spi10");
fal_init();
return 0;
}
INIT_ENV_EXPORT(rt_flash_init);
/*
* File : wifi_config.c
* This file is part of RT-Thread RTOS
* COPYRIGHT (C) 2006 - 2018, RT-Thread Development Team
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA.
*
* Change Logs:
* Date Author Notes
* 2018-09-04 ZeroFree first implementation
* 2019-06-14 armink add easyflash v4.0 support
*/
#include <rtthread.h>
#ifdef BSP_USING_WIFI
#include <wlan_mgnt.h>
#include <wlan_cfg.h>
#include <wlan_prot.h>
#include <easyflash.h>
#include <fal.h>
#include <stdio.h>
#include <stdlib.h>
#if (EF_SW_VERSION_NUM < 0x40000)
static char *str_base64_encode_len(const void *src, char *out, int input_length);
static int str_base64_decode(const char *data, int input_length, char *decoded_data);
static const unsigned char base64_table[65] =
"ABCDEFGHIJKLMNOPQRSTUVWXYZabcdefghijklmnopqrstuvwxyz0123456789+/";
static const char base64_decode_table[256] =
{
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x3E, 0x00, 0x00, 0x00, 0x3F,
0x34, 0x35, 0x36, 0x37, 0x38, 0x39, 0x3A, 0x3B, 0x3C, 0x3D, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
0x00, 0x00, 0x01, 0x02, 0x03, 0x04, 0x05, 0x06, 0x07, 0x08, 0x09, 0x0A, 0x0B, 0x0C, 0x0D, 0x0E,
0x0F, 0x10, 0x11, 0x12, 0x13, 0x14, 0x15, 0x16, 0x17, 0x18, 0x19, 0x00, 0x00, 0x00, 0x00, 0x00,
0x00, 0x1A, 0x1B, 0x1C, 0x1D, 0x1E, 0x1F, 0x20, 0x21, 0x22, 0x23, 0x24, 0x25, 0x26, 0x27, 0x28,
0x29, 0x2A, 0x2B, 0x2C, 0x2D, 0x2E, 0x2F, 0x30, 0x31, 0x32, 0x33, 0x00, 0x00, 0x00, 0x00, 0x00,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
};
static char *str_base64_encode_len(const void *src, char *out, int len)
{
unsigned char *pos;
const unsigned char *end, *in;
size_t olen;
olen = len * 4 / 3 + 4; /* 3-byte blocks to 4-byte */
olen += olen / 72; /* line feeds */
olen++; /* nul termination */
end = (const unsigned char *)src + len;
in = (const unsigned char *)src;
pos = (unsigned char *)out;
while (end - in >= 3)
{
*pos++ = base64_table[in[0] >> 2];
*pos++ = base64_table[((in[0] & 0x03) << 4) | (in[1] >> 4)];
*pos++ = base64_table[((in[1] & 0x0f) << 2) | (in[2] >> 6)];
*pos++ = base64_table[in[2] & 0x3f];
in += 3;
}
if (end - in)
{
*pos++ = base64_table[in[0] >> 2];
if (end - in == 1)
{
*pos++ = base64_table[(in[0] & 0x03) << 4];
*pos++ = '=';
}
else
{
*pos++ = base64_table[((in[0] & 0x03) << 4) |
(in[1] >> 4)];
*pos++ = base64_table[(in[1] & 0x0f) << 2];
}
*pos++ = '=';
}
*pos = '\0';
return (char *)out;
}
/*
* return: length, 0 is error.
*/
static int str_base64_decode(const char *data, int input_length, char *decoded_data)
{
int out_len;
int i, j;
if (input_length % 4 != 0) return 0;
out_len = input_length / 4 * 3;
if (data[input_length - 1] == '=') out_len--;
if (data[input_length - 2] == '=') out_len--;
for (i = 0, j = 0; i < input_length;)
{
uint32_t sextet_a = data[i] == '=' ? 0 & i++ : base64_decode_table[data[i++]];
uint32_t sextet_b = data[i] == '=' ? 0 & i++ : base64_decode_table[data[i++]];
uint32_t sextet_c = data[i] == '=' ? 0 & i++ : base64_decode_table[data[i++]];
uint32_t sextet_d = data[i] == '=' ? 0 & i++ : base64_decode_table[data[i++]];
uint32_t triple = (sextet_a << 3 * 6)
+ (sextet_b << 2 * 6)
+ (sextet_c << 1 * 6)
+ (sextet_d << 0 * 6);
if (j < out_len) decoded_data[j++] = (triple >> 2 * 8) & 0xFF;
if (j < out_len) decoded_data[j++] = (triple >> 1 * 8) & 0xFF;
if (j < out_len) decoded_data[j++] = (triple >> 0 * 8) & 0xFF;
}
return out_len;
}
static int read_cfg(void *buff, int len)
{
char *wlan_cfg_info = RT_NULL;
wlan_cfg_info = ef_get_env("wlan_cfg_info");
if (wlan_cfg_info != RT_NULL)
{
str_base64_decode(wlan_cfg_info, rt_strlen(wlan_cfg_info), buff);
return len;
}
else
{
return 0;
}
}
static int get_len(void)
{
int len;
char *wlan_cfg_len = RT_NULL;
wlan_cfg_len = ef_get_env("wlan_cfg_len");
if (wlan_cfg_len == RT_NULL)
{
len = 0;
}
else
{
len = atoi(wlan_cfg_len);
}
return len;
}
static int write_cfg(void *buff, int len)
{
char wlan_cfg_len[12] = {0};
char *base64_buf = RT_NULL;
base64_buf = rt_malloc(len * 4 / 3 + 4); /* 3-byte blocks to 4-byte, and the end. */
if (base64_buf == RT_NULL)
{
return -RT_ENOMEM;
}
rt_memset(base64_buf, 0, len);
/* interger to string */
sprintf(wlan_cfg_len, "%d", len);
/* set and store the wlan config lengths to Env */
ef_set_env("wlan_cfg_len", wlan_cfg_len);
str_base64_encode_len(buff, base64_buf, len);
/* set and store the wlan config information to Env */
ef_set_env("wlan_cfg_info", base64_buf);
ef_save_env();
rt_free(base64_buf);
return len;
}
#else
static int read_cfg(void *buff, int len)
{
size_t saved_len;
ef_get_env_blob("wlan_cfg_info", buff, len, &saved_len);
if (saved_len == 0)
{
return 0;
}
return len;
}
static int get_len(void)
{
int len;
size_t saved_len;
ef_get_env_blob("wlan_cfg_len", &len, sizeof(len), &saved_len);
if (saved_len == 0)
{
return 0;
}
return len;
}
static int write_cfg(void *buff, int len)
{
/* set and store the wlan config lengths to Env */
ef_set_env_blob("wlan_cfg_len", &len, sizeof(len));
/* set and store the wlan config information to Env */
ef_set_env_blob("wlan_cfg_info", buff, len);
return len;
}
#endif /* (EF_SW_VERSION_NUM < 0x40000) */
static const struct rt_wlan_cfg_ops ops =
{
read_cfg,
get_len,
write_cfg
};
void wlan_autoconnect_init(void)
{
fal_init();
easyflash_init();
rt_wlan_cfg_set_ops(&ops);
rt_wlan_cfg_cache_refresh();
}
#endif
\ No newline at end of file
Import('rtconfig')
from building import *
cwd = GetCurrentDir()
LIBS = []
LIBPATH = []
src = []
LIBPATH = [cwd]
if rtconfig.CROSS_TOOL == 'gcc':
LIBS += ['wifi_6212_armcm7_2.1.2_gcc']
elif rtconfig.CROSS_TOOL == 'keil':
LIBS += ['libwifi_6212_armcm7_2.1.2_armcc']
path = [cwd]
group = DefineGroup('WICED', src, depend = ['ART_PI_USING_WIFI_6212_LIB'], CPPPATH = path, LIBS = LIBS, LIBPATH = LIBPATH)
Return('group')
Markdown is supported
0% .
You are about to add 0 people to the discussion. Proceed with caution.
先完成此消息的编辑!
想要评论请 注册