Initial commit

This commit is contained in:
ChesterTseng 2017-10-15 14:36:37 +08:00
commit 6f665866d6
3358 changed files with 1106791 additions and 0 deletions

View file

@ -0,0 +1,30 @@
/*
* Routines to access hardware
*
* Copyright (c) 2013 Realtek Semiconductor Corp.
*
* This module is a confidential and proprietary property of RealTek and
* possession or use of this module requires written permission of RealTek.
*/
#ifndef _AMEBA_SOC_H_
#define _AMEBA_SOC_H_
/* rom headers */
#include "rtl8710b.h"
#ifndef CONFIG_BUILD_ROM
/* ram headers */
#include "platform_opts.h"
#include "rtl_consol_ram.h"
#include "rtl8710b_ota.h"
#ifdef PLATFORM_FREERTOS
#include "freertos_pmu.h"
#include "rtl8710b_freertos_pmu.h"
#include "FreeRTOS.h"
#include "task.h"
#include "semphr.h"
#endif
#endif
#endif //_AMEBA_SOC_H_

View file

@ -0,0 +1,501 @@
/******************************************************************************
*
* Copyright(c) 2007 - 2011 Realtek Corporation. All rights reserved.
*
* This program is free software; you can redistribute it and/or modify it
* under the terms of version 2 of the GNU General Public License as
* published by the Free Software Foundation.
*
* 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, USA
*
*
******************************************************************************/
#ifndef __BASIC_TYPES_H__
#define __BASIC_TYPES_H__
//#define PLATFORM_FREERTOS
#include <stdint.h>
#define PLATFORM_LITTLE_ENDIAN 0
#define PLATFORM_BIG_ENDIAN 1
#define SYSTEM_ENDIAN PLATFORM_LITTLE_ENDIAN
#define SUCCESS 0
#define FAIL (-1)
#undef _SUCCESS
#define _SUCCESS 1
#undef _FAIL
#define _FAIL 0
#ifndef FALSE
#define FALSE 0
#endif
#ifndef TRUE
#define TRUE (!FALSE)
#endif
#define _TRUE TRUE
#define _FALSE FALSE
#ifndef NULL
#define NULL 0
#endif
#ifdef __GNUC__
#define __weak __attribute__((weak))
#define likely(x) __builtin_expect ((x), 1)
#define unlikely(x) __builtin_expect ((x), 0)
#endif
typedef unsigned int uint;
typedef signed int sint;
#ifdef __ICCARM__
typedef signed long long __int64_t;
typedef unsigned long long __uint64_t;
#endif
#define s8 int8_t
#define u8 uint8_t
#define s16 int16_t
#define u16 uint16_t
#define s32 int32_t
#define u32 uint32_t
#define s64 int64_t
#define u64 uint64_t
#ifdef CONFIG_MBED_ENABLED
typedef unsigned int BOOL;
#else
#ifndef BOOL
typedef unsigned char BOOL;
#endif
#ifndef bool
typedef unsigned char bool;
#endif
#endif
#define UCHAR uint8_t
#define USHORT uint16_t
#define UINT uint32_t
#define ULONG uint32_t
typedef struct { volatile int counter; } atomic_t;
typedef enum _RTK_STATUS_ {
_EXIT_SUCCESS = 0,
_EXIT_FAILURE = 1
}RTK_STATUS, *PRTK_STATUS;
#define IN
#define OUT
#define VOID void
#define INOUT
#define NDIS_OID uint
#define NDIS_STATUS uint
#ifndef PVOID
typedef void * PVOID;
#endif
typedef u32 dma_addr_t;
typedef void (*proc_t)(void*);
typedef unsigned int __kernel_size_t;
typedef int __kernel_ssize_t;
typedef __kernel_size_t SIZE_T;
typedef __kernel_ssize_t SSIZE_T;
#define FIELD_OFFSET(s,field) ((SSIZE_T)&((s*)(0))->field)
#define MEM_ALIGNMENT_OFFSET (sizeof (SIZE_T))
#define MEM_ALIGNMENT_PADDING (sizeof(SIZE_T) - 1)
#define SIZE_PTR SIZE_T
#define SSIZE_PTR SSIZE_T
#ifndef ON
#define ON 1
#endif
#ifndef OFF
#define OFF 0
#endif
#ifndef ENABLE
#define ENABLE 1
#endif
#ifndef DISABLE
#define DISABLE 0
#endif
#define BIT0 0x0001
#define BIT1 0x0002
#define BIT2 0x0004
#define BIT3 0x0008
#define BIT4 0x0010
#define BIT5 0x0020
#define BIT6 0x0040
#define BIT7 0x0080
#define BIT8 0x0100
#define BIT9 0x0200
#define BIT10 0x0400
#define BIT11 0x0800
#define BIT12 0x1000
#define BIT13 0x2000
#define BIT14 0x4000
#define BIT15 0x8000
#define BIT16 0x00010000
#define BIT17 0x00020000
#define BIT18 0x00040000
#define BIT19 0x00080000
#define BIT20 0x00100000
#define BIT21 0x00200000
#define BIT22 0x00400000
#define BIT23 0x00800000
#define BIT24 0x01000000
#define BIT25 0x02000000
#define BIT26 0x04000000
#define BIT27 0x08000000
#define BIT28 0x10000000
#define BIT29 0x20000000
#define BIT30 0x40000000
#define BIT31 0x80000000
#define BIT_(__n) (1<<(__n))
#ifndef BIT
#define BIT(__n) (1<<(__n))
#endif
#if defined (__ICCARM__)
#define STRINGIFY(s) #s
#define SECTION(_name) _Pragma( STRINGIFY(location=_name))
#define ALIGNMTO(_bound) _Pragma( STRINGIFY(data_alignment=_bound))
#define _PACKED_ __packed
#define _LONG_CALL_
#define _WEAK __weak
#define _OPTIMIZE_NONE_ _Pragma( STRINGIFY(optimize=none))
#else
#define SECTION(_name) __attribute__ ((__section__(_name)))
#define ALIGNMTO(_bound) __attribute__ ((aligned (_bound)))
#define _PACKED_ __attribute__ ((packed))
#define _LONG_CALL_ __attribute__ ((long_call))
#define _WEAK __attribute__ ((weak))
#define _OPTIMIZE_NONE_ __attribute__ ((optimize("O0")))
#endif
//port from fw by thomas
// TODO: Belows are Sync from SD7-Driver. It is necessary to check correctness
#define SWAP32(x) ((u32)( \
(((u32)(x) & (u32)0x000000ff) << 24) | \
(((u32)(x) & (u32)0x0000ff00) << 8) | \
(((u32)(x) & (u32)0x00ff0000) >> 8) | \
(((u32)(x) & (u32)0xff000000) >> 24)))
#define WAP16(x) ((u16)( \
(((u16)(x) & (u16)0x00ff) << 8) | \
(((u16)(x) & (u16)0xff00) >> 8)))
#if SYSTEM_ENDIAN == PLATFORM_LITTLE_ENDIAN
#ifndef rtk_le16_to_cpu
#define rtk_cpu_to_le32(x) ((u32)(x))
#define rtk_le32_to_cpu(x) ((u32)(x))
#define rtk_cpu_to_le16(x) ((u16)(x))
#define rtk_le16_to_cpu(x) ((u16)(x))
#define rtk_cpu_to_be32(x) SWAP32((x))
#define rtk_be32_to_cpu(x) SWAP32((x))
#define rtk_cpu_to_be16(x) WAP16((x))
#define rtk_be16_to_cpu(x) WAP16((x))
#endif
#elif SYSTEM_ENDIAN == PLATFORM_BIG_ENDIAN
#ifndef rtk_le16_to_cpu
#define rtk_cpu_to_le32(x) SWAP32((x))
#define rtk_le32_to_cpu(x) SWAP32((x))
#define rtk_cpu_to_le16(x) WAP16((x))
#define rtk_le16_to_cpu(x) WAP16((x))
#define rtk_cpu_to_be32(x) ((__u32)(x))
#define rtk_be32_to_cpu(x) ((__u32)(x))
#define rtk_cpu_to_be16(x) ((__u16)(x))
#define rtk_be16_to_cpu(x) ((__u16)(x))
#endif
#endif
/*
* Call endian free function when
* 1. Read/write packet content.
* 2. Before write integer to IO.
* 3. After read integer from IO.
*/
//
// Byte Swapping routine.
//
#define EF1Byte (u8)
#define EF2Byte le16_to_cpu
#define EF4Byte le32_to_cpu
//
// Read LE format data from memory
//
#define ReadEF1Byte(_ptr) EF1Byte(*((u8 *)(_ptr)))
#define ReadEF2Byte(_ptr) EF2Byte(*((u16 *)(_ptr)))
#define ReadEF4Byte(_ptr) EF4Byte(*((u32 *)(_ptr)))
//
// Write LE data to memory
//
#define WriteEF1Byte(_ptr, _val) (*((u8 *)(_ptr)))=EF1Byte(_val)
#define WriteEF2Byte(_ptr, _val) (*((u16 *)(_ptr)))=EF2Byte(_val)
#define WriteEF4Byte(_ptr, _val) (*((u32 *)(_ptr)))=EF4Byte(_val)
//
// Example:
// BIT_LEN_MASK_32(0) => 0x00000000
// BIT_LEN_MASK_32(1) => 0x00000001
// BIT_LEN_MASK_32(2) => 0x00000003
// BIT_LEN_MASK_32(32) => 0xFFFFFFFF
//
#define BIT_LEN_MASK_32(__BitLen) \
(0xFFFFFFFF >> (32 - (__BitLen)))
//
// Example:
// BIT_OFFSET_LEN_MASK_32(0, 2) => 0x00000003
// BIT_OFFSET_LEN_MASK_32(16, 2) => 0x00030000
//
#define BIT_OFFSET_LEN_MASK_32(__BitOffset, __BitLen) \
(BIT_LEN_MASK_32(__BitLen) << (__BitOffset))
//
// Description:
// Return 4-byte value in host byte ordering from
// 4-byte pointer in litten-endian system.
//
#define LE_P4BYTE_TO_HOST_4BYTE(__pStart) \
(EF4Byte(*((u32 *)(__pStart))))
//
// Description:
// Translate subfield (continuous bits in little-endian) of 4-byte value in litten byte to
// 4-byte value in host byte ordering.
//
#define LE_BITS_TO_4BYTE(__pStart, __BitOffset, __BitLen) \
( \
( LE_P4BYTE_TO_HOST_4BYTE(__pStart) >> (__BitOffset) ) \
& \
BIT_LEN_MASK_32(__BitLen) \
)
//
// Description:
// Mask subfield (continuous bits in little-endian) of 4-byte value in litten byte oredering
// and return the result in 4-byte value in host byte ordering.
//
#define LE_BITS_CLEARED_TO_4BYTE(__pStart, __BitOffset, __BitLen) \
( \
LE_P4BYTE_TO_HOST_4BYTE(__pStart) \
& \
( ~ BIT_OFFSET_LEN_MASK_32(__BitOffset, __BitLen) ) \
)
//
// Description:
// Set subfield of little-endian 4-byte value to specified value.
//
#define SET_BITS_TO_LE_4BYTE(__pStart, __BitOffset, __BitLen, __Value) \
*((u32 *)(__pStart)) = \
EF4Byte( \
LE_BITS_CLEARED_TO_4BYTE(__pStart, __BitOffset, __BitLen) \
| \
( (((u32)__Value) & BIT_LEN_MASK_32(__BitLen)) << (__BitOffset) ) \
);
#define BIT_LEN_MASK_16(__BitLen) \
(0xFFFF >> (16 - (__BitLen)))
#define BIT_OFFSET_LEN_MASK_16(__BitOffset, __BitLen) \
(BIT_LEN_MASK_16(__BitLen) << (__BitOffset))
#define LE_P2BYTE_TO_HOST_2BYTE(__pStart) \
(EF2Byte(*((u16 *)(__pStart))))
#define LE_BITS_TO_2BYTE(__pStart, __BitOffset, __BitLen) \
( \
( LE_P2BYTE_TO_HOST_2BYTE(__pStart) >> (__BitOffset) ) \
& \
BIT_LEN_MASK_16(__BitLen) \
)
#define LE_BITS_CLEARED_TO_2BYTE(__pStart, __BitOffset, __BitLen) \
( \
LE_P2BYTE_TO_HOST_2BYTE(__pStart) \
& \
( ~ BIT_OFFSET_LEN_MASK_16(__BitOffset, __BitLen) ) \
)
#define SET_BITS_TO_LE_2BYTE(__pStart, __BitOffset, __BitLen, __Value) \
*((u16 *)(__pStart)) = \
EF2Byte( \
LE_BITS_CLEARED_TO_2BYTE(__pStart, __BitOffset, __BitLen) \
| \
( (((u16)__Value) & BIT_LEN_MASK_16(__BitLen)) << (__BitOffset) ) \
);
#define BIT_LEN_MASK_8(__BitLen) \
(0xFF >> (8 - (__BitLen)))
#define BIT_OFFSET_LEN_MASK_8(__BitOffset, __BitLen) \
(BIT_LEN_MASK_8(__BitLen) << (__BitOffset))
#define LE_P1BYTE_TO_HOST_1BYTE(__pStart) \
(EF1Byte(*((u8 *)(__pStart))))
#define LE_BITS_TO_1BYTE(__pStart, __BitOffset, __BitLen) \
( \
( LE_P1BYTE_TO_HOST_1BYTE(__pStart) >> (__BitOffset) ) \
& \
BIT_LEN_MASK_8(__BitLen) \
)
#define LE_BITS_CLEARED_TO_1BYTE(__pStart, __BitOffset, __BitLen) \
( \
LE_P1BYTE_TO_HOST_1BYTE(__pStart) \
& \
( ~BIT_OFFSET_LEN_MASK_8(__BitOffset, __BitLen) ) \
)
#define SET_BITS_TO_LE_1BYTE(__pStart, __BitOffset, __BitLen, __Value) \
*((u8 *)(__pStart)) = \
EF1Byte( \
LE_BITS_CLEARED_TO_1BYTE(__pStart, __BitOffset, __BitLen) \
| \
( (((u8)__Value) & BIT_LEN_MASK_8(__BitLen)) << (__BitOffset) ) \
);
//pclint
#define LE_BITS_CLEARED_TO_1BYTE_8BIT(__pStart, __BitOffset, __BitLen) \
( \
LE_P1BYTE_TO_HOST_1BYTE(__pStart) \
)
//pclint
#define SET_BITS_TO_LE_1BYTE_8BIT(__pStart, __BitOffset, __BitLen, __Value) \
{ \
*((pu1Byte)(__pStart)) = \
EF1Byte( \
LE_BITS_CLEARED_TO_1BYTE_8BIT(__pStart, __BitOffset, __BitLen) \
| \
((u1Byte)__Value) \
); \
}
// Get the N-bytes aligment offset from the current length
#define N_BYTE_ALIGMENT(__Value, __Aligment) ((__Aligment == 1) ? (__Value) : (((__Value + __Aligment - 1) / __Aligment) * __Aligment))
typedef unsigned char BOOLEAN,*PBOOLEAN,boolean;
#define TEST_FLAG(__Flag,__testFlag) (((__Flag) & (__testFlag)) != 0)
#define SET_FLAG(__Flag, __setFlag) ((__Flag) |= __setFlag)
#define CLEAR_FLAG(__Flag, __clearFlag) ((__Flag) &= ~(__clearFlag))
#define CLEAR_FLAGS(__Flag) ((__Flag) = 0)
#define TEST_FLAGS(__Flag, __testFlags) (((__Flag) & (__testFlags)) == (__testFlags))
/* Define compilor specific symbol */
//
// inline function
//
#if defined ( __ICCARM__ )
#define __inline__ inline
#define __inline inline
#define __inline_definition //In dialect C99, inline means that a function's definition is provided
//only for inlining, and that there is another definition
//(without inline) somewhere else in the program.
//That means that this program is incomplete, because if
//add isn't inlined (for example, when compiling without optimization),
//then main will have an unresolved reference to that other definition.
// Do not inline function is the function body is defined .c file and this
// function will be called somewhere else, otherwise there is compile error
#elif defined ( __CC_ARM )
#define __inline__ __inline //__linine__ is not supported in keil compilor, use __inline instead
#define inline __inline
#define __inline_definition // for dialect C99
#elif defined ( __GNUC__ )
#define __inline__ inline
#define __inline inline
#define __inline_definition inline
#endif
//
// pack
//
#if defined (__ICCARM__)
#define RTW_PACK_STRUCT_BEGIN _Pragma( STRINGIFY(pack(1)))
#define RTW_PACK_STRUCT_STRUCT
#define RTW_PACK_STRUCT_END _Pragma( STRINGIFY(pack()))
//#define RTW_PACK_STRUCT_USE_INCLUDES
#elif defined (__CC_ARM)
#define RTW_PACK_STRUCT_BEGIN __packed
#define RTW_PACK_STRUCT_STRUCT
#define RTW_PACK_STRUCT_END
#elif defined (__GNUC__)
#define RTW_PACK_STRUCT_BEGIN
#define RTW_PACK_STRUCT_STRUCT __attribute__ ((__packed__))
#define RTW_PACK_STRUCT_END
#elif defined(PLATFORM_WINDOWS)
#define RTW_PACK_STRUCT_BEGIN
#define RTW_PACK_STRUCT_STRUCT
#define RTW_PACK_STRUCT_END
#define RTW_PACK_STRUCT_USE_INCLUDES
#endif
// for standard library
#ifdef __ICCARM__
#define __extension__ /* Ignore */
#define __restrict /* Ignore */
#endif
typedef struct _RAM_START_FUNCTION_ {
VOID (*RamStartFun) (VOID);
VOID (*RamWakeupFun) (VOID);
}RAM_START_FUNCTION, *PRAM_START_FUNCTION;
typedef struct _RAM_FUNCTION_START_TABLE_ {
VOID (*RamStartFun) (VOID);
VOID (*RamWakeupFun) (VOID);
VOID (*RamPatchFun0) (VOID);
VOID (*RamPatchFun1) (VOID);
VOID (*RamPatchFun2) (VOID);
VOID (*FlashStartFun) (VOID);
}RAM_FUNCTION_START_TABLE, *PRAM_FUNCTION_START_TABLE;
#endif// __BASIC_TYPES_H__

View file

@ -0,0 +1,29 @@
/*
* Routines to access hardware
*
* Copyright (c) 2013 Realtek Semiconductor Corp.
*
* This module is a confidential and proprietary property of RealTek and
* possession or use of this module requires written permission of RealTek.
*/
#ifndef _HAL_API_H_
#define _HAL_API_H_
#include "basic_types.h"
#include "rtl8711b_vector.h"
typedef enum _HAL_Status
{
HAL_OK = 0x00,
HAL_BUSY = 0x01,
HAL_TIMEOUT = 0x02,
HAL_ERR_PARA = 0x03, // error with invaild parameters
HAL_ERR_MEM = 0x04, // error with memory allocation failed
HAL_ERR_HW = 0x05, // error with hardware error
HAL_ERR_UNKNOWN = 0xee // unknown error
} HAL_Status;
#endif //_HAL_API_H_

View file

@ -0,0 +1,18 @@
/*
* Routines to access hardware
*
* Copyright (c) 2013 Realtek Semiconductor Corp.
*
* This module is a confidential and proprietary property of RealTek and
* possession or use of this module requires written permission of RealTek.
*/
#ifndef __HAL_CRYPTO_H__
#define __HAL_CRYPTO_H__
#include "ameba_soc.h"
#include "basic_types.h"
#endif /* __HAL_CRYPTO_H__ */

View file

@ -0,0 +1,779 @@
/**
******************************************************************************
* @file hal_platform.h
* @author
* @version V1.0.0
* @date 2016-05-17
* @brief This file contains all the definations of platform.
******************************************************************************
* @attention
*
* This module is a confidential and proprietary property of RealTek and
* possession or use of this module requires written permission of RealTek.
*
* Copyright(c) 2016, Realtek Semiconductor Corporation. All rights reserved.
******************************************************************************
*/
#ifndef _HAL_PLATFORM_
#define _HAL_PLATFORM_
#define ROMVERSION 0x01
#define ROMINFORMATION (ROMVERSION)
#define HAL_READ32(base, addr) rtk_le32_to_cpu(*((volatile u32*)(base + addr)))
#define HAL_WRITE32(base, addr, value32) ((*((volatile u32*)(base + addr))) = rtk_cpu_to_le32(value32))
#define HAL_READ16(base, addr) rtk_le16_to_cpu(*((volatile u16*)(base + addr)))
#define HAL_WRITE16(base, addr, value) ((*((volatile u16*)(base + addr))) = rtk_cpu_to_le16(value))
#define HAL_READ8(base, addr) (*((volatile u8*)(base + addr)))
#define HAL_WRITE8(base, addr, value) ((*((volatile u8*)(base + addr))) = value)
#ifdef __cplusplus
#define __I volatile /*!< Defines 'read only' permissions */
#else
#define __I volatile const /*!< Defines 'read only' permissions */
#endif
#define __O volatile /*!< Defines 'write only' permissions */
#define __IO volatile /*!< Defines 'read / write' permissions */
/**************************************************************************//**
* @defgroup AmebaZ_Outline
* @{
*****************************************************************************/
/** @addtogroup AmebaZ_Outline
* @verbatim
*****************************************************************************************
* CPU
*****************************************************************************************
* -Clock speed: 125MHz
* -Core: CM4F
* -Working votage: 3.3V
*
*****************************************************************************************
* Memory
*****************************************************************************************
* -ROM: 512KB
* -RAM: 256KB
* -FLash: 128MB
*
*****************************************************************************************
* GPIO
*****************************************************************************************
* -GPIOA: 0~31, IN/OUT/INT
* -GPIOB: 0~6, IN/OUT
*
*****************************************************************************************
* Flash
*****************************************************************************************
* -Max. speed: 100MHz
* -SPI Mode: Quad IO mode
* -cache: 32K I/D read cache
* -XIP: support executed in place
*
*****************************************************************************************
* Firmware Protection
*****************************************************************************************
* -RSIP(OTF):(Realsil Image Protection)
* -Flash Encryption
* -key store in OTP EFUSE Area, and can not read
* -RDP
* -4K RAM read protection
* -key store in OTP EFUSE Area, and can not read
*
*****************************************************************************************
* UART
*****************************************************************************************
* -Set count: 2
* -IrDA: support
* -Low Power: support
* -Sleep wakeup: support
* -Baud rate: 110~6000000
* -GDMA: support
*
*****************************************************************************************
* UART LOG
*****************************************************************************************
* -Set count: 1
* -IrDA: support
* -Low Power: not support
* -Sleep wakeup: not support
* -Baud rate: 110~6000000
*
*****************************************************************************************
* SPI Master
*****************************************************************************************
* -Set count: 1
* -Max. Speed: 31.25MHz
* -GDMA: support
*
*****************************************************************************************
* SPI Slave
*****************************************************************************************
* -Set count: 1
* -Max. Speed: 31.25MHz
* -GDMA: support
*
*****************************************************************************************
* I2C
*****************************************************************************************
* -Set count: 2
* -Speed: Standard (up to 100 kHz) and Fast (up to 400 kHz) Modes
* -Role: Master & Slave
* -Sleep wakeup: support
* -GDMA: support
*
*****************************************************************************************
* RTC
*****************************************************************************************
* -Set count: 1
* -H: 12/24 hour mode
* -M: 0~59
* -S: 0~59
* -D: 0~255
* -Alarm: support D/H/M/S
* -Daylight: support
* -Calibration: support
*
*****************************************************************************************
* PWM
*****************************************************************************************
* -Channel count: 6
* -Max. Resolution: 16bits (customizable)
* -Max. Frequency: 40MHz@1-bit mode, 40/(2^x))MHz@x-bit
* -GDMA: support
*
*****************************************************************************************
* PWM capture
*****************************************************************************************
* -Channel count: 1
* -Max. Resolution: 16bits (customizable)
* -Max. Frequency: 40MHz@1-bit mode, 40/(2^x))MHz@x-bit
* -capture width: supoort
* -capture number: support
* -GDMA: support
*
*****************************************************************************************
* Timer
*****************************************************************************************
* -Set count: 6
* -32KHz timer: 4
* -40MHz timer: 2
*
*****************************************************************************************
* I2S
*****************************************************************************************
* -Set count: 1
* -Source clk: 22.579MHz or 24.576MHz(default)
* -Sample rate: 8K, 16K, 24K, 32K, 48K, 96K, 7.35K, 14.7K, 22.05K, 29.4K, 44.1K, 88.2K
* -Sample bit: 16 bit, 24 bit
* -DMA: support
*
*****************************************************************************************
* WIFI
*****************************************************************************************
* -Set count: 1
* -Mode: B/G/N(2.4G)
* -BW: 20MHz/40MHz
* -Ant: 1T/1R
*
*****************************************************************************************
* USB device
*****************************************************************************************
* -Set count: 1
* -DMA: support
*
*****************************************************************************************
* SDIO device
*****************************************************************************************
* -Set count: 1
* -GSPI: support
* -DMA: support
*
*****************************************************************************************
* BACKUP REG
*****************************************************************************************
* -Set count: 4 dwords
*
*****************************************************************************************
* CRYPTO
*****************************************************************************************
* -MD5
* -SHA1
* -SHA2
* -HMAC-MD5
* -HMAC-SHA1
* -HMAC-SHA2
*
* -AES-CBC
* -AES-ECB
* -AES-CTR
* -3DES-CBC
* -3DES-ECB
* -DES-CBC
* -DES-ECB
*
*****************************************************************************************
* ADC
*****************************************************************************************
* -Set count: 1
* -Channel: 4
* -Sample rate: max frequency up to 1MHz per channel, configurable
* -Resolution: 12 bit
* -signal sampling: CH1 & CH3: 0 ~ 3V, CH2: 0~5V
* -power save: Support one shot mode
* -GDMA: support
*
*****************************************************************************************
* GDMA
*****************************************************************************************
* -Set count: 2
* -Channel: 2*6
*
*****************************************************************************************
* @endverbatim
*/
/**************************************************************************//**
* @defgroup AmebaZ_Address_Map AmebaZ Address Map
* @{
*****************************************************************************/
#define SYSTEM_CTRL_BASE 0x40000000
#define PERI_ON_BASE 0x40000000
#define VENDOR_REG_BASE 0x40002800
#define SPI_FLASH_BASE 0x08000000
#define NCO1_REG_BASE 0x40000080
#define BACKUP_REG_BASE 0x40000138
#define NCO2_REG_BASE 0x4000026C
#define PINMUX_REG_BASE 0x40000280
#define GPIO_REG_BASE 0x40001000
#define TIMER_REG_BASE 0x40002000
#define LOG_UART_REG_BASE 0x40003000
#define RTC_BASE 0x40003400
#define SPIC_CACHE_BASE 0x40003C00
#define ADC_REG_BASE 0x40010000
#define SPI_FLASH_CTRL_BASE 0x40020000
#define UART0_REG_BASE 0x40040000
#define UART1_REG_BASE 0x40040400
#define UART2_REG_BASE LOG_UART_REG_BASE
#define SPI0_REG_BASE 0x40042000
#define SPI1_REG_BASE 0x40042400
#define I2C0_REG_BASE 0x40044000
#define I2C1_REG_BASE 0x40044400
#define SDIO_DEVICE_REG_BASE 0x40050000
#define GDMA0_REG_BASE 0x40060000
#define GDMA1_REG_BASE 0x40061000
#define I2S0_REG_BASE 0x40062000
#define CRYPTO_REG_BASE 0x40070000
#define WIFI_REG_BASE 0x40080000
#define SIE_REG_BASE 0x400C0000
#define USOC_REG_BASE 0x400C2000
#define GDMA1_REG_OFF 0x1000
/** @} End of group AmebaZ_Address_Map */
/**************************************************************************//**
* @defgroup AmebaZ_Peripheral_Registers_Structures AmebaZ Peripheral_Registers_Structures
* @{
*****************************************************************************/
/**************************************************************************//**
* @defgroup AMEBAZ_UART
* @{
* @brief AMEBAZ_UART Register Declaration
*****************************************************************************/
typedef struct {
__IO u32 DLL; /*!< UART Divisor Latch register(not used in Amebaz), Address offset: 0x00*/
__IO u32 DLH_INTCR; /*!< UART interrupt enable register, Address offset: 0x04*/
__IO u32 INTID; /*!< UART interrupt identification register, Address offset: 0x08*/
__IO u32 LCR; /*!< UART line control register, Address offset: 0x0C*/
__IO u32 MCR; /*!< UART modem control register, Address offset: 0x10*/
__I u32 LSR; /*!< UART line status register, Address offset: 0x14*/
__I u32 MDSR; /*!< UART modem status register, Address offset: 0x18*/
__IO u32 SPR; /*!< UART scratch pad register, Address offset: 0x1C*/
__IO u32 STSR; /*!< UART STS register, Address offset: 0x20*/
__IO u32 RB_THR; /*!< UART receive buffer/transmitter holding register, Address offset: 0x24*/
__IO u32 MISCR; /*!< UART MISC control register, Address offset: 0x28*/
__IO u32 TXPLSR; /*!< UART IrDA SIR TX Pulse Width Control register, Address offset: 0x2C*/
__IO u32 RXPLSR; /*!< UART IrDA SIR RX Pulse Width Control register, Address offset: 0x30*/
__IO u32 BAUDMONR; /*!< UART baud monitor register, Address offset: 0x34*/
__IO u32 RSVD2; /*!< UART reserved field, Address offset: 0x38*/
__IO u32 DBG_UART; /*!< UART debug register, Address offset: 0x3C*/
/* AmebaZ add for power save */
__IO u32 RX_PATH; /*!< UART rx path control register, Address offset: 0x40*/
__IO u32 MON_BAUD_CTRL; /*!< UART monitor baud rate control register, Address offset: 0x44*/
__IO u32 MON_BAUD_STS; /*!< UART monitor baud rate status register, Address offset: 0x48*/
__IO u32 MON_CYC_NUM; /*!< UART monitor cycle number register, Address offset: 0x4c*/
__IO u32 RX_BYTE_CNT; /*!< UART rx byte counter register, Address offset: 0x50*/
/* AmebaZ change */
__IO u32 FCR; /*!< UART FIFO Control register, Address offset: 0x54*/
} UART_TypeDef;
/** @} */
/**************************************************************************//**
* @defgroup AMEBAZ_SPI
* @{
* @brief AMEBAZ_SPI Register Declaration
*****************************************************************************/
typedef struct {
__IO uint32_t CTRLR0; /*!< SSI control register 0, Address offset: 0x00 */
__IO uint32_t CTRLR1; /*!< SSI control register 1, Address offset: 0x04 */
__IO uint32_t SSIENR; /*!< SSI enable register, Address offset: 0x08 */
__IO uint32_t MWCR; /*!< SSI microwire control register, Address offset: 0x0C */
__IO uint32_t SER; /*!< SSI slave enable register, Address offset: 0x10 */
__IO uint32_t BAUDR; /*!< SSI baud rate select register, Address offset: 0x14 */
__IO uint32_t TXFTLR; /*!< SSI transmit FIFO threshold level register, Address offset: 0x18 */
__IO uint32_t RXFTLR; /*!< SSI Receive FIFO Threshold Level register, Address offset: 0x1C */
__I uint32_t TXFLR; /*!< SSI transmit FIFO level register, Address offset: 0x20 */
__I uint32_t RXFLR; /*!< SSI receive FIFO level register, Address offset: 0x24*/
__I uint32_t SR; /*!< SSI status register, Address offset: 0x28 */
__IO uint32_t IMR; /*!< SSI interrupt mask register, Address offset: 0x2C */
__I uint32_t ISR; /*!< SSI interrupt status register, Address offset: 0x30 */
__I uint32_t RISR; /*!< SSI raw interrupt status register, Address offset: 0x34 */
__I uint32_t TXOICR; /*!< SSI transmit FIFO overflow interrupt clear register, Address offset: 0x38 */
__I uint32_t RXOICR; /*!< SSI receive FIFO overflow interrupt clear register, Address offset: 0x3C */
__I uint32_t RXUICR; /*!< SSI receive FIFO underflow interrupt clear register, Address offset: 0x40 */
__I uint32_t MSTICR; /*!< SSI multi-master interrupt clear register, Address offset: 0x44 */
__I uint32_t ICR; /*!< SSI interrupt clear register, Address offset: 0x48 */
__IO uint32_t DMACR; /*!< SSI DMA control register, Address offset: 0x4C */
__IO uint32_t DMATDLR; /*!< SSI DMA transmit data level register, Address offset: 0x50 */
__IO uint32_t DMARDLR; /*!< SSI DMA receive data level register, Address offset: 0x54 */
__I uint32_t IDR; /*!< SSI identification register, Address offset: 0x58 */
__I uint32_t SSI_COMP_VERSION; /*!< SSI coreKit version ID register, Address offset: 0x5C */
__IO uint32_t DR[36]; /*!< SSI data register, Address offset: 0x60 - 0xEC */
__IO uint32_t RX_SAMPLE_DLY; /*!< SSI rxd sample delay register, Address offset: 0xF0 */
}SPI_TypeDef;
/** @} */
/**************************************************************************//**
* @defgroup AMEBAZ_SPIC
* @{
* @brief AMEBAZ_SPIC Register Declaration
*****************************************************************************/
typedef struct
{
__IO uint32_t ctrlr0; /*!< SPIC control register0, Address offset: 0x000 */
__IO uint32_t ctrlr1; /*!< SPIC control register1, Address offset: 0x004 */
__IO uint32_t ssienr; /*!< SPIC enable register, Address offset: 0x008 */
__IO uint32_t mwcr; /*!< N/A, Address offset: 0x00C */
__IO uint32_t ser; /*!< SPIC slave enable register, Address offset: 0x010 */
__IO uint32_t baudr; /*!< SPIC baudrate select register, Address offset: 0x014 */
__IO uint32_t txftlr; /*!< SPIC transmit FIFO threshold level, Address offset: 0x018 */
__IO uint32_t rxftlr; /*!< SPIC receive FIFO threshold level, Address offset: 0x01C */
__IO uint32_t txflr; /*!< SPIC transmit FIFO level register, Address offset: 0x020 */
__IO uint32_t rxflr; /*!< SPIC receive FIFO level register, Address offset: 0x024 */
__IO uint32_t sr; /*!< SPIC status register, Address offset: 0x028 */
__IO uint32_t imr; /*!< SPIC interrupt mask register, Address offset: 0x02C */
__IO uint32_t isr; /*!< SPIC interrupt status register, Address offset: 0x030 */
__IO uint32_t risr; /*!< SPIC raw interrupt status register, Address offset: 0x034 */
__IO uint32_t txoicr; /*!< SPIC transmit FIFO overflow interrupt clear register, Address offset: 0x038 */
__IO uint32_t rxoicr; /*!< SPIC receive FIFO overflow interrupt clear register, Address offset: 0x03C */
__IO uint32_t rxuicr; /*!< SPIC receive FIFO underflow interrupt clear register, Address offset: 0x040 */
__IO uint32_t msticr; /*!< SPIC master error interrupt clear register, Address offset: 0x044 */
__IO uint32_t icr; /*!< SPIC interrupt clear register, Address offset: 0x048 */
__IO uint32_t dmacr; /*!< N/A, Address offset: 0x04C */
__IO uint32_t dmatdlr; /*!< N/A, Address offset: 0x050 */
__IO uint32_t dmardlr; /*!< N/A, Address offset: 0x054 */
__IO uint32_t idr; /*!< SPIC Identiation register, Address offset: 0x058 */
__IO uint32_t spi_flash_version; /*!< SPIC version ID register, Address offset: 0x05C */
union{
__IO uint8_t byte;
__IO uint16_t half;
__IO uint32_t word;
} dr[32]; /*!< SPIC data register, Address offset: 0x060~0x0DC */
__IO uint32_t rd_fast_single; /*!< Fast read data command of SPI Flash, Address offset: 0x0E0 */
__IO uint32_t rd_dual_o; /*!< Dual output read command of SPI Flash, Address offset: 0x0E4 */
__IO uint32_t rd_dual_io; /*!< Dual I/O read command of SPI Flash, Address offset: 0x0E8 */
__IO uint32_t rd_quad_o; /*!< Quad output read command of SPI Flash, Address offset: 0x0EC */
__IO uint32_t rd_quad_io; /*!< Quad I/O read command of SPI Flash, Address offset: 0x0F0 */
__IO uint32_t wr_single; /*!< Page program command of SPI Flash, Address offset: 0x0F4 */
__IO uint32_t wr_dual_i; /*!< Dual data input program command of SPI Flash, Address offset: 0x0F8 */
__IO uint32_t wr_dual_ii; /*!< Dual address and data input program command of SPI Flash, Address offset: 0x0FC */
__IO uint32_t wr_quad_i; /*!< Quad data input program command of SPI Flash, Address offset: 0x100 */
__IO uint32_t wr_quad_ii; /*!< Quad address and data input program command of SPI Flash, Address offset: 0x104 */
__IO uint32_t wr_enable; /*!< Write enabe command of SPI Flash, Address offset: 0x108 */
__IO uint32_t rd_status; /*!< Read status command of SPI Flash, Address offset: 0x10C */
__IO uint32_t ctrlr2; /*!< SPIC control register2, Address offset: 0x110 */
__IO uint32_t fbaudr; /*!< SPIC fast baudrate select, Address offset: 0x114 */
__IO uint32_t addr_length; /*!< SPIC address length register, Address offset: 0x118 */
__IO uint32_t auto_length; /*!< SPIC auto address length register, Address offset: 0x11C */
__IO uint32_t valid_cmd; /*!< SPIC valid command register, Address offset: 0x120 */
__IO uint32_t flash_size; /*!< SPIC flash size register, Address offset: 0x124 */
__IO uint32_t flush_fifo; /*!< SPIC flush FIFO register, Address offset: 0x128 */
} SPIC_TypeDef;
/** @} */
/**************************************************************************//**
* @defgroup AMEBAZ_ADC
* @{
* @brief AMEBAZ_ADC Register Declaration
*****************************************************************************/
typedef struct {
__IO uint32_t FIFO_READ; /*!< ADC chan0-chan3 RX FIFO read register, Address offset: 0x00 */
__IO uint32_t CONTROL; /*!< ADC control register, Address offset: 0x04 */
__IO uint32_t INTR_EN; /*!< ADC interrupt enable register, Address offset: 0x08 */
__IO uint32_t INTR_STS; /*!< ADC interrupt status register, Address offset: 0x0C */
__IO uint32_t COMP_VALUE_L; /*!< ADC chan0-1 compare value register, Address offset: 0x10 */
__IO uint32_t COMP_VALUE_H; /*!< ADC chan2-3 compare value register, Address offset: 0x14 */
__IO uint32_t COMP_SET; /*!< ADC compare setting register, Address offset: 0x18 */
__IO uint32_t POWER; /*!< ADC power register, Address offset: 0x1C */
__IO uint32_t ANAPAR_AD0; /*!< ADC analog parameter ad0 register, Address offset: 0x20 */
__IO uint32_t ANAPAR_AD1; /*!< ADC analog parameter ad1 register, Address offset: 0x24 */
__IO uint32_t ANAPAR_AD2; /*!< ADC analog parameter ad2 register, Address offset: 0x28 */
__IO uint32_t ANAPAR_AD3; /*!< ADC analog parameter ad3 register, Address offset: 0x2C */
__IO uint32_t ANAPAR_AD4; /*!< ADC analog parameter ad4 register, Address offset: 0x30 */
__IO uint32_t ANAPAR_AD5; /*!< ADC analog parameter ad5 register, Address offset: 0x34 */
__IO uint32_t CALI_DATA; /*!< ADC calibration data register, Address offset: 0x38 */
} ADC_TypeDef;
/** @} */
/**************************************************************************//**
* @defgroup AMEBAZ_I2C
* @{
* @brief AMEBAZ_I2C Register Declaration
*****************************************************************************/
typedef struct
{
__IO uint32_t IC_CON; /*!< I2C control register, Address offset: 0x00 */
__IO uint32_t IC_TAR; /*!< I2C target address register, Address offset: 0x04 */
__IO uint32_t IC_SAR; /*!< I2C slave0 address register, Address offset: 0x08 */
__IO uint32_t IC_HS_MADDR; /*!< I2C HS master mode code address register, Address offset: 0x0C */
__IO uint32_t IC_DATA_CMD; /*!< I2C rx/tx data buffer and command register, Address offset: 0x10 */
__IO uint32_t IC_SS_SCL_HCNT; /*!< I2C standard speed clock SCL high count register, Address offset: 0x14 */
__IO uint32_t IC_SS_SCL_LCNT; /*!< I2C standard speed clock SCL low count register, Address offset: 0x18 */
__IO uint32_t IC_FS_SCL_HCNT; /*!< I2C fast speed clock SCL high count register, Address offset: 0x1C */
__IO uint32_t IC_FS_SCL_LCNT; /*!< I2C fast speed clock SCL low count register, Address offset: 0x20 */
__IO uint32_t IC_HS_SCL_HCNT; /*!< I2C high speed clock SCL high count register, Address offset: 0x24 */
__IO uint32_t IC_HS_SCL_LCNT; /*!< I2C high speed clock SCL low count register, Address offset: 0x28 */
__I uint32_t IC_INTR_STAT; /*!< I2C interrupt status register, Address offset: 0x2C */
__IO uint32_t IC_INTR_MASK; /*!< I2C interrupt mask register, Address offset: 0x30 */
__I uint32_t IC_RAW_INTR_STAT; /*!< I2C raw interrupt status register, Address offset: 0x34 */
__IO uint32_t IC_RX_TL; /*!< I2C receive FIFO threshold register, Address offset: 0x38 */
__IO uint32_t IC_TX_TL; /*!< I2C transmit FIFO threshold register, Address offset: 0x3C */
__I uint32_t IC_CLR_INTR; /*!< I2C clear combined and individual interrupts register, Address offset: 0x40 */
__I uint32_t IC_CLR_RX_UNDER; /*!< I2C clear RX_UNDER interrupt register, Address offset: 0x44 */
__I uint32_t IC_CLR_RX_OVER; /*!< I2C clear RX_OVER interrupt register, Address offset: 0x48 */
__I uint32_t IC_CLR_TX_OVER; /*!< I2C clear TX_OVER interrupt register, Address offset: 0x4C */
__I uint32_t IC_CLR_RD_REQ; /*!< I2C clear RD_REQ interrupt register, Address offset: 0x50 */
__I uint32_t IC_CLR_TX_ABRT; /*!< I2C clear TX_ABRT interrupt register, Address offset: 0x54 */
__I uint32_t IC_CLR_RX_DONE; /*!< I2C clear RX_DONE interrupt register, Address offset: 0x58 */
__I uint32_t IC_CLR_ACTIVITY; /*!< I2C clear ACTIVITY interrupt register, Address offset: 0x5C */
__I uint32_t IC_CLR_STOP_DET; /*!< I2C clear STOP_DET interrupt register, Address offset: 0x60 */
__I uint32_t IC_CLR_START_DET; /*!< I2C clear START_DET interrupt register, Address offset: 0x64 */
__I uint32_t IC_CLR_GEN_CALL; /*!< I2C clear GEN_CALL interrupt register, Address offset: 0x68 */
__IO uint32_t IC_ENABLE; /*!< I2C enable register, Address offset: 0x6C */
__I uint32_t IC_STATUS; /*!< I2C status register, Address offset: 0x70 */
__I uint32_t IC_TXFLR; /*!< I2C transmit FIFO level register, Address offset: 0x74 */
__I uint32_t IC_RXFLR; /*!< I2C receive FIFO level register, Address offset: 0x78 */
__IO uint32_t IC_SDA_HOLD; /*!< I2C SDA hold time length register, Address offset: 0x7C */
__I uint32_t IC_TX_ABRT_SOURCE; /*!< I2C transmit abort status register, Address offset: 0x80 */
__IO uint32_t IC_SLV_DATA_NACK_ONLY; /*!< I2C generate SLV_DATA_NACK register, Address offset: 0x84 */
__IO uint32_t IC_DMA_CR; /*!< I2C DMA control register, Address offset: 0x88 */
__IO uint32_t IC_DMA_TDLR; /*!< I2C DMA transmit data level register, Address offset: 0x8C */
__IO uint32_t IC_DMA_RDLR; /*!< I2C DMA receive data level register, Address offset: 0x90 */
__IO uint32_t IC_SDA_SETUP; /*!< I2C SDA setup register, Address offset: 0x94 */
__IO uint32_t IC_ACK_GENERAL_CALL; /*!< I2C ACK general call register, Address offset: 0x98 */
__IO uint32_t IC_ENABLE_STATUS; /*!< I2C enable status register, Address offset: 0x9C */
/* AmebaZ added New registers */
__IO uint32_t IC_DMA_CMD; /*!< I2C DMA command register, Address offset: 0xA0 */
__IO uint32_t IC_DMA_DAT_LEN; /*!< I2C DMA transmit data length register, Address offset: 0xA4 */
__IO uint32_t IC_DMA_MOD; /*!< I2C DMA mode register, Address offset: 0xA8 */
__IO uint32_t IC_SLEEP; /*!< I2C sleep control register, Address offset: 0xAC */
__IO uint32_t IC_RSVD1[4]; /*!< I2C reserved field, Address offset: 0xB0 */
__I uint32_t IC_RSVD2[4]; /*!< I2C reserved field, Address offset: 0xC0 */
__I uint32_t IC_RSVD3[4]; /*!< I2C reserved field, Address offset: 0xD0 */
__I uint32_t IC_RSVD4; /*!< I2C reserved field, Address offset: 0xE0 */
__I uint32_t IC_CLR_ADDR_MATCH; /*!< I2C clear ADDR_MATCH interrupt register, Address offset: 0xE4 */
__I uint32_t IC_CLR_DMA_I2C_DONE; /*!< I2C clear DMA_I2C_DONE interrupt register, Address offset: 0xE8 */
__IO uint32_t IC_FILTER; /*!< I2C filter register, Address offset: 0xEC */
__I uint32_t IC_RSVD5; /*!< I2C reserved field, Address offset: 0xF0 */
__IO uint32_t IC_SAR1; /*!< I2C slave1 address register, Address offset: 0xF4 */
__IO uint32_t IC_DATA_S1; /*!< I2C slave1 rx/tx data buffer register, Address offset: 0xF8 */
__I uint32_t IC_COMP_VERSION; /*!< I2C component version ID register, Address offset: 0xFC */
} I2C_TypeDef;
/** @} */
/**************************************************************************//**
* @defgroup AMEBAZ_I2S
* @{
* @brief AMEBAZ_I2S Register Declaration
*****************************************************************************/
typedef struct
{
__IO uint32_t IS_CTL; /*!< I2S control register, Address offset: 0x00 */
__IO uint32_t IS_TX_PAGE_PTR; /*!< I2S TX page pointer register, Address offset: 0x04 */
__IO uint32_t IS_RX_PAGE_PTR; /*!< I2S RX page pointer register, Address offset: 0x08 */
__IO uint32_t IS_SETTING; /*!< I2S page size and sample rate setting register, Address offset: 0x0c */
__IO uint32_t IS_TX_MASK_INT; /*!< I2S TX interrupt enable register, Address offset: 0x10 */
__IO uint32_t IS_TX_STATUS_INT; /*!< I2S TX interrupt status register, Address offset: 0x14 */
__IO uint32_t IS_RX_MASK_INT; /*!< I2S RX interrupt enable register, Address offset: 0x18 */
__IO uint32_t IS_RX_STATUS_INT; /*!< I2S RX interrupt status register, Address offset: 0x1C */
__IO uint32_t IS_TX_PAGE_OWN[4]; /*!< I2S TX page own bit register, Address offset: 0x20-0x2c */
__IO uint32_t IS_RX_PAGE_OWN[4]; /*!< I2S RX page own bit register, Address offset: 0x30-0x3c */
} I2S_TypeDef;
/** @} */
/**************************************************************************//**
* @defgroup AMEBAZ_TIMER
* @{
* @brief AMEBAZ_TIMER Register Declaration
* @note TIM1 have 6 CCR registers: bit[15:0] is CCR, bit[31:24] is CCMR
* @note TIM3 have 1 CCR registesr: bit[15:0] is CCR, bit[31:24] is CCMR
* @note TIM5-8 dont have CCR register
*****************************************************************************/
/**
* @brief RTK TIM CCR
*/
typedef struct {
__IO uint16_t CCRx; /*!< TIM capture/compare register */
__IO uint8_t RSVD; /*!< TIM capture/compare rsvd register */
__IO uint8_t CCMRx; /*!< TIM capture/compare register */
} RTIM_CCR_TypeDef;
/**
* @brief RTK TIM
*/
typedef struct {
__IO uint32_t EN; /*!< TIM Enable register, Address offset: 0x00 */
__IO uint32_t CR; /*!< TIM control register, Address offset: 0x04 */
__IO uint32_t DIER; /*!< TIM DMA/interrupt enable register, Address offset: 0x08 */
__IO uint32_t SR; /*!< TIM status register, Address offset: 0x0C */
__IO uint32_t EGR; /*!< TIM event generation register, Address offset: 0x10 */
__IO uint32_t CNT; /*!< TIM counter register, Address offset: 0x14 */
__IO uint32_t PSC; /*!< TIM prescaler, Address offset: 0x18 */
__IO uint32_t ARR; /*!< TIM auto-reload register, Address offset: 0x1C */
__IO uint32_t CCMRx[6]; /*!< TIM capture/compare register */
} RTIM_TypeDef;
/** @} */
/**************************************************************************//**
* @defgroup AMEBAZ_RTC
* @{
* @brief AMEBAZ_RTC Register Declaration
*****************************************************************************/
typedef struct {
__IO uint32_t TR; /*!< RTC time register, Address offset: 0x00 */
__IO uint32_t CR; /*!< RTC control register, Address offset: 0x04 */
__IO uint32_t ISR; /*!< RTC initialization and status register, Address offset: 0x08 */
__IO uint32_t PRER; /*!< RTC prescaler register, Address offset: 0x0C*/
__IO uint32_t CALIBR; /*!< RTC calibration register, Address offset: 0x10 */
__IO uint32_t ALMR1; /*!< RTC alarm register1, Address offset: 0x14 */
__IO uint32_t ALMR2; /*!< RTC alarm register2, Address offset: 0x18 */
__IO uint32_t WPR; /*!< RTC write protection register, Address offset: 0x1C */
} RTC_TypeDef;
/** @} */
/**************************************************************************//**
* @defgroup AMEBAZ_PINMUX
* @{
* @brief AMEBAZ_PINMUX Register Declaration
*****************************************************************************/
typedef struct {
__IO uint32_t PADCTR[21]; /*!< Pad control register */
} PINMUX_TypeDef;
/** @} */
/**************************************************************************//**
* @defgroup AMEBAZ_GPIO
* @{
* @brief AMEBAZ_GPIO Register Declaration
*****************************************************************************/
/**
* @brief GPIO port
*/
typedef struct {
__IO uint32_t DR; /*!< data register */
__IO uint32_t DDR; /*!< data direction */
__IO uint32_t CTRL; /*!< data source control, we should keep it as default: data source from software */
} GPIO_Port_TypeDef;
/**
* @brief General purpose input and output. (GPIO)
*/
typedef struct {
GPIO_Port_TypeDef PORT[4]; /*!< GPIO IP have 4 ports, Address offset: 0x00-0x2C */
__IO uint32_t INT_EN; /*!< GPIO interrupt enable register, Address offset: 0x30 */
__IO uint32_t INT_MASK; /*!< GPIO interrupt mask register, Address offset: 0x34 */
__IO uint32_t INT_TYPE; /*!< GPIO interrupt type(level/edge) register, Address offset: 0x38 */
__IO uint32_t INT_POLARITY; /*!< GPIO interrupt polarity(Active low/high) register, Address offset: 0x3C */
__IO uint32_t INT_STATUS; /*!< GPIO interrupt status register, Address offset: 0x40 */
__IO uint32_t INT_RAWSTATUS; /*!< GPIO interrupt status without mask register, Address offset: 0x44 */
__IO uint32_t DEBOUNCE; /*!< GPIO interrupt signal debounce register, Address offset: 0x48 */
__IO uint32_t PORTA_EOI; /*!< GPIO clear interrupt register, Address offset: 0x4C */
__IO uint32_t EXT_PORT[4]; /*!< GPIO IN read or OUT read back register, Address offset: 0x50-0x5C */
__IO uint32_t LSSYNC; /*!< GPIO level-sensitive synchronization enable register, Address offset: 0x60 */
__IO uint32_t IDCODE; /*!< GPIO ID code register, Address offset: 0x64 */
__IO uint32_t RSVD2; /*!< Reserved, Address offset: 0x68 */
__IO uint32_t VERIDCODE; /*!< GPIO component Version register, Address offset: 0x6C */
__IO uint32_t CONFIG2; /*!< GPIO configuration Register 2, Address offset: 0x70 */
__IO uint32_t CONFIG1; /*!< GPIO configuration Register 1, Address offset: 0x74 */
} GPIO_TypeDef;
/** @} */
/**************************************************************************//**
* @defgroup AMEBAZ_IPSEC
* @{
* @brief AMEBAZ_IPSEC Register Declaration
*****************************************************************************/
typedef struct {
__IO uint32_t IPSSDAR; /*!< (0x00) IPSec Source Descriptor Starting Address Register */
__IO uint32_t IPSDDAR; /*!< (0x04) IPSec Destination Descriptor Starting Address Register */
__IO uint32_t IPSCSR; /*!< (0x08) IPSec Command/Status Register */
__IO uint32_t IPSCTR; /*!< (0x0C) IPSec Control Register */
} IPSEC_TypeDef;
/** @} */
/**************************************************************************//**
* @defgroup AMEBAZ_USOC
* @{
* @brief AMEBAZ_USOC Register Declaration
*****************************************************************************/
typedef struct {
__IO uint32_t SIE_CR; /*!< SIE control register, Address offset: 0x00 */
__IO uint32_t CLK_RST_CTRL; /*!< USOC clock and reset control register, Address offset: 0x04 */
__IO uint32_t CHANN_CTRL; /*!< USOC channel control register, Address offset: 0x08 */
__IO uint32_t BUFF_SIZE_CTRL; /*!< USOC tx/rx buffer size control register, Address offset: 0x0C */
__IO uint32_t TXBD_BAR; /*!< USOC TXBD base address register, Address offset: 0x10 */
__IO uint32_t RXBD_BAR; /*!< USOC RXBD base address register, Address offset: 0x14 */
__IO uint32_t RING_SIZE_CTRL; /*!< USOC ring size control register, Address offset: 0x18 */
__IO uint32_t RSVD1; /*!< reserved , Address offset: 0x1C */
__I uint32_t TXBD_HW_IDX; /*!< USOC TXBD hardware index, Address offset: 0x20 */
__IO uint32_t TXBD_SW_IDX; /*!< USOC TXBD software index, Address offset: 0x24 */
__I uint32_t RXBD_HW_IDX; /*!< USOC RXBD hardware index, Address offset: 0x28 */
__IO uint32_t RXBD_SW_IDX; /*!< USOC RXBD software index, Address offset: 0x2C */
__IO uint32_t INTR_MASK; /*!< USOC interrupt mask register, Address offset: 0x30 */
__IO uint32_t INTR_CLR; /*!< USOC interrupt clear register, Address offset: 0x34 */
__IO uint32_t INTR_STAT; /*!< USOC interrupt status register, Address offset: 0x38 */
__IO uint32_t RSVD2; /*!< reserved , Address offset: 0x3C */
__IO uint32_t TX_MIT; /*!< USOC TX mitigation register, Address offset: 0x40 */
__IO uint32_t RX_MIT; /*!< USOC RX mitigation register, Address offset: 0x44 */
__IO uint32_t RSVD3[2]; /*!< Reserved register, Address offset: 0x48 */
__IO uint32_t IOREG_MAR; /*!< USOC HOST access device register, Address offset: 0x50 */
__IO uint32_t RSVD4[3]; /*!< Reserved , Address offset: 0x54 */
__IO uint32_t TX_MAIN_BUF_CTRL; /*!< USOC tx main buffer control register, Address offset: 0x60 */
__IO uint32_t TX_DEST_BUF_CTRL; /*!< USOC tx destination buffer control register, Address offset: 0x64 */
__IO uint32_t RX_MAIN_BUF_CTRL; /*!< USOC rx main buffer control register, Address offset: 0x68 */
__IO uint32_t RX_SRC_BUF_CTRL; /*!< USOC rx source buffer control register, Address offset: 0x6C */
__IO uint32_t TX_STUCK_TIMER; /*!< USOC tx stuck timer register, Address offset: 0x70 */
__IO uint32_t RX_STUCK_TIMER; /*!< USOC rx stuck timer register, Address offset: 0x74 */
__IO uint32_t QOS_CTRL; /*!< USOC QoS control register, Address offset: 0x78 */
} USOC_REG_TypeDef;
/** @} */
/**************************************************************************//**
* @defgroup AMEBAZ_NCO32k
* @{
* @brief AMEBAZ_NCO32k Register Declaration
*****************************************************************************/
typedef struct {
__IO uint32_t CLK_INFO; /*!< (0x00) [23:0]: BIT_FREQVALUE_UNREGCLK, [24]: BIT_32K_CLK_OUT_RDY, [25]: 32K calibration ready flag */
__IO uint32_t CLK_OUT; /*!< (0x04) expected frequency of NCO calibration output clk */
__IO uint32_t CLK_REF; /*!< (0x08) low 32 bits of frequency value of ref clk, this will be used to gen clk_out, and clk_ref is used to monitor frequency of clk_in (ASIC: OSC8M, FPGA: 128K) */
__IO uint32_t CTRL; /*!< (0x0c) [9:0]high 10 bits of frequency value of ref clk, [16] 32k enable, [17] ref clk enable, [23:20] 32k monitor, [30:24]32k threshold*/
} NCO32k_TypeDef;
/** @} */
/**************************************************************************//**
* @defgroup AMEBAZ_NCO8M
* @{
* @brief AMEBAZ_NCO8M Register Declaration
* @note [0]: function enable
* @note [15:1]: expected frequency of nco output clk, unit is 1KHz
* @note [31:16] frequency of nco input clk, unit is 1KHz
*****************************************************************************/
typedef struct {
__IO uint32_t NCOReg;
} NCO8M_TypeDef;
/** @} */
/**************************************************************************//**
* @defgroup AMEBAZ_BACKUP_REG
* @{
* @brief AMEBAZ_BACKUP_REG Register Declaration
* @note 16 Bytes total
*****************************************************************************/
typedef struct {
__IO uint32_t DWORD[4]; /* 0x138 */
} BACKUP_REG_TypeDef;
/** @} */
/**************************************************************************//**
* @defgroup AMEBAZ_CACHE
* @{
* @brief AMEBAZ_CACHE Register Declaration
*****************************************************************************/
typedef struct {
__IO uint32_t SPICC_EN; /*!< SPICC Enable register, Address offset: 0x00 */
__IO uint32_t SPICC_FLUSH; /*!< SPICC Flush register, Address offset: 0x4 */
__IO uint32_t SPICC_INTR; /*!< SPICC Interrupt register, Address offset: 0x8 */
__IO uint32_t SPICC_RST_CUNT; /*!< SPICC Reset counter register, Address offset: 0xC */
__IO uint32_t SPICC_RD_EVT_CUNT; /*!< SPICC Read event counter register, Address offset: 0x10 */
__IO uint32_t SPICC_HIT_EVT_CUNT; /*!< SPICC Hit event counter register, Address offset: 0x14 */
__IO uint32_t SPICC_HIT_LSTW_EVT_CUNT; /*!< SPICC Hit lastway event counter register, Address offset: 0x18 */
__IO uint32_t SPICC_RD_PEND_CUNT; /*!< SPICC Read pending counter register, Address offset: 0x1C */
} SPIC_CACHE_TypeDef;
/** @} */
/** @} End of group AmebaZ_Peripheral_Registers_Structures */
/**************************************************************************//**
* @defgroup AmebaZ_Peripheral_Declaration AmebaZ Peripheral Declarations
* @{
*****************************************************************************/
#define UART0_DEV ((UART_TypeDef *) UART0_REG_BASE)
#define UART1_DEV ((UART_TypeDef *) UART1_REG_BASE)
#define UART2_DEV ((UART_TypeDef *) LOG_UART_REG_BASE)
#define SPI0_DEV ((SPI_TypeDef *) SPI0_REG_BASE)
#define SPI1_DEV ((SPI_TypeDef *) SPI1_REG_BASE)
#define SPIC ((SPIC_TypeDef *) SPI_FLASH_CTRL_BASE)
#define ADC ((ADC_TypeDef *) ADC_REG_BASE)
#define I2C0_DEV ((I2C_TypeDef *) I2C0_REG_BASE)
#define I2C1_DEV ((I2C_TypeDef *) I2C1_REG_BASE)
#define I2S_DEV ((I2S_TypeDef *) I2S0_REG_BASE)
#define TIM0 ((RTIM_TypeDef *) TIMER_REG_BASE)
#define TIM1 ((RTIM_TypeDef *) (TIMER_REG_BASE + 0x040))
#define TIM2 ((RTIM_TypeDef *) (TIMER_REG_BASE + 0x080))
#define TIM3 ((RTIM_TypeDef *) (TIMER_REG_BASE + 0x0C0))
#define TIM4 ((RTIM_TypeDef *) (TIMER_REG_BASE + 0x100))
#define TIM5 ((RTIM_TypeDef *) (TIMER_REG_BASE + 0x140))
#define RTC_DEV ((RTC_TypeDef *) (RTC_BASE);
#define PINMUX ((PINMUX_TypeDef *) PINMUX_REG_BASE)
#define GPIO ((GPIO_TypeDef *) GPIO_REG_BASE)
#define IPSEC ((IPSEC_TypeDef *) CRYPTO_REG_BASE)
#define USOC_REG ((USOC_REG_TypeDef *) USOC_REG_BASE)
#define NCO32k ((NCO32k_TypeDef *) NCO1_REG_BASE)
#define NCO8M ((NCO8M_TypeDef *) NCO2_REG_BASE)
#define BACKUP_REG ((BACKUP_REG_TypeDef *) BACKUP_REG_BASE)
#define SPIC_CACHE ((SPIC_CACHE_TypeDef *) SPIC_CACHE_BASE)
/** @} End of group AmebaZ_Peripheral_Declaration */
/** @} End of group AmebaZ_Outline */
#endif //_HAL_PLATFORM_
/******************* (C) COPYRIGHT 2016 Realtek Semiconductor *****END OF FILE****/

View file

@ -0,0 +1,160 @@
/*
* Routines to access hardware
*
* Copyright (c) 2013 Realtek Semiconductor Corp.
*
* This module is a confidential and proprietary property of RealTek and
* possession or use of this module requires written permission of RealTek.
*/
#ifndef _HAL_8710B_H_
#define _HAL_8710B_H_
#include "platform_autoconf.h"
#include "basic_types.h"
#include "section_config.h"
#include "memproc.h"
#include "rtl8710b_sys_on.h"
#include "rtl8711b_peri_on.h"
#include "hal_platform.h"
#include "rtl8710b_pinmux.h"
#include "rtl8711b_vector.h"
#include "rtl8711b_diag.h"
#include "rtl8711b_efuse.h"
#include "rtl8710b_soc_ps.h"
#include "diag.h"
#include "rtl_consol.h"
#include "rtl8711b_rcc.h"
#include "rtl8711b_cache.h"
#include "rtl8711b_syscfg.h"
#include "rtl8710b_pmc.h"
#include "rtl8710b_clk.h"
#include "rtl8710b_bor.h"
#include "rtl8711b_crypto.h"
#include "rtl8710b_crypto_api.h"
#include "rtl8710b_boot.h"
#include "rtl8710b_wl_on.h"
#include "rtl8711b_otf.h"
#include "rtl8711b_flash.h"
#include "rtl8710b_backup_reg.h"
#include "rtl8710b_pinmap.h"
#include "hal_api.h"
#define __CM3_REV 0x0200 /**< Core revision r0p0 */
#define __MPU_PRESENT 1 /**< Defines if an MPU is present or not */
#define __NVIC_PRIO_BITS 4 /**< Number of priority bits implemented in the NVIC */
#define __Vendor_SysTickConfig 1 /**< Vendor specific implementation of SysTickConfig is defined *///see vPortSetupTimerInterrupt
#if !defined (__FPU_PRESENT)
#define __FPU_PRESENT 1 /*!< FPU present */
#define __VFP_FP__ 1
#endif /* __FPU_PRESENT */
#if defined (ARM_CORE_CM4)
#include "core_cm4.h"
#elif defined (ARM_CORE_CM3)
#include "core_cm3.h"
#endif
#include "rtl8711b_gdma.h"
#include "rtl8711b_tim.h"
#include "rtl8711b_gpio.h"
#include "rtl8711b_ssi.h"
#include "rtl8711b_uart.h"
#include "rtl8711b_i2c.h"
#include "rtl8711b_i2s.h"
#include "rtl8711b_adc.h"
#include "rtl8710b_sdio.h"
#include "rtl8711b_wdg.h"
#include "rtl8710b_usb.h"
#include "rtl8710b_dongle.h"
#include "rtl8711b_otf.h"
#include "rtl8711b_rtc.h"
#include "rtl8710b_delay.h"
// firmware information, located at the header of Image2
#define FW_VERSION (0x0100)
#define FW_SUBVERSION (0x0001)
#define FW_CHIP_ID (0x8195)
#define FW_CHIP_VER (0x01)
#define FW_BUS_TYPE (0x01) // the iNIC firmware type: USB/SDIO
#define FW_INFO_RSV1 (0x00) // the firmware information reserved
#define FW_INFO_RSV2 (0x00) // the firmware information reserved
#define FW_INFO_RSV3 (0x00) // the firmware information reserved
#define FW_INFO_RSV4 (0x00) // the firmware information reserved
#define FLASH_RESERVED_DATA_BASE 0x8000 // reserve 32K for Image1
#define FLASH_SYSTEM_DATA_ADDR 0x9000 // reserve 32K+4K for Image1 + Reserved data
#define FLASH_OTA1_CODE_ADDR 0xB020
// Flash Map for Calibration data
#define FLASH_CAL_DATA_BASE 0xA000
#define FLASH_CAL_DATA_ADDR(_offset) (FLASH_CAL_DATA_BASE + _offset)
#define FLASH_CAL_DATA_SIZE 0x1000
#define FLASH_SECTOR_SIZE 0x1000
// SPIC Calibration Data
#define FLASH_USB_PARA_OFFSET 0x100
#define FLASH_USB_PARA_BASE (FLASH_SYSTEM_DATA_ADDR+FLASH_SPIC_PARA_OFFSET)
// ADC Calibration Data
#define FLASH_ADC_PARA_OFFSET 0x200
#define FLASH_ADC_PARA_BASE (FLASH_SYSTEM_DATA_ADDR+FLASH_ADC_PARA_OFFSET)
/* Spic_Mode */
#define ReadQuadIOMode 0
#define ReadQuadOMode 1
#define ReadDualIOMode 2
#define ReadDualOMode 3
#define ReadOneMode 4
#define IMAGE_HEADER_LEN 0x20
typedef struct {
u32 signature[2];
u32 image_size;
u32 image_addr;
/* reserved for extention */
u32 reserved[4];
} IMAGE_HEADER;
typedef struct {
u32 OTA2_FlashAddr;
u32 Valid_Image2;
u32 OTA1_ForceGpio;
u32 Rsvd1;
u32 RDP_FlashAddr;
u32 RDP_Len; /* not include check sum */
u32 Rsvd2;
u32 Rsvd3;
u16 Spic_Mode;
u16 Spic_Speed;
u16 Flash_ID;
u16 Flash_Size;
u16 Flash_Status;
u16 Rsvd4;
u32 Rsvd5;
/* uart log */
u32 UlogRate;
u32 UlogDbgEn;
u32 UlogRsvd2;
u32 UlogRsvd3;
} SYSTEM_DATA;
#define USE_FULL_ASSERT
#ifdef USE_FULL_ASSERT
/**
* @brief The assert_param macro is used for function's parameters check.
* @param expr: If expr is false, it calls assert_failed function which reports
* the name of the source file and the source line number of the call
* that failed. If expr is true, it returns no value.
* @retval None
*/
#define assert_param(expr) ((expr) ? (void)0 : io_assert_failed((uint8_t *)__FILE__, __LINE__))
/* Exported functions ------------------------------------------------------- */
void io_assert_failed(uint8_t* file, uint32_t line);
#else
#define assert_param(expr) ((void)0)
#endif /* USE_FULL_ASSERT */
#endif //_HAL_8710B_H_

View file

@ -0,0 +1,142 @@
/**
******************************************************************************
* @file rtl8710b_backup_reg.h
* @author
* @version V1.0.0
* @date 2016-05-17
* @brief This file provides firmware functions to manage the 16bytes backup registers
******************************************************************************
* @attention
*
* This module is a confidential and proprietary property of RealTek and
* possession or use of this module requires written permission of RealTek.
*
* Copyright(c) 2016, Realtek Semiconductor Corporation. All rights reserved.
******************************************************************************
*/
#ifndef _RTL8710B_BACKUP_REG_H_
#define _RTL8710B_BACKUP_REG_H_
/** @addtogroup AmebaZ_Platform
* @{
*/
/** @defgroup BKUP_REG
* @brief BKUP_REG driver modules
* @{
*/
/** @addtogroup BKUP_REG
* @verbatim
*****************************************************************************************
* Introduction
*****************************************************************************************
* backup register size:
* -16bytes (4 dwords)
*
* usage:
* - user can use this registers to save some data before reset happens
*
* backup register can not be reset by following functions:
* - cpu reset
* - system reset
* - soc sleep mode
* - soc deep standby mode
*
* backup register will be reset by following functions:
* - soc deep sleep mode
* - soc power down reset
* - soc power off
*
* system defined bits (other bits are reserved for user):
* - dword0[0]: watchdog reset or system reset (distinguish from BIT(5) by Software)
* - dword0[1]: BOR2 HW temp bit
* - dword0[2]: SW reserved
* - dword0[3]: this is SW set bit before reboot, for uart download
* - dword0[4]: this is SW set bit before reboot, for uart download debug
* - dword0[5]: this is SW set bit before reboot, for distinguish watchdog and system reset
* - dword0[6]: BOR2 HW temp bit
* - dword0[7]: 1: enable bor2 detection; 0: disable
*
*****************************************************************************************
* how to use
*****************************************************************************************
* BKUP_Write: write a dword backup register
* BKUP_Read: read a dword backup register
* BKUP_Set: set 1 to some bits of backup register
* BKUP_Clear: set 0 to some bits of backup register
*****************************************************************************************
* @endverbatim
*/
/* Exported constants --------------------------------------------------------*/
/** @defgroup BKUP_REG_Exported_Constants BKUP_REG Exported Constants
* @{
*/
/** @defgroup BKUP_REG_Idx_definitions
* @{
*/
#define BKUP_REG0 ((u32)0x00000000) /*!< bit0~bit5 is defined by system, other bits can be used by user */
#define BKUP_REG1 ((u32)0x00000001) /*!< all bits can be used by user */
#define BKUP_REG2 ((u32)0x00000002) /*!< all bits can be used by user */
#define BKUP_REG3 ((u32)0x00000003) /*!< all bits can be used by user */
#define IS_BKUP_REG(IDX) (((IDX) == BKUP_REG0) || \
((IDX) == BKUP_REG1) ||\
((IDX) == BKUP_REG2) ||\
((IDX) == BKUP_REG3))
/**
* @}
*/
/**
* @}
*/
/** @defgroup BKUP_REG_Exported_Functions BKUP_REG Exported Functions
* @{
*/
_LONG_CALL_ void BKUP_Write(u32 DwordIdx, u32 WriteVal);
_LONG_CALL_ u32 BKUP_Read(u32 DwordIdx);
_LONG_CALL_ void BKUP_Set(u32 DwordIdx, u32 BitMask);
_LONG_CALL_ void BKUP_Clear(u32 DwordIdx, u32 BitMask);
/**
* @}
*/
/* Registers Definitions --------------------------------------------------------*/
/**************************************************************************//**
* @defgroup BKUP_REG_Register_Definitions BKUP_REG Register Definitions
* @{
*****************************************************************************/
/**************************************************************************//**
* @defgroup BKUP_REG_WDORD0
* @{
*****************************************************************************/
#define BIT_SYS_BOR_DETECION BIT(7) /*!< 1: enable bor2 detection; 0: disable */
#define BIT_BOR2_RESET_TEMP BIT(6) /*!< BOR2 HW temp bit */
#define BIT_SYS_RESET_HAPPEN BIT(5) /*!< this is SW set bit before reboot, for distinguish watchdog and system reset */
#define BIT_UARTBURN_DEBUG BIT(4) /*!< this is SW set bit before reboot, for uart download debug */
#define BIT_UARTBURN_BOOT BIT(3) /*!< this is SW set bit before reboot, for uart download */
#define BIT_RTC_RESTORE BIT(2) /*!< this is SW set bit after rtc init */
#define BIT_BOR2_RESET_HAPPEN BIT(1) /*!< BOR2 (brown out reset) happen */
#define BIT_CPU_RESET_HAPPEN BIT(0) /*!< watchdog reset or system reset (distinguish from BIT(5) by Software) */
#define BIT_RTC_BACKUP ((u32)0x0000FF00) /*!< used to backup rtc year before reset */
/** @} */
/** @} */
/**
* @}
*/
/**
* @}
*/
#endif //_RTL8710B_BACKUP_REG_H_
/******************* (C) COPYRIGHT 2016 Realtek Semiconductor *****END OF FILE****/

View file

@ -0,0 +1,63 @@
#ifndef _HAL_8710B_BOOT_
#define _HAL_8710B_BOOT_
#if defined ( __ICCARM__ )
extern u8* __image2_entry_func__;
extern u8* __image2_validate_code__;
extern u8* __image1_bss_start__;
extern u8* __image1_bss_end__;
#else
extern u8 __image1_validate_code__[];
extern u8 __image1_bss_start__[];
extern u8 __image1_bss_end__[];
extern u8 __image2_entry_func__[];
extern u8 __image2_validate_code__[];
extern u8 __bss_start__[];
extern u8 __bss_end__[];
#endif
extern u8 __rom_bss_start__[];
extern u8 __rom_bss_end__[];
extern u8 __flash_text_start__[];
extern u8 __ram_start_table_start__[];
extern u8 __rom_top_4k_start_[];
enum _BOOT_TYPE_ {
BOOT_FROM_FLASH = 0,
BOOT_FROM_SDIO = 1,
BOOT_FROM_USB = 2,
BOOT_FROM_UART0 = 3,
BOOT_FROM_UART1 = 4,
BOOT_FROM_SPI = 5,
BOOT_FROM_RSVD = 6,
};
typedef struct {
u32 (*rdp_valid)(void);
int (*swd_off)(void);
int (*boot_system_init1)(void);
int (*boot_system_init2)(void);
u32 boot_ram_end;
} BOOT_EXPORT_SYMB_TABLE;
_LONG_CALL_ VOID SPI_Boot_ROM(VOID);
_LONG_CALL_ VOID UARTIMG_Download(u8 uart_idx);
_LONG_CALL_ VOID USB_Boot_ROM(VOID);
_LONG_CALL_ VOID SDIO_Boot_Up(VOID);
_LONG_CALL_ VOID BOOT_ROM_ShowBuildInfo(u32 Complete);
#ifdef CONFIG_KERNEL
extern void vPortSVCHandler( void );
//extern void xPortPendSVHandler( void );
extern void xPortSysTickHandler( void );
#if defined (__ICCARM__)
extern void xPortPendSVHandler( void );
#elif defined (__GNUC__)
extern void xPortPendSVHandler( void ) __attribute__ (( naked ));
#endif
#endif
extern void BOOT_FLASH_Image1(void);
extern u32 BOOT_FLASH_RDP_VALID(void);
extern BOOT_EXPORT_SYMB_TABLE boot_export_symbol;
#endif //_HAL_8710B_BOOT_

View file

@ -0,0 +1,116 @@
/**
******************************************************************************
* @file rtl8711b_bor.h
* @author
* @version V1.0.0
* @date 2016-05-17
* @brief This file contains all the functions prototypes for the bor2.
******************************************************************************
* @attention
*
* This module is a confidential and proprietary property of RealTek and
* possession or use of this module requires written permission of RealTek.
*
* Copyright(c) 2016, Realtek Semiconductor Corporation. All rights reserved.
******************************************************************************
*/
#ifndef _RTL8710B_BOR_H_
#define _RTL8710B_BOR_H_
/** @addtogroup AmebaZ_Periph_Driver
* @{
*/
/** @defgroup BOR
* @brief BOR driver modules
* @{
*/
/** @addtogroup BOR
* @verbatim
*****************************************************************************************
* Introduction
*****************************************************************************************
* functions:
* - set bor2 mode
* - enable/disable bor2 intr
* - register bor2 intr handler
*
*****************************************************************************************
* How to use BOR2
*****************************************************************************************
* To use the BOR2 mode, the following steps are mandatory:
*
* 1. Choose bor2 mode using the follwoing functions.
* BOR2_ModeSet(u32 Option);
*
* 2. If Choose bor2 Interrupt mode, register bor2 Interrupt handler using the follwoing functions.
* BOR2_INTRegister(void *bor_intr_hook_fun);
*
* 3. Enable bor2 using the follwoing functions.
* BOR2_INTCmd(ENABLE);
*
*****************************************************************************************
* @endverbatim
*/
/* Exported types ------------------------------------------------------------*/
/** @defgroup BOR2_Exported_Types BOR2 Exported Types
* @{
*/
/**
* @brief BOR_IRQ_FUN function definition
*/
typedef void (*BOR_IRQ_FUN)(void);
/**
* @}
*/
/**
* @}
*/
/** @defgroup BOR2_Exported_Constants BOR2 Exported Constants
* @{
*/
/* Exported constants ------------------------------------------------------------*/
/** @defgroup BOR2_Mode_definitions
* @{
*/
#define BOR2_RESET ((u32)(0x00000001 << 0))
#define BOR2_INTR ((u32)(0x00000001 << 1))
/**
* @}
*/
/**
* @}
*/
/** @defgroup BOR2_Exported_Functions BOR2 Exported Functions
* @{
*/
VOID BOR2_INTRegister(void *bor_intr_hook_fun);
VOID BOR2_INTCmd(u32 NewStatus);
VOID BOR2_ModeSet(u32 Option);
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
#endif //_RTL8710B_BOR_H_
/******************* (C) COPYRIGHT 2016 Realtek Semiconductor *****END OF FILE****/

View file

@ -0,0 +1,426 @@
/**
******************************************************************************
* @file rtl8711b_clk.h
* @author
* @version V1.0.0
* @date 2016-05-17
* @brief This file provides firmware functions to manage the following
* functionalities of clock control:
* - NCO32K clock
* - NCO8M clock
* - CPU clock
* - XTAL clock get
* - OSC32K clock
* - EXT32K clock
******************************************************************************
* @attention
*
* This module is a confidential and proprietary property of RealTek and
* possession or use of this module requires written permission of RealTek.
*
* Copyright(c) 2015, Realtek Semiconductor Corporation. All rights reserved.
******************************************************************************
*/
#ifndef _RTL8710B_CLK_H_
#define _RTL8710B_CLK_H_
/** @addtogroup AmebaZ_Platform
* @{
*/
/** @defgroup CLOCK
* @brief CLOCK driver modules
* @{
*/
/** @addtogroup CLOCK
* @verbatim
*****************************************************************************************
* NCO32K
*****************************************************************************************
* -RTC clock in
* -TIM0-TIM3 clock in
* -WIFI 32K clock in
*****************************************************************************************
* OSC32K OSC8M
*****************************************************************************************
* -OSC32K is used to calibration OSC8M
* -OSC8M is used for LP UART when SOC suspend and close XTAL
*****************************************************************************************
*****************************************************************************************
* NCO8M
*****************************************************************************************
* -used for LP UART when SOC active
* -Clock in is XTAL (40MHz)
* -Clock out is 8MHz
*
*****************************************************************************************
* CPU clock
*****************************************************************************************
* -CLK_125M: 125000000
* -CLK_62_5M: 62500000
* -CLK_31_25M: 31250000
* -CLK_16_625M: 15625000
* -CLK_XTAL: XTAL
* -CLK_ANA_4M: 4000000
*
*****************************************************************************************
* XTAL clock
*****************************************************************************************
* -Get XTAL clock from EFUSE setting:
* -40000000
* -25000000
* -13000000
* -19200000
* -20000000
* -26000000
* -38400000
* -17664000
* -16000000
* -14318000
* -12000000
* -52000000
* -48000000
* -26000000
* -27000000
* -24000000
*****************************************************************************************
* EXT32K
*****************************************************************************************
* -External 32K: 32K clock from external 32k source
* -Internal 32K: 32K clock from internal 32K source: NCO32K
*
*****************************************************************************************
* @endverbatim
*/
/* Exported constants --------------------------------------------------------*/
/** @defgroup CLK_Exported_Constants CLK Exported Constants
* @{
*/
/** @defgroup CPU_CLK_definitions
* @{
*/
#define CLK_125M 0
#define CLK_62_5M 1
#define CLK_31_25M 2
#define CLK_16_625M 3
#define CLK_XTAL 4
#define CLK_ANA_4M 5
/**
* @}
*/
/** @defgroup OSC32K_CLK_definitions
* @note just used by function OSC32K_Calibration or OSC8M_Calibration
* @{
*/
#define OSC32K_CALI_32KCYC_004 0
#define OSC32K_CALI_32KCYC_008 1
#define OSC32K_CALI_32KCYC_016 2
#define OSC32K_CALI_32KCYC_032 3
#define OSC32K_CALI_32KCYC_064 4
#define OSC32K_CALI_32KCYC_128 5
#define OSC32K_CALI_32KCYC_256 6
#define OSC32K_CALI_32KCYC_512 7
/**
* @}
*/
/** @defgroup OSC8M_CLK_definitions
* @note just used by function OSC8M_Calibration
* @{
*/
#define OSC8M_8388608HZ 0
#define OSC8M_8192000HZ 1
#define OSC8M_8000000HZ 2
#define OSC8M_16777216HZ 3
/**
* @}
*/
/**
* @}
*/
/* Exported functions --------------------------------------------------------*/
/** @defgroup NCO32K_CLK_Exported_Functions NCO32K_CLK Exported Functions
* @{
*/
_LONG_CALL_ void NCO32K_Init(u32 clk_out, u32 clk_ref, u8 calibration_cycles, u8 calibration_thrs);
/**
* @}
*/
/** @defgroup EXT32K_CLK_Exported_Functions EXT32K_CLK Exported Functions
* @{
*/
_LONG_CALL_ void EXT32K_Cmd(u32 NewStatus);
/**
* @}
*/
/** @defgroup NCO8M_CLK_Exported_Functions NCO8M_CLK Exported Functions
* @{
*/
_LONG_CALL_ void NCO8M_Init(u32 clk_ref_M, u32 clk_out_M);
_LONG_CALL_ void NCO8M_Cmd(u32 NewState);
/**
* @}
*/
/** @defgroup CPU_CLK_Exported_Functions CPU_CLK Exported Functions
* @{
*/
_LONG_CALL_ u32 CPU_ClkGet(u8 Is_FPGA);
_LONG_CALL_ void CPU_ClkSet(u8 CpuType);
/**
* @}
*/
/** @defgroup XTAL_CLK_Exported_Functions XTAL_CLK Exported Functions
* @{
*/
_LONG_CALL_ u32 XTAL_ClkGet(void);
/**
* @}
*/
/** @defgroup OSC_CLK_Exported_Functions OSC_CLK Exported Functions
* @{
*/
_LONG_CALL_ void OSC8M_Calibration(u32 LOG_EN, u32 CaliCycles, u32 TargetClock);
_LONG_CALL_ void OSC32K_Calibration(u32 LOG_EN, u32 CaliCycles);
_LONG_CALL_ void OSC32K_Cmd(u32 NewStatus);
_LONG_CALL_ u32 OSC8M_Get(void);
/**
* @}
*/
/** @defgroup ISO_CTL_Exported_Functions ISO_CTL Exported Functions
* @{
*/
_LONG_CALL_ void ISO_Set(u32 BitMask, u32 NewState);
/**
* @}
*/
/** @defgroup PLL_Exported_Functions PLL Exported Functions
* @{
*/
_LONG_CALL_ void PLL0_Set(u32 BitMask, u32 NewState);
_LONG_CALL_ void PLL1_Set(u32 BitMask, u32 NewState);
_LONG_CALL_ void PLL2_Set(u32 BitMask, u32 NewState);
_LONG_CALL_ void PLL3_Set(u32 BitMask, u32 NewState);
/**
* @}
*/
/** @defgroup XTAL_CTL_Exported_Functions XTAL_CTL Exported Functions
* @{
*/
_LONG_CALL_ void XTAL0_Set(u32 BitMask, u32 NewState);
_LONG_CALL_ void XTAL1_Set(u32 BitMask, u32 NewState);
_LONG_CALL_ void XTAL2_Set(u32 BitMask, u32 NewState);
/**
* @}
*/
/* Registers Definitions --------------------------------------------------------*/
/**************************************************************************//**
* @defgroup CLK_Register_Definitions CLK Register Definitions
* @{
*****************************************************************************/
/**************************************************************************//**
* @defgroup NCO1_CLK_INFO
* @{
*****************************************************************************/
#define NCO1_BIT_32K_CLK_OUT_RDY (0x00000001 << 24)
/** @} */
/**************************************************************************//**
* @defgroup NCO1_CTRL
* @{
*****************************************************************************/
#define NCO1_BIT_32K_CLK_EN (0x00000001 << 16)
#define NCO1_BIT_REF_CLK_EN (0x00000001 << 17)
#define NCO1_BIT_CALI_CYCLES (0x00F00000)
#define NCO1_BIT_CALI_THRS (0x7F000000)
/** @} */
/**************************************************************************//**
* @defgroup NCO8M
* @{
*****************************************************************************/
#define NCO2_BIT_OUT_CLK_EN (0x00000001)
/** @} */
/**************************************************************************//**
* @defgroup REG_SYS_CLK_CTRL0
* @{
*****************************************************************************/
#define BIT_SOC_OCP_IOBUS_CK_EN (0x00000001 << 2)
#define BIT_SYSON_CK_EELDR_EN (0x00000001 << 1)
#define BIT_SYSON_CK_SYSREG_EN (0x00000001 << 0)
/** @} */
/**************************************************************************//**
* @defgroup REG_SYS_CLK_CTRL1
* @{
*****************************************************************************/
#define BIT_PESOC_EXT32K_CK_SEL (0x00000001 << 8)
#define BIT_PESOC_OCP_CPU_CK_SEL (0x00000007 << 4)
#define BIT_PESOC_EELDR_CK_SEL (0x00000001 << 0)
/** @} */
/**************************************************************************//**
* @defgroup REG_SYS_XTAL_CTRL0
* @{
*****************************************************************************/
#define BIT_SYS_XTAL_XQSEL_RF (0x00000001 << 31)
#define BIT_SYS_XTAL_GATED_OK0 (0x00000001 << 30)
#define BIT_SYS_XTAL_SC_XO(x) (((x) & 0x0000003f) << 24)
#define BIT_SYS_XTAL_SC_XI(x) (((x) & 0x0000003f) << 18)
#define BIT_SYS_XTAL_GMN(x) (((x) & 0x0000001f) << 13)
#define BIT_SYS_XTAL_GMP(x) (((x) & 0x0000001f) << 8)
#define BIT_SYS_XTAL_GSPL_EN (0x00000001 << 4) /*!< 1: Gate PLL ref clock from XTAL ; 0: not gated */
#define BIT_SYS_XTAL_EN (0x00000001 << 1)
#define BIT_SYS_XTAL_BGMB_EN (0x00000001 << 0)
/** @} */
/**************************************************************************//**
* @defgroup REG_SYS_XTAL_CTRL1
* @{
*****************************************************************************/
#define BIT_SYS_XTAL_DELAY_SYSPLL (0x00000001 << 25)
#define BIT_SYS_XTAL_DELAY_USB (0x00000001 << 24)
#define BIT_SYS_XTAL_DELAY_WLAFE (0x00000001 << 23)
#define BIT_SYS_XTAL_EN_AAC_GM (0x00000001 << 21)
#define BIT_SYS_XTAL_EN_AAC_PEAKDET (0x00000001 << 20)
#define BIT_SYS_XTAL_AGPIO(x) (((x) & 0x00000001) << 17)
#define BIT_SYS_XTAL_DRV_SYSPLL(x) (((x) & 0x00000003) << 15)
#define BIT_SYS_XTAL_GATE_SYSPLL (0x00000001 << 14)
#define BIT_SYS_XTAL_DRV_USB(x) (((x) & 0x00000003) << 12)
#define BIT_SYS_XTAL_GATE_USB (0x00000001 << 11)
#define BIT_SYS_XTAL_DRV_WLAFE(x) (((x) & 0x00000003) << 9)
#define BIT_SYS_XTAL_GATE_WLAFE (0x00000001 << 8)
#define BIT_SYS_XTAL_DRV_RF2(x) (((x) & 0x00000003) << 6)
#define BIT_SYS_XTAL_GATE_RF2 (0x00000001 << 5)
#define BIT_SYS_XTAL_DRV_RF1(x) (((x) & 0x00000003) << 3)
#define BIT_SYS_XTAL_GATE_RF1 (0x00000001 << 2)
#define BIT_SYS_XTAL_LDO(x) (((x) & 0x00000003) << 0)
/** @} */
/**************************************************************************//**
* @defgroup REG_SYS_SYSPLL_CTRL0
* @{
*****************************************************************************/
#define BIT_SYS_SYSPLL_CKTST_EN (0x00000001 << 22)
#define BIT_SYS_SYSPLL_MONCK_SEL(x) (((x) & 0x00000007) << 19)
#define BIT_SYS_SYSPLL_CP_IOFFSET(x) (((x) & 0x0000001f) << 14)
#define BIT_SYS_SYSPLL_FREF_EDGE (0x00000001 << 9)
#define BIT_SYS_SYSPLL_EN (0x00000001 << 1)
#define BIT_SYS_SYSPLL_LVPC_EN (0x00000001 << 0)
/** @} */
/**************************************************************************//**
* @defgroup REG_SYS_SYSPLL_CTRL1
* @{
*****************************************************************************/
#define BIT_SYS_SYSPLL_CL200M_SEL (0x00000001 << 17) /*!< 1:200MHz, 0:166.666MHz */
#define BIT_SYS_SYSPLL_CK500K_SEL (0x00000001 << 15) /*!< 1:external source 0:PLL */
#define BIT_SYS_SYSPLL_CK200M_EN (0x00000001 << 14) /*!< 1: enable CK200M */
#define BIT_SYS_SYSPLL_CKSDR_EN (0x00000001 << 13) /*!< 1: enable CK_SDRAM */
#define BIT_SYS_SYSPLL_CKSDR_DIV (0x00000003 << 11) /*!< SDR PLL select: 00/01/10/11 no clock/25M/50M/100M */
#define BIT_SYS_SYSPLL_CK24P576_EN (0x00000001 << 10) /*!< 1:enable CK24.576M PLL */
#define BIT_SYS_SYSPLL_CK22P5792_EN (0x00000001 << 9) /*!< 1: enable CK22.5792M PLL */
#define BIT_SYS_SYSPLL_CK83P33M_EN (0x00000001 << 8) /*!< 1: enable CK83.33M PLL */
#define BIT_SYS_SYSPLL_CK_PS_EN (0x00000001 << 7) /*!< reg_ps_en Enable phase shift */
#define BIT_SYS_SYSPLL_CK_PS_SEL (0x00000007 << 4) /*!< "decide clock phase when reg_ps_enb = 1000/001¡­/111: phase 0, 45¡­315 */
/** @} */
/**************************************************************************//**
* @defgroup REG_SYS_SYSPLL_CTRL2
* @{
*****************************************************************************/
#define BIT_SYS_SYSPLL_CK_ADC_EN (0x00000001 << 25) /*!< Set ADC PLL EN */
/** @} */
/**************************************************************************//**
* @defgroup REG_SYS_SYSPLL_CTRL3
* @{
*****************************************************************************/
#define BIT_DIV_SEL (0x000001FF << 6) /*!< The period of signal CK500M_SYNC/CK500M_PS_SYNC is: (r_DIV_SEL[8:0] + 2) cycles of 500MHz clock */
#define BIT_PHASE_SEL (0x00000007 << 3) /*!< Phase selection for CK_500M_PS 0: 0, 1: 45, 2: 90, 3: 135, 4: 180, 5: 225, 6: 270, 7: 315 */
#define BIT_EN_CK_500M_PS (0x00000001 << 2) /*!< 1: enable PLL 500M phase shift clock; 0: disable, Enable this bit when use FLASH_CalibrationPhase */
#define BIT_EN_CK_500M (0x00000001 << 1) /*!< 1: enable PLL 500M clock; 0: disable, HW auto enable this bit */
/** @} */
/**************************************************************************//**
* @defgroup REG_OSC32K_CTRL
* @{
*****************************************************************************/
#define BIT_SYS_OSC32K_POW_CKGEN (0x00000001 << 0) /*!< 1: enable OSC 32K clock generator; 0: turn off OSC 32K clock gen */
#define BIT_SYS_OSC32K_OUT_SEL (0x00000001 << 1) /*!< 1: New Calibration Mode(REGUOUT=OSCIN=8M) 0: Original Calibration Mode (REGUOUT=OSCIN=32k) */
#define BIT_SYS_OSC32K_RESISTOR_COM (0x00000003 << 2) /*!< Compensate resistor control */
#define BIT_SYS_OSC32K_CKE_8M (0x00000001 << 4) /*!< 1: osc 8m clk is enabled */
#define BIT_SYS_OSC32K_CKE_FREF (0x00000001 << 5) /*!< 1: referece 25M clk is enabled */
#define BIT_32K_BIAS_CURRENT (0x0000FFFF << 16) /*! Bias current control */
/** @} */
/**************************************************************************//**
* @defgroup REG_OSC32K_REG_CTRL0
* @{
*****************************************************************************/
#define BIT_32K_REG_INDIRT_CMD (0x00000001 << 23) /*!< 1: write command, 0: read command */
#define BIT_32K_REG_INDIRT_ADDR (0x0000003F << 16)
#define BIT_32K_REG_INDIRT_WDATA (0x0000FFFF << 0)
/** @} */
/**************************************************************************//**
* @defgroup REG_OSC32K_REG_CTRL0
* @{
*****************************************************************************/
#define BIT_32K_REG_INDIRT_RDATA (0x0000FFFF << 0) /*!< 32K OSC register indirect read data */
/** @} */
/** @} */
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/* Other definations --------------------------------------------------------*/
extern u32 NCO32K_Enable;
/**
* @brief Configures NCO 32K monitor function
* @param NewStatus: Disable/Enable
* @note you should disable monitor when XTAL 40M close
*/
static inline void NCO32K_Monitor(u32 NewStatus)
{
if (NewStatus == ENABLE) {
NCO32k->CTRL |= NCO1_BIT_REF_CLK_EN;
} else {
NCO32k->CTRL &= ~NCO1_BIT_REF_CLK_EN;
}
}
#endif //_RTL8710B_CLK_H_
/******************* (C) COPYRIGHT 2016 Realtek Semiconductor *****END OF FILE****/

View file

@ -0,0 +1,204 @@
/**
******************************************************************************
* @file rtl8710b_crypto_api_rom.h
* @author
* @version V1.0.0
* @date 2016-05-17
* @brief This file provides firmware functions to manage the following
* functionalities of the HW crypto:
* - Initialization
* - MD5
* - SHA1/SHA2
* - HMAC
* - AES CBC/ECB/CTR
* - 3DES CBC/ECB
* - DES CBC/ECB
******************************************************************************
* @attention
*
* This module is a confidential and proprietary property of RealTek and
* possession or use of this module requires written permission of RealTek.
*
* Copyright(c) 2015, Realtek Semiconductor Corporation. All rights reserved.
******************************************************************************
*/
#ifndef __RTL8710B_CRYPTO_API_H__
#define __RTL8710B_CRYPTO_API_H__
/** @addtogroup AmebaZ_Periph_Driver
* @{
*/
/** @defgroup CRYPTO
* @brief CRYPTO driver modules
* @{
*/
/** @addtogroup CRYPTO
* @verbatim
*****************************************************************************************
* Introduction
*****************************************************************************************
* -Authentication or Cipher use hardware to improve data process performance
*
*****************************************************************************************
* Authentication
*****************************************************************************************
* -MD5
* -SHA1
* -SHA2
* -HMAC-MD5
* -HMAC-SHA1
* -HMAC-SHA2
*
*****************************************************************************************
*****************************************************************************************
* Cipher
*****************************************************************************************
* -AES-CBC
* -AES-ECB
* -AES-CTR
* -3DES-CBC
* -3DES-ECB
* -DES-CBC
* -DES-ECB
*
*****************************************************************************************
* How to use
*****************************************************************************************
* -call rtl_cryptoEngine_init to open IPSEC function & clock
*
* -call following API for set key:
* -rtl_crypto_xxx_init
*
* -call following API for encrypt decrypt:
* -rtl_crypto_xxx_process or
*
* -rtl_crypto_xxx_encrypt
* -rtl_crypto_xxx_decrypt
*
*
*****************************************************************************************
* @endverbatim
*/
/* Exported constants --------------------------------------------------------*/
/** @defgroup CRYPTO_Exported_Constants CRYPTO Exported Constants
* @{
*/
/** @defgroup CRYPTO_Process_Status_definitions
* @{
*/
#define _ERRNO_CRYPTO_DESC_NUM_SET_OutRange -2
#define _ERRNO_CRYPTO_BURST_NUM_SET_OutRange -3
#define _ERRNO_CRYPTO_NULL_POINTER -4
#define _ERRNO_CRYPTO_ENGINE_NOT_INIT -5
#define _ERRNO_CRYPTO_ADDR_NOT_4Byte_Aligned -6
#define _ERRNO_CRYPTO_KEY_OutRange -7
#define _ERRNO_CRYPTO_MSG_OutRange -8
#define _ERRNO_CRYPTO_IV_OutRange -9
#define _ERRNO_CRYPTO_AUTH_TYPE_NOT_MATCH -10
#define _ERRNO_CRYPTO_CIPHER_TYPE_NOT_MATCH -11
#define _ERRNO_CRYPTO_KEY_IV_LEN_DIFF -12
/**
* @}
*/
/**
* @}
*/
/* Exported functions --------------------------------------------------------*/
/** @defgroup cryptoEngine_Exported_Functions cryptoEngine Exported Functions
* @{
*/
_LONG_CALL_ int rtl_cryptoEngine_init(void);
_LONG_CALL_ void rtl_cryptoEngine_info(void);
/**
* @}
*/
/** @defgroup Authentication_Exported_Functions Authentication Exported Functions
* @{
*/
_LONG_CALL_ int rtl_crypto_md5(IN const u8* message, IN const u32 msglen, OUT u8* pDigest);
_LONG_CALL_ int rtl_crypto_md5_init(void);
_LONG_CALL_ int rtl_crypto_md5_process(IN const u8* message, const IN u32 msglen, OUT u8* pDigest);
_LONG_CALL_ int rtl_crypto_sha1(IN const u8* message, IN const u32 msglen, OUT u8* pDigest);
_LONG_CALL_ int rtl_crypto_sha1_init(void);
_LONG_CALL_ int rtl_crypto_sha1_process(IN const u8* message, IN const u32 msglen, OUT u8* pDigest);
_LONG_CALL_ int rtl_crypto_sha2(IN const SHA2_TYPE sha2type, IN const u8* message, IN const u32 msglen, OUT u8* pDigest);
_LONG_CALL_ int rtl_crypto_sha2_init(IN const SHA2_TYPE sha2type);
_LONG_CALL_ int rtl_crypto_sha2_process(IN const u8* message, IN const u32 msglen, OUT u8* pDigest);
_LONG_CALL_ int rtl_crypto_hmac_md5(IN const u8* message, IN const u32 msglen, IN const u8* key, IN const u32 keylen, OUT u8* pDigest);
_LONG_CALL_ int rtl_crypto_hmac_md5_init(IN const u8* key, IN const u32 keylen);
_LONG_CALL_ int rtl_crypto_hmac_md5_process(IN const u8* message, IN const u32 msglen, OUT u8* pDigest);
_LONG_CALL_ int rtl_crypto_hmac_sha1(IN const u8* message, IN const u32 msglen, IN const u8* key, IN const u32 keylen, OUT u8* pDigest);
_LONG_CALL_ int rtl_crypto_hmac_sha1_init(IN const u8* key, IN const u32 keylen);
_LONG_CALL_ int rtl_crypto_hmac_sha1_process(IN const u8* message, IN const u32 msglen, OUT u8* pDigest);
_LONG_CALL_ int rtl_crypto_hmac_sha2(IN const SHA2_TYPE sha2type, IN const u8* message, IN const u32 msglen, IN const u8* key, IN const u32 keylen, OUT u8* pDigest);
_LONG_CALL_ int rtl_crypto_hmac_sha2_init(IN const SHA2_TYPE sha2type, IN const u8* key, IN const u32 keylen);
_LONG_CALL_ int rtl_crypto_hmac_sha2_process(IN const u8* message, IN const u32 msglen, OUT u8* pDigest);
/**
* @}
*/
/** @defgroup Cipher_Exported_Functions Cipher Exported Functions
* @{
*/
_LONG_CALL_ int rtl_crypto_aes_cbc_init(IN const u8* key, IN const u32 keylen);
_LONG_CALL_ int rtl_crypto_aes_cbc_encrypt(IN const u8* message, IN const u32 msglen, IN const u8* iv, IN const u32 ivlen, OUT u8* pResult);
_LONG_CALL_ int rtl_crypto_aes_cbc_decrypt(IN const u8* message, IN const u32 msglen, IN const u8* iv, IN const u32 ivlen, OUT u8* pResult);
_LONG_CALL_ int rtl_crypto_aes_ecb_init(IN const u8* key, IN const u32 keylen);
_LONG_CALL_ int rtl_crypto_aes_ecb_encrypt(IN const u8* message, IN const u32 msglen, IN const u8* iv, IN const u32 ivlen, OUT u8* pResult);
_LONG_CALL_ int rtl_crypto_aes_ecb_decrypt(IN const u8* message, IN const u32 msglen, IN const u8* iv, IN const u32 ivlen, OUT u8* pResult);
_LONG_CALL_ int rtl_crypto_aes_ctr_init(IN const u8* key, IN const u32 keylen);
_LONG_CALL_ int rtl_crypto_aes_ctr_encrypt(IN const u8* message, IN const u32 msglen, IN const u8* iv, IN const u32 ivlen, OUT u8* pResult);
_LONG_CALL_ int rtl_crypto_aes_ctr_decrypt(IN const u8* message, IN const u32 msglen, IN const u8* iv, IN const u32 ivlen, OUT u8* pResult);
_LONG_CALL_ int rtl_crypto_3des_cbc_init(IN const u8* key, IN const u32 keylen);
_LONG_CALL_ int rtl_crypto_3des_cbc_encrypt(IN const u8* message, IN const u32 msglen, IN const u8* iv, IN const u32 ivlen, OUT u8* pResult);
_LONG_CALL_ int rtl_crypto_3des_cbc_decrypt(IN const u8* message, IN const u32 msglen, IN const u8* iv, IN const u32 ivlen, OUT u8* pResult);
_LONG_CALL_ int rtl_crypto_3des_ecb_init(IN const u8* key, IN const u32 keylen);
_LONG_CALL_ int rtl_crypto_3des_ecb_encrypt(IN const u8* message, IN const u32 msglen, IN const u8* iv, IN const u32 ivlen, OUT u8* pResult);
_LONG_CALL_ int rtl_crypto_3des_ecb_decrypt(IN const u8* message, IN const u32 msglen, IN const u8* iv, IN const u32 ivlen, OUT u8* pResult);
_LONG_CALL_ int rtl_crypto_des_cbc_init(IN const u8* key, IN const u32 keylen);
_LONG_CALL_ int rtl_crypto_des_cbc_encrypt(IN const u8* message, IN const u32 msglen, IN const u8* iv, IN const u32 ivlen, OUT u8* pResult);
_LONG_CALL_ int rtl_crypto_des_cbc_decrypt(IN const u8* message, IN const u32 msglen, IN const u8* iv, IN const u32 ivlen, OUT u8* pResult);
_LONG_CALL_ int rtl_crypto_des_ecb_init(IN const u8* key, IN const u32 keylen);
_LONG_CALL_ int rtl_crypto_des_ecb_encrypt(IN const u8* message, IN const u32 msglen, IN const u8* iv, IN const u32 ivlen, OUT u8* pResult);
_LONG_CALL_ int rtl_crypto_des_ecb_decrypt(IN const u8* message, IN const u32 msglen, IN const u8* iv, IN const u32 ivlen, OUT u8* pResult);
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
#endif /* __RTL8710B_CRYPTO_API_H__ */
/******************* (C) COPYRIGHT 2016 Realtek Semiconductor *****END OF FILE****/

View file

@ -0,0 +1,81 @@
/**
******************************************************************************
* @file rtl8710b_delay.h
* @author
* @version V1.0.0
* @date 2016-05-17
* @brief This file provides firmware functions to manage the following
* functionalities of the systimer & delay:
* - SYSTIMER_GetPassTime
* - SYSTIMER_TickGet
* - DelayUs
* - DelayMs
* - DelayNop
******************************************************************************
* @attention
*
* This module is a confidential and proprietary property of RealTek and
* possession or use of this module requires written permission of RealTek.
*
* Copyright(c) 2016, Realtek Semiconductor Corporation. All rights reserved.
******************************************************************************
*/
#ifndef _8710B_DELAY_H_
#define _8710B_DELAY_H_
/** @addtogroup AmebaZ_Platform
* @{
*/
/** @defgroup DELAY
* @brief DELAY driver modules
* @{
*/
/** @addtogroup DELAY
* @verbatim
*****************************************************************************************
* Delay
*****************************************************************************************
* - DelayUs
* - DelayMs
* - DelayNop
*
*****************************************************************************************
* Sys Timer
*****************************************************************************************
* - TIM0 is used as systimer, so TIM0 can not be used for other purpose
* - init when boot in rom code
* - resolution is 31us
* - you can get timer tick use SYSTIMER_TickGet, every tick is 31us
* - you can get passing time use SYSTIMER_GetPassTime in ms
*
*****************************************************************************************
* @endverbatim
*/
/** @defgroup DELAY_Exported_Functions DELAY Exported Functions
* @{
*/
_LONG_CALL_ void SYSTIMER_Init(void);
_LONG_CALL_ u32 SYSTIMER_TickGet(void);
_LONG_CALL_ u32 SYSTIMER_GetPassTime(u32 start);
_LONG_CALL_ void DelayUs(u32 us);
_LONG_CALL_ void DelayMs(u32 ms);
_LONG_CALL_ void DelayNop(u32 count);
#define HalDelayUs DelayUs
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
#endif//_8710B_DELAY_H_
/******************* (C) COPYRIGHT 2016 Realtek Semiconductor *****END OF FILE****/

View file

@ -0,0 +1,221 @@
/**
******************************************************************************
* @file rtl8711b_rtc.h
* @author
* @version V1.0.0
* @date 2016-05-17
* @brief This file contains all the functions prototypes for the WDG firmware
* library.
******************************************************************************
* @attention
*
* This module is a confidential and proprietary property of RealTek and
* possession or use of this module requires written permission of RealTek.
*
* Copyright(c) 2016, Realtek Semiconductor Corporation. All rights reserved.
******************************************************************************
*/
#ifndef _RTL8710B_DONGLE_H_
#define _RTL8710B_DONGLE_H_
/** @addtogroup AmebaZ_Periph_Driver
* @{
*/
/** @defgroup DONGLE
* @brief DONGLE driver modules
* @{
*/
/** @addtogroup DONGLE
* @verbatim
*****************************************************************************************
* Introduction
*****************************************************************************************
* functions:
* - init usb to dongle mode
* - usb dongle read/write efuse
* - usb dongle read/write flash
*
*****************************************************************************************
* How to use DONGLE
*****************************************************************************************
* ROM boot use it, user don't use if no needed.
*
*****************************************************************************************
* Host indrect access guide
*****************************************************************************************
*
* read flash
* 1) write 0x80F8: 0x00xxxxxx =>xxxxxx is flash address
* 2) write 0x806C: 0x80000000
* 3) poll bit31
* 4) read 0x809C: 0xyyyyyyyy => yyyyyyyy is flash data
*
* write flash
* 1) write 0x80F8: 0x00xxxxxx =>xxxxxx is flash address
* 2) write 0x809C: 0xyyyyyyyy =>yyyyyyyy is flash data
* 3) write 0x806C: 0x81000000
* 4) poll bit31
*
* flash erase
* 1) write 0x80F8: 0x00xxxxxx =>xxxxxx is flash address
* 2) write 0x806C: 0x82000000
* 3) poll bit31
*
*
* read any register
* 1) write 0x80F8: 0xxxxxxxxx =>xxxxxx is register complete address
* 2) write 0x806C: 0x83000000
* 3) poll bit31
* 4) read 0x809C: 0xyyyyyyyy => yyyyyyyy is register data
*
* write any register
* 1) write 0x80F8: 0xxxxxxxxx =>xxxxxx is register complete address
* 2) write 0x809C: 0xyyyyyyyy =>yyyyyyyy is register data
* 3) write 0x806C: 0x84000000
* 4) poll bit31
*
* efuse read
* 1) write 0x80F8: 0x000000xx =>xx is efuse physical address
* 2) write 0x806C: 0x85000000
* 3) poll bit31
* 4) read 0x809C: 0x000000yy => yy is efuse physical data
*
* efuse write
* 1) write 0x80F8: 0x000000xx =>xx is efuse physical address
* 2) write 0x809C: 0x000000yy => yy is efuse physical data
* 3) write 0x806C: 0x86000000
* 4) poll bit31
*
*****************************************************************************************
* @endverbatim
*/
/* Exported types ------------------------------------------------------------*/
/** @defgroup DONGLE_Exported_Types DONGLE Exported Types
* @{
*/
/**
* @brief DONGLE Init structure definition
*/
typedef struct {
void (*usb_dongle_interrupt)(void); /*!< USOC_DongleIsr_RAM function in RAM */
} DONGLE_InitTypeDef;
/**
* @brief DONGLE ROM_Patch function definition
*/
typedef void (*DONGLE_PATCH_FUN)(void);
/**
* @}
*/
/** @defgroup DONGLE_Exported_Constants DONGLE Exported Constants
* @{
*/
/* Exported constants ------------------------------------------------------------*/
/** @defgroup DONGLE_HOST_SpecialCmd_definitions
* @{
*/
#define USB_HOST_SPECIALCMD_FLASH_READ 0
#define USB_HOST_SPECIALCMD_FLASH_WRITE 1
#define USB_HOST_SPECIALCMD_FLASH_ERASE 2
#define USB_HOST_SPECIALCMD_REG_READ 3
#define USB_HOST_SPECIALCMD_REG_WRITE 4
#define USB_HOST_SPECIALCMD_EFUSE_READ 5
#define USB_HOST_SPECIALCMD_EFUSE_WRITE 6
/**
* @}
*/
/**
* @}
*/
/** @defgroup DONGLE_Exported_Functions DONGLE Exported Functions
* @{
*/
_LONG_CALL_ void USOC_DongleSpecialCmd(u8 cmd_val);
_LONG_CALL_ void USOC_DongleCmd(void);
_LONG_CALL_ void USOC_DongleIsr(void *DATA);
_LONG_CALL_ u32 USOC_PHY_Write(u8 addr, u8 data);
_LONG_CALL_ u32 USOC_PHY_Read(u8 addr, u8 *data);
_LONG_CALL_ void USOC_PHY_Autoload(void);
_LONG_CALL_ void USOC_DongleInit(DONGLE_PATCH_FUN patch_func);
_LONG_CALL_ void USOC_SIE_INTConfig(u32 SIE_INT, u32 NewState);
_LONG_CALL_ void USOC_SIE_INTClear(void);
void USOC_DongleIsr_RAM(void);
VOID USOC_DongleReOpen_RAM(void);
VOID USOC_DongleInitPatch_RAM(void);
VOID USOC_Dongle_InitThread(void *param);
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/* Registers Definitions --------------------------------------------------------*/
/******************** REG definition for SIE register *******************/
#define USB_SIE_REG_40_ADDR 0x40 /*!< VCONTROL: uphy_reg_addr, Haddr[7:4] and Laddr[3:0], 4-bit wide respectively. The Haddr value is restricted in 8~F while LADDR in 0~7 */
#define USB_SIE_REG_41_DATAIN 0x41 /*!< VSTATUS_IN[7:0]: uphy_reg_data_input */
#define USB_SIE_REG_42_CMD 0x42 /*!< VLOADM: 42[0]=0: VSTATUS serves as input for PHY. Otherwise, VSTATUS serves as output that passes the selected internal signals out.
42[7]: uphy_reg_en, enable to load uphy_reg_addr. This bit will be cleared at the end of accessing usbphy register */
#define USB_SIE_REG_43_DATAOUT 0x43 /*!< VSTATUS_OUT[7:0]: uphy_reg_data_output */
#define USB_SIE_REG_64 0x64
#define USB_SIE_REG_E0 0xE0
#define USB_SIE_REG_E1 0xE1
#define USB_SIE_REG_E2 0xE2
#define USB_SIE_REG_E3 0xE3
#define USB_SIE_REG_E4 0xE4
#define USB_SIE_REG_E5 0xE5
#define USB_SIE_REG_E6 0xE6
#define USB_SIE_REG_E7 0xE7
#define USB_SIE_REG_E8 0xE8
#define USB_SIE_REG_E9 0xE9
#define USB_SIE_REG_EA 0xEA
#define USB_SIE_REG_EB 0xEB
#define USB_SIE_REG_EC 0xEC
#define USB_SIE_REG_ED 0xED
#define USB_SIE_REG_EE 0xEE
#define USB_SIE_REG_EF 0xEF
#define USB_SIE_REG_F0 0xF0
#define USB_SIE_REG_F1 0xF1
#define USB_SIE_REG_F2 0xF2
#define USB_SIE_REG_F3 0xF3
#define USB_SIE_REG_F4 0xF4
#define USB_SIE_REG_F5 0xF5
#define USB_SIE_REG_F6 0xF6
#define USB_SIE_REG_F7 0xF7
/* Other Definitions --------------------------------------------------------*/
#define USB_PHY_INDIRECT_ACCESS_POLL_TIMES 0xFFF
#ifdef CONFIG_CHIP_A_CUT
#define USOC_PHY_AUTOLOAD USOC_PHY_Autoload_ACUT
#else
#define USOC_PHY_AUTOLOAD USOC_PHY_Autoload
#endif
#endif //_RTL8710B_DONGLE_H_
/******************* (C) COPYRIGHT 2016 Realtek Semiconductor *****END OF FILE****/

View file

@ -0,0 +1,159 @@
/**
******************************************************************************
* @file rtl8710b_inic.h
* @author
* @version V1.0.0
* @date 2016-05-17
* @brief This file contains all the functions prototypes for the USB & SDIO INIC firmware
* library.
******************************************************************************
* @attention
*
* This module is a confidential and proprietary property of RealTek and
* possession or use of this module requires written permission of RealTek.
*
* Copyright(c) 2015, Realtek Semiconductor Corporation. All rights reserved.
******************************************************************************
*/
#ifndef _RTL8710B_INIC_H_
#define _RTL8710B_INIC_H_
/** @addtogroup AmebaZ_Periph_Driver
* @{
*/
/** @defgroup INIC
* @brief INIC driver modules
* @{
*/
/* Exported types ------------------------------------------------------------*/
/** @defgroup INIC_Exported_Types INIC Exported Types
* @{
*/
/**
* @brief INIC TX DESC structure definition
* @note: Ameba1 is 6 dword, but AmebaZ is 4 dwords
*/
typedef struct {
/* u4Byte 0 */
u32 txpktsize:16; // bit[15:0]
u32 offset:8; // bit[23:16], store the sizeof(INIC_TX_DESC)
u32 bus_agg_num:8; // bit[31:24], the bus aggregation number
/* u4Byte 1 */
u32 type:8; // bit[7:0], the packet type
u32 data:8; // bit[8:15], the value to be written to the memory
u32 reply:1; // bit[16], request to send a reply message
u32 rsvd0:15;
/* u4Byte 2 */
u32 start_addr; // 1) memory write/read start address 2) RAM start_function address
/* u4Byte 3 */
u32 data_len:16; // bit[15:0], the length to write/read
u32 rsvd2:16; // bit[31:16]
} INIC_TX_DESC, *PINIC_TX_DESC;
/**
* @brief INIC RX DESC structure definition
* @note: Ameba1 is 6 dword, but AmebaZ is 4 dwords
*/
typedef struct {
/* u4Byte 0 */
u32 pkt_len:16; // bit[15:0], the packet size
u32 offset:8; // bit[23:16], the offset from the packet start to the buf start, also means the size of RX Desc
u32 rsvd0:6; // bit[29:24]
u32 icv:1; //icv error
u32 crc:1; // crc error
/* u4Byte 1 */
/************************************************/
/*****************receive packet type*********************/
/* 0x82: 802.3 packet */
/* 0x80: 802.11 packet */
/* 0x10: C2H command */
/* 0x50: Memory Read */
/* 0x52: Memory Write */
/* 0x54: Memory Set */
/* 0x60: Indicate the firmware is started */
u32 type:8; // bit[7:0], the type of this packet
u32 rsvd1:24; // bit[31:8]
/* u4Byte 2 */
u32 start_addr;
/* u4Byte 3 */
u32 data_len:16; // bit[15:0], the type of this packet
u32 result:8; // bit[23:16], the result of memory write command
u32 rsvd2:8; // bit[31:24]
} INIC_RX_DESC, *PINIC_RX_DESC;
/**
* @}
*/
/* Exported constants --------------------------------------------------------*/
/** @defgroup INIC_Exported_Constants INIC Exported Constants
* @{
*/
/** @defgroup INIC_packet_type_definitions
* @{
*/
#define TX_PACKET_802_3 (0x83)
#define TX_PACKET_802_11 (0x81)
#define TX_H2C_CMD (0x11)
#define TX_MEM_READ (0x51)
#define TX_MEM_WRITE (0x53)
#define TX_MEM_SET (0x55)
#define TX_FM_FREETOGO (0x61)
#define TX_PACKET_USER (0x41)
#define RX_PACKET_802_3 (0x82)
#define RX_PACKET_802_11 (0x80)
#define RX_C2H_CMD (0x10)
#define RX_MEM_READ (0x50)
#define RX_MEM_WRITE (0x52)
#define RX_MEM_SET (0x54)
#define RX_FM_FREETOGO (0x60)
#define RX_PACKET_USER (0x40)
/**
* @}
*/
/** @defgroup INIC_DESC_Size_definitions
* @{
*/
#define SIZE_RX_DESC (sizeof(INIC_RX_DESC))
#define SIZE_TX_DESC (sizeof(INIC_TX_DESC))
/**
* @}
*/
/**
* @}
*/
/** @defgroup INIC_Exported_Functions INIC Exported Functions
* @{
*/
//_LONG_CALL_
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
#endif //_RTL8710B_INIC_H_
/******************* (C) COPYRIGHT 2016 Realtek Semiconductor *****END OF FILE****/

View file

@ -0,0 +1,181 @@
/**
******************************************************************************
* @file rtl8710b_ota.h
* @author
* @version V1.0.0
* @date 2016-05-17
* @brief This file provides firmware functions to manage the OTA functions.
******************************************************************************
* @attention
*
* This module is a confidential and proprietary property of RealTek and
* possession or use of this module requires written permission of RealTek.
*
* Copyright(c) 2015, Realtek Semiconductor Corporation. All rights reserved.
******************************************************************************
*/
#ifndef _RTL8710B_OTA_H_
#define _RTL8710B_OTA_H_
/** @addtogroup AmebaZ_Platform
* @{
*/
#define SINGLE_IMG_OTA_UPGRADE 1 /*single image method upgrade defination */
#define SERVER_TYPE SERVER_LOCAL /*configure OTA demo type*/
#define CONFIG_CUSTOM_SIGNATURE 1 /*custom signature used or not*/
/** @defgroup OTA
* @brief OTA driver modules
* @{
*/
/* Exported Types --------------------------------------------------------*/
/** @defgroup OTA_Exported_Types OTA Exported Types
* @{
*/
#if SINGLE_IMG_OTA_UPGRADE
/**
* @brief OTA firmware file header structure definition
*/
typedef struct
{
u32 FwVer; /*!< Specifies the OTA firmware verision.
This parameter is in first Dword in the firmware file. */
u32 HdrNum;/*!< Specifies the OTA firmware header number.
This parameter indicates how many headers in firmware file. */
}update_file_hdr;
/**
* @brief OTA firmware file image header structure definition
*/
typedef struct
{
u8 ImgId[4]; /*!< Specifies the OTA image ID.
This parameter is used to identify the OTA header needed. */
u32 ImgHdrLen; /*!< Specifies the OTA image header length.
This parameter indicates the Image Header Length. */
u32 Checksum; /*!< Specifies the OTA image checksum.
This parameter is used to judge whether the image received is correct. */
u32 ImgLen; /*!< Specifies the OTA image length. */
u32 Offset; /*!< Specifies the the location in the total firmware file. */
u32 FlashOffset; /*!< Specifies the flash offset address of the corresponding image. */
}update_file_img_hdr;
/**
* @brief OTA firmware file download information structure definition
*/
typedef struct
{
u32 ImgId; /*!< Specifies the Image ID.*/
u32 FlashAddr; /*!< Specifies the Flash Address.
This parameter is used to write the Image to the flash. */
u32 ImgOffset; /*!< Specifies the Image location in Firmware header.
This parameter indicates the Image location in firmware file. */
u32 ImageLen; /*!< Specifies the OTA image length. */
}update_dw_info;
/**
* @brief OTA target image header structure definition
*/
typedef struct
{
update_file_hdr FileHdr; /*!< Specifies the firmware file header. */
update_file_img_hdr FileImgHdr; /*!< Specifies the target OTA image firmware file header. */
update_file_img_hdr FileRdpHdr; /*!< Specifies the target RDP image firmware file header. */
u32 RdpStatus;
}update_ota_target_hdr;
/**
* @brief OTA image ID header structure definition
*/
typedef struct
{
u8 ImgId[5]; /*!< Specifies the image ID strings. */
}update_file_img_id;
#endif
/**
* @}
*/
/* Exported constants --------------------------------------------------------*/
/** @defgroup OTA_Exported_Constants OTA Exported Constants
* @{
*/
/** @defgroup OTA_system_parameter_definitions
* @{
*/
#define OFFSET_DATA FLASH_SYSTEM_DATA_ADDR /*system data offset address*/
#define BACKUP_SECTOR (FLASH_SYSTEM_DATA_ADDR - 0x1000) /*back up system data offset address*/
#define OTA1_ADDR 0x0800B000 /*the OTA1 start address*/
#define OTA2_ADDR 0x08080000 /*the OTA2 start address*/
#define BUF_SIZE 512 /*the size of the buffer used for receiving firmware data from server*/
#define RDP_FLASH_ADDR 0x080FF000 /*the flash addresss for RDP image*/
#define OTA_IMAG 0 /*identify the OTA image*/
#define RDP_IMAG 1 /*identify the RDP image*/
/**
* @}
*/
/** @defgroup OTA_Index_definitions
* @{
*/
#define OTA_INDEX_1 0
#define OTA_INDEX_2 1
/**
* @}
*/
/**
* @}
*/
/* Exported functions --------------------------------------------------------*/
/** @defgroup OTA_Exported_Functions OTA Exported Functions
* @{
*/
u32 OTA_Change(u32 OTAIdx);
void* ota_update_malloc(unsigned int size);
void ota_update_free(void *buf);
#if (SERVER_TYPE == SERVER_LOCAL)
void ota_platform_reset(void);
int ota_write_ota2_addr(uint32_t ota_addr);
u32 ota_get_cur_index(void);
#if SINGLE_IMG_OTA_UPGRADE
u32 recv_file_info_from_server(u8 * Recvbuf, u32 len, int socket);
u32 recv_ota_file_hdr(u8 * Recvbuf, u32 * len, update_ota_target_hdr * pOtaTgtHdr, int socket);
u32 get_ota_tartget_header(u8* buf, u32 len, update_ota_target_hdr * pOtaTgtHdr, u8 * ImgId);
void erase_ota_target_flash(u32 addr, u32 len);
s32 download_new_fw_from_server(u32 addr, int socket, update_ota_target_hdr * pOtaTgtHdr, u8 * signature);
u32 verify_ota_checksum(u32 addr, u32 len, u8 * signature, update_ota_target_hdr * pOtaTgtHdr);
u32 change_ota_signature(u32 addr, u8 * signature, u32 ota_target_index);
u32 get_ota_address(u32 ota_target_index, u32 * new_addr, update_ota_target_hdr * pOtaTgtHdr);
#endif
#endif
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
#endif //_RTL8710B_OTA_H_
/******************* (C) COPYRIGHT 2016 Realtek Semiconductor *****END OF FILE****/

View file

@ -0,0 +1,105 @@
/**
******************************************************************************
* @file rtl8710b_pinmap.h
* @author
* @version V1.0.0
* @date 2016-05-17
* @brief This file provides firmware functions to manage the following
* functionalities of pin control:
* - pinmux
* - active pad pull up & pull down
* - sleep pad pull up & pull down
******************************************************************************
* @attention
*
* This module is a confidential and proprietary property of RealTek and
* possession or use of this module requires written permission of RealTek.
*
* Copyright(c) 2015, Realtek Semiconductor Corporation. All rights reserved.
******************************************************************************
*/
#ifndef _RTL8710B_PINMAP_H_
#define _RTL8710B_PINMAP_H_
/** @addtogroup AmebaZ_Platform
* @{
*/
/** @defgroup PIN
* @brief PIN driver modules
* @{
*/
/** @defgroup PINMAP
* @brief PINMAP driver modules
* @{
*/
/** @addtogroup PINMAP
* @verbatim
*****************************************************************************************
* PINMAP
*****************************************************************************************
* you can use pinmap to config pinmux instead of Pinmux_Config function
* you can use pinmap to config GPIO pull high/low status for power save when enter power save mode
*****************************************************************************************
* How To Use
*****************************************************************************************
* -1) ENABLE MACRO: CONFIG_PINMAP_ENABLE
* -2) Set all pins function in pmap_func based on your board
* -3) Bootloader will call PMAP_Init, then all pinmux will be set based on pmap_func
* -4) PMAP_Sleep will be called when enter sleep mode, all GPIO will pull high or low based on pmap_func
* -5) PMAP_Wake will be called when wake from sleep mode, all GPIO will back to active mode
*****************************************************************************************
* @endverbatim
*/
/* Exported types ------------------------------------------------------------*/
/** @defgroup PINMAP_Exported_Types PINMAP Exported Types
* @{
*/
/**
* @brief PINMAP Init structure definition
*/
typedef struct
{
u32 PinName; /*!< Specifies the pin name, This parameter can be a value of @ref PINMUX_Pin_Name_definitions */
u32 Function;/*!< Specifies the pin function, This parameter can be a value of @ref PINMUX_Function_definitions */
u32 FuncPuPd;/*!< Specifies the pin function PU/PD, This parameter can be a value of @ref GPIO_Pull_parameter_definitions */
u32 SleepPuPd;/*!< Specifies the pin sleep PU/PD, This parameter can be a value of @ref GPIO_Pull_parameter_definitions */
u32 DrvStrenth;/*!< Specifies the pin driving strength, This parameter is 3 bits */
} PMAP_TypeDef;
/**
* @}
*/
/* Exported functions --------------------------------------------------------*/
/** @defgroup PINMAP_Exported_Functions PINMAP Exported Functions
* @{
*/
void PMAP_Init(void);
void PMAP_Sleep(void);
void PMAP_Wake(void);
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/* Other definations --------------------------------------------------------*/
#endif //_RTL8710B_PINMAP_H_
/******************* (C) COPYRIGHT 2016 Realtek Semiconductor *****END OF FILE****/

View file

@ -0,0 +1,248 @@
/**
******************************************************************************
* @file rtl8710b_pinmux.h
* @author
* @version V1.0.0
* @date 2016-05-17
* @brief This file contains all the functions prototypes for the pinmux firmware
* library.
******************************************************************************
* @attention
*
* This module is a confidential and proprietary property of RealTek and
* possession or use of this module requires written permission of RealTek.
*
* Copyright(c) 2016, Realtek Semiconductor Corporation. All rights reserved.
******************************************************************************
*/
#ifndef _HAL_8710B_PINMUX_
#define _HAL_8710B_PINMUX_
/** @addtogroup AmebaZ_Platform
* @{
*/
/** @defgroup PIN
* @brief PIN driver modules
* @{
*/
/** @defgroup PINMUX
* @brief PINMUX modules
* @{
*/
/** @addtogroup PINMUX
* @verbatim
*****************************************************************************************
* Introduction
*****************************************************************************************
* -Every GPIO pin can be set to some function based on pinmux spec.
* -Every GPIO pin can set internal pull-up, pull-down based on pinmux spec.
*
*====================================================================
* pad control Spec.
*====================================================================
* -[15] reservd
* -[14] Schmitt trigger enable
* -[13] H3L1 for SDIO pad, other pad reservd
* -[12] slew rate
* -[11:9] pad driving strength
* -[8] pad shut down enable, 0: is shut down
* -[7] pull down resistor enable
* -[6] pull up resistor enable
* -[5:4] rserved for function id extend
* -[3:0] function id
*
*****************************************************************************************
* How to use Pinmux
*****************************************************************************************
* 1. Set the Internal pad function type for each pin using the follwoing function:
* Pinmux_Config(u8 PinName, u32 PinFunc)
*
* 2. Set the Internal pad pull type for each pin using the follwoing function:
* PAD_PullCtrl(u8 PinName, u8 PullType)
*
*****************************************************************************************
* @endverbatim
*/
/* Exported constants --------------------------------------------------------*/
/** @defgroup PINMUX_Exported_Constants PINMUX Exported Constants
* @{
*/
/** @defgroup PINMUX_Pin_Name_definitions
* @note: Pin_Name = (((port)<<5)|(pin))
* @{
*/
#define _PA_0 (0x00)
#define _PA_1 (0x01)
#define _PA_2 (0x02)
#define _PA_3 (0x03)
#define _PA_4 (0x04)
#define _PA_5 (0x05)
#define _PA_6 (0x06)
#define _PA_7 (0x07)
#define _PA_8 (0x08)
#define _PA_9 (0x09)
#define _PA_10 (0x0A)
#define _PA_11 (0x0B)
#define _PA_12 (0x0C)
#define _PA_13 (0x0D)
#define _PA_14 (0x0E)
#define _PA_15 (0x0F)
#define _PA_16 (0x10)
#define _PA_17 (0x11)
#define _PA_18 (0x12)
#define _PA_19 (0x13)
#define _PA_20 (0x14)
#define _PA_21 (0x15)
#define _PA_22 (0x16)
#define _PA_23 (0x17)
#define _PA_24 (0x18)
#define _PA_25 (0x19)
#define _PA_26 (0x1A)
#define _PA_27 (0x1B)
#define _PA_28 (0x1C)
#define _PA_29 (0x1D)
#define _PA_30 (0x1E)
#define _PA_31 (0x1F)
#define _PB_0 (0x20)
#define _PB_1 (0x21)
#define _PB_2 (0x22)
#define _PB_3 (0x23)
#define _PB_4 (0x24)
#define _PB_5 (0x25)
#define _PB_6 (0x26)
#define _PB_7 (0x27)
#define _PB_8 (0x28)
#define _PNC (0xFFFFFFFF)
/**
* @}
*/
/** @defgroup PINMUX_Port_And_Pin_definitions
* @{
*/
#define PORT_NUM(pin) ((pin>>5) & 0x03)
#define PIN_NUM(pin) (pin & 0x1f)
/**
* @}
*/
/** @defgroup PINMUX_Function_definitions
* @{
*/
#define PINMUX_FUNCTION_GPIO (0)
#define PINMUX_FUNCTION_UART (1)
#define PINMUX_FUNCTION_SPIM (2)
#define PINMUX_FUNCTION_SPIS (3)
#define PINMUX_FUNCTION_SPIF (4)
#define PINMUX_FUNCTION_I2C (5)
#define PINMUX_FUNCTION_SDIOD (6)
#define PINMUX_FUNCTION_PWM (7)
#define PINMUX_FUNCTION_TIMINPUT (7)
#define PINMUX_FUNCTION_SWD (8)
#define PINMUX_FUNCTION_EXT32K (8)
#define PINMUX_FUNCTION_RTCOUT (8)
#define PINMUX_FUNCTION_I2S (9)
#define PINMUX_FUNCTION_COEX_EXT32K (10)
#define PINMUX_FUNCTION_BTCOEX (10)
#define PINMUX_FUNCTION_WLLED (10)
/**
* @}
*/
/** @defgroup PINMUX_Peripheral_definitions
* @note just used by function PINMUX_Ctrl or PinCtrl
* @{
*/
#define PERIPHERAL_UART0 (0)
#define PERIPHERAL_UART1 (1)
#define PERIPHERAL_SPI0 (3)
#define PERIPHERAL_SPI1 (4)
#define PERIPHERAL_I2C0 (5)
#define PERIPHERAL_I2C1 (6)
#define PERIPHERAL_I2S0 (7)
#define PERIPHERAL_LOG_UART (8)
#define PERIPHERAL_SPI_FLASH (10)
#define PERIPHERAL_SDIOD (11)
#define PERIPHERAL_JTAG (13)
/**
* @}
*/
/** @defgroup PINMUX_Peripheral_Location_definitions
* @note just used by function PINMUX_Ctrl or PinCtrl
* @{
*/
#define S0 (0)
#define S1 (1)
#define S2 (2)
#define S3 (3)
/**
* @}
*/
/** @defgroup PINMUX_PAD_DrvStrength_definitions
* @{
*/
#define PAD_DRV_STRENGTH_0 (0x00000000 << 9)
#define PAD_DRV_STRENGTH_1 (0x00000001 << 9)
#define PAD_DRV_STRENGTH_2 (0x00000002 << 9)
#define PAD_DRV_STRENGTH_3 (0x00000003 << 9)
#define PAD_DRV_STRENGTH_4 (0x00000004 << 9)
#define PAD_DRV_STRENGTH_5 (0x00000005 << 9)
#define PAD_DRV_STRENGTH_6 (0x00000006 << 9)
#define PAD_DRV_STRENGTH_7 (0x00000007 << 9)
/**
* @}
*/
/**
* @}
*/
/** @defgroup PINMUX_Exported_Functions PINMUX Exported Functions
* @{
*/
_LONG_CALL_ void PAD_CMD(u8 PinName, u8 NewStatus);
_LONG_CALL_ void PAD_DrvStrength(u8 PinName, u32 DrvStrength);
_LONG_CALL_ void PAD_PullCtrl(u8 PinName, u8 PullType);
_LONG_CALL_ void Pinmux_Config(u8 PinName, u32 PinFunc);
_LONG_CALL_ u32 Pinmux_ConfigGet(u8 PinName);
_LONG_CALL_ void Pinmux_Deinit(u8 PinName);
_LONG_CALL_ void PINMUX_Ctrl(u32 Function, u32 PinLocation, BOOL Operation);
_LONG_CALL_ void PINMUX_SWD_OFF(void);
_LONG_CALL_ BOOL PINMUX_SWD_REG(u32 Addr);
#define PinCtrl PINMUX_Ctrl
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/** @defgroup PIN
* @brief PIN driver modules
* @{
*/
/* Other definations --------------------------------------------------------*/
#endif //_HAL_8710B_PINMUX_
/******************* (C) COPYRIGHT 2016 Realtek Semiconductor *****END OF FILE****/

View file

@ -0,0 +1,519 @@
/**
******************************************************************************
* @file rtl8710b_pmc.h
* @author
* @version V1.0.0
* @date 2016-05-17
* @brief This file provides firmware functions to manage the following
* functionalities of the soc power management circut:
* - wakeup timer
* - wakeup pin
* - sleep option
* - sleep mode
******************************************************************************
* @attention
*
* This module is a confidential and proprietary property of RealTek and
* possession or use of this module requires written permission of RealTek.
*
* Copyright(c) 2015, Realtek Semiconductor Corporation. All rights reserved.
******************************************************************************
*/
#ifndef _RTL8710B_PMC_H_
#define _RTL8710B_PMC_H_
/** @addtogroup AmebaZ_Platform
* @{
*/
/** @defgroup PMC
* @brief PMC driver modules
* @{
*/
/** @addtogroup PMC
* @verbatim
*****************************************************************************************
* Introduction
*****************************************************************************************
* we support following soc power save functions:
* - sleep clock gating
* - sleep power gating
* - deep standby
* - deep sleep
*
*****************************************************************************************
* sleep power gating
*****************************************************************************************
* following functions can be used when power gating:
* -UART0/UART1
* -TIM4/TIM5
* -RTC
* -WIFI
* -SDIO
* -USB
* -I2C0/I2C1
* -ADC
* -GPIO
* -REGU timer
* -normal wakepin
* -ANA timer
* following functions will be closed when power gating:
* -UART2 LOGUART
* -TIM0-TIM3
* -SPIC flash
*
*****************************************************************************************
* deep standby
*****************************************************************************************
* following functions can be used when deep standby:
* -RTC
* -REGU timer
* -normal wakepin
* -ANA timer
*
*****************************************************************************************
* deep sleep
*****************************************************************************************
* following functions can be used when deep standby:
* -REGU timer
* -REGU wakepin
*
*****************************************************************************************
* wakepin (A18/A5/A22/A23: mux normal wakepin and REGU wakepin)
*****************************************************************************************
* normal wakepin:
* -SLP_CG
* -SLP_PG
* -STDBY
* REGU wakepin:
* -just used in DSLP (1.2V closed)
* -just support high acive, so this pin should pull low on your board
*
*****************************************************************************************
*****************************************************************************************
* SLP & SNZ power option
*****************************************************************************************
* BIT_SYSON_PMOPT_SLP_EN_SWR & BIT_SYSON_PMOPT_SNZ_EN_SWR
* -we have two 1.2V LDO
* -BIG LDO: SWR mode or LDO mode (can config )
* -LITTLE LDO: a little 1.2v LDO
* -BIT_SYSON_PMOPT_SLP_EN_SWR
* -ENABLE/DISABLE BIG LDO when SLP
* BIT_SYSON_PMOPT_SNZ_EN_SWR
* -ENABLE/DISABLE BIG LDO when SNZ, WIFI & ADC need open BIG LDO when SNZ
*
* BIT_SYSON_PMOPT_SLP_EN_PWM & BIT_SYSON_PMOPT_SNZ_EN_PWM
* -BIT_SYSON_PMOPT_SLP_EN_PWM
* -ENABLE/DISABLE LDO heavy loading current mode when SLP
* -BIT_SYSON_PMOPT_SNZ_EN_PWM
* -ENABLE/DISABLE heavy loading current mode when SNZ, WIFI & ADC need heavy loading when SNZ
*
* BIT_SYSON_PMOPT_SLP_XTAL_EN & BIT_SYSON_PMOPT_SNZ_XTAL_EN
* -WIFI and SOC both need XTAL when work,
* -but WIFI have individual option to control XTAL, so BIT_SYSON_PMOPT_SNZ_XTAL_EN not needed
*
* BIT_SYSON_PMOPT_SLP_SYSPLL_EN & BIT_SYSON_PMOPT_SNZ_SYSPLL_EN
* -WIFI and SOC both have individual PLL, here is SOC 500M PLL
* -So BIT_SYSON_PMOPT_SNZ_SYSPLL_EN not needed
*
* BIT_SYSON_SNFEVT_WIFI_MSK = 1 & BIT_SYSON_BYPASS_SNZ_SLP = 1
* - after OS suspend, platform will enter SNZ and close CPU, then platform enter sleep mode when WIFI 32K
* - BIT_SYSON_PMOPT_SNZ_EN_SOC should never open, or CPU will not close when platform will enter SNZ
*
* BIT_SYSON_SNFEVT_WIFI_MSK = 1 & BIT_SYSON_BYPASS_SNZ_SLP = 0 (not use this config)
* - after OS suspend, platform will enter sleep mode & close CPU after WIFI 32K
*****************************************************************************************
* @endverbatim
*/
/* Exported constants --------------------------------------------------------*/
/** @defgroup PMC_Exported_Constants PMC Exported Constants
* @{
*/
/** @defgroup PMC_WakePin_definitions
* @{
*/
#define WAKEUP_BY_GPIO_NONE ((u32)(0x00000000))
#define WAKEUP_BY_GPIO_WAKEUP0_LOW ((u32)(0x00000001)) //PA18
#define WAKEUP_BY_GPIO_WAKEUP0_HIG ((u32)(0x00000101))
#define WAKEUP_BY_GPIO_WAKEUP1_LOW ((u32)(0x00000001 << 1)) //PA5
#define WAKEUP_BY_GPIO_WAKEUP1_HIG ((u32)(0x00000101 << 1))
#define WAKEUP_BY_GPIO_WAKEUP2_LOW ((u32)(0x00000001 << 2)) //PA22
#define WAKEUP_BY_GPIO_WAKEUP2_HIG ((u32)(0x00000101 << 2))
#define WAKEUP_BY_GPIO_WAKEUP3_LOW ((u32)(0x00000001 << 3)) //PA23
#define WAKEUP_BY_GPIO_WAKEUP3_HIG ((u32)(0x00000101 << 3))
/**
* @}
*/
/** @defgroup SOCPS_PS_Mode_definitions
* @{
*/
#define SOCPS_MODE_DSLP ((u32)(0x00000001 << 0))
#define SOCPS_MODE_DSTBY ((u32)(0x00000001 << 1))
#define SOCPS_MODE_SLP ((u32)(0x00000001 << 2))
/**
* @}
*/
/** @defgroup SOCPS_PS_ANA_Clk_definitions
* @{
*/
#define ANACK_250K ((u32)0x00000000)
#define ANACK_4M ((u32)0x00000001)
/**
* @}
*/
/** @defgroup SOCPS_PS_Calibration_Clk_definitions
* @{
*/
#define ANACK ((u32)0x00000000)
#define A33CK ((u32)0x00000001)
/**
* @}
*/
/** @defgroup SOCPS_PS_Wakeup_Pin_definitions
* @{
*/
#define WAKUP_0 ((u32)0x00000000)/*!< _PA_18 */
#define WAKUP_1 ((u32)0x00000001)/*!< _PA_5 */
#define WAKUP_2 ((u32)0x00000002)/*!< _PA_22 */
#define WAKUP_3 ((u32)0x00000003)/*!< _PA_23 */
/**
* @}
*/
/** @defgroup SOCPS_PS_Wakeup_Pin_Mask_definitions
* @{
*/
#define WAKUP_0_MASK ((u32)(0x00000001 << 0))/*!< _PA_18 */
#define WAKUP_1_MASK ((u32)(0x00000001 << 1))/*!< _PA_5 */
#define WAKUP_2_MASK ((u32)(0x00000001 << 2))/*!< _PA_22 */
#define WAKUP_3_MASK ((u32)(0x00000001 << 3))/*!< _PA_23 */
#define IS_WAKEPIN_MASK(MASK) (((MASK) & 0x0000000F) != 0)
/**
* @}
*/
/**
* @}
*/
/* Exported functions --------------------------------------------------------*/
/** @defgroup PMC_Exported_Functions PMC Exported Functions
* @{
*/
_LONG_CALL_ void SOCPS_BackupCPUClk(void);
_LONG_CALL_ void SOCPS_RestoreCPUClk(void);
_LONG_CALL_ void SOCPS_BootFromPS(u32 NewStatus);
_LONG_CALL_ void SOCPS_TrapPin(u32 NewStatus);
_LONG_CALL_ void SOCPS_ANACKSel(u32 ANACLK);
_LONG_CALL_ void SOCPS_SetWakeEvent(u32 Option, u32 NewStatus);
_LONG_CALL_ void SOCPS_ClearWakeEvent(void);
_LONG_CALL_ void SOCPS_WakePinsCtrl(u32 GpioOption);
_LONG_CALL_ void SOCPS_WakePinCtrl(u32 Index, u32 Polarity);
_LONG_CALL_ void SOCPS_SetANATimer(u32 SDuration, u32 NewStatus);
_LONG_CALL_ void SOCPS_SetReguWakepin(void);
_LONG_CALL_ void SOCPS_SetReguTimer(u32 SDuration, u32 CalibData);
_LONG_CALL_ void SOCPS_PWRMode(u32 pwrmode, u32 snz_bypss);
_LONG_CALL_ void SOCPS_PWROption(u32 pwrmgt_option);
_LONG_CALL_ void SOCPS_PWROptionExt(u32 pwrmgt_option);
_LONG_CALL_ void SOCPS_SNZMode(u32 SnzMask, u32 NewStatus);
_LONG_CALL_ u32 SOCPS_CLKCal(u32 ClkSel);
_LONG_CALL_ void SOCPS_DeepStandby(void);
_LONG_CALL_ void SOCPS_DeepSleep(void);
_LONG_CALL_ void SOCPS_SleepPG(void);
_LONG_CALL_ void SOCPS_SetReguWakepins(u32 PinMask);
_LONG_CALL_ void SOCPS_ReguTimerCmd(u32 NewStatus);
_LONG_CALL_ void SOCPS_WakePinDebounce(u32 Index, u32 Status);
_LONG_CALL_ void SOCPS_DeepStandby_RAM(void);
_LONG_CALL_ void SOCPS_SleepPG_RAM(void);
_LONG_CALL_ void SOCPS_DeepSleep_RAM(void);
_LONG_CALL_ void SOCPS_FlashPin_PullUp_RAM(u32 NewStatus);
void SOCPS_SetReguWakepins_RAM(u32 PinMask);
void SOCPS_ReguTimerCmd_RAM(u32 NewStatus);
void SOCPS_WakePinDebounce_RAM(u32 Index, u32 Status);
void SOCPS_SetReguTimer_RAM(u32 SDuration, u32 CalibData);
void SOCPS_SleepCG(void);
int SOCPS_DsleepWakeReason(void);
/**
* @}
*/
/* Registers Definitions --------------------------------------------------------*/
/**************************************************************************//**
* @defgroup PMC_Register_Definitions PMC Register Definitions
* @{
*****************************************************************************/
/**************************************************************************//**
* @defgroup REG_SYS_ANA_TIM_CTRL
* @{
*****************************************************************************/
#define BIT_SYS_ANACK_TU_TIME(x) (((x) & 0x0000003f) << 16)
#define BIT_SYS_DSBYCNT_EN (0x00000001 << 15)
#define BIT_SYS_DSTDY_TIM_SCAL(x) (((x) & 0x0000000f) << 8)
#define BIT_SYS_DSTBY_TIM_PERIOD(x) (((x) & 0x000000ff) << 0)
/** @} */
/**************************************************************************//**
* @defgroup REG_SYS_DSLP_TIM_CTRL
* @{
*****************************************************************************/
#define BIT_SYS_REGU_ASIF_EN(x) (((x) & 0x000000ff) << 24)
#define BIT_SYS_REGU_ASIF_THP_DA(x) (((x) & 0x00000003) << 20)
#define BIT_SYS_REGU_ASIF_TPD_CK(x) (((x) & 0x00000003) << 18)
#define BIT_SYS_REGU_ASIF_TSP_DA(x) (((x) & 0x3) << 16)
#define BIT_SYS_REGU_ASIF_POLL (0x00000001 << 15)
#define BIT_SYS_REGU_ASIF_MODE (0x00000001 << 14)
#define BIT_SYS_REGU_ASIF_WE (0x00000001 << 12)
#define BIT_SYS_REGU_ASIF_AD(x) (((x) & 0x0000000f) << 8)
#define BIT_SYS_REGU_ASIF_WD(x) (((x) & 0x000000ff) << 0)
/** @} */
/**************************************************************************//**
* @defgroup REG_SYS_DSLP_TIM_CAL_CTRL
* @{
*****************************************************************************/
#define BIT_SYS_DSLP_TIM_EN (0x00000001 << 24)
#define BIT_SYS_DSLP_TIM_PERIOD(x) (((x) & 0x7fffff) << 0)
/** @} */
/**************************************************************************//**
* @defgroup REG_SYS_GPIO_DSTBY_WAKE_CTRL0
* @{
*****************************************************************************/
#define BIT_SYS_WAKEPIN3_WEVENT_STS (0x00000001 << 27)
#define BIT_SYS_WAKEPIN2_WEVENT_STS (0x00000001 << 26)
#define BIT_SYS_WAKEPIN1_WEVENT_STS (0x00000001 << 25)
#define BIT_SYS_WAKEPIN0_WEVENT_STS (0x00000001 << 24)
#define BIT_SYS_WAKEPIN3_PULL_CTRL_EN (0x00000001 << 19)
#define BIT_SYS_WAKEPIN2_PULL_CTRL_EN (0x00000001 << 18)
#define BIT_SYS_WAKEPIN1_PULL_CTRL_EN (0x00000001 << 17)
#define BIT_SYS_WAKEPIN0_PULL_CTRL_EN (0x00000001 << 16)
#define BIT_SYS_WAKEPIN3_WINT_MODE (0x00000001 << 11)
#define BIT_SYS_WAKEPIN2_WINT_MODE (0x00000001 << 10)
#define BIT_SYS_WAKEPIN1_WINT_MODE (0x00000001 << 9)
#define BIT_SYS_WAKEPIN0_WINT_MODE (0x00000001 << 8)
#define BIT_SYS_WAKEPIN3_PIN_EN (0x00000001 << 3)
#define BIT_SYS_WAKEPIN2_PIN_EN (0x00000001 << 2)
#define BIT_SYS_WAKEPIN1_PIN_EN (0x00000001 << 1)
#define BIT_SYS_WAKEPIN0_PIN_EN (0x00000001 << 0)
#define MARSK_WAKEPIN0_HIGH_WAKE (BIT_SYS_WAKEPIN0_PIN_EN | \
BIT_SYS_WAKEPIN0_WINT_MODE | \
BIT_SYS_WAKEPIN0_PULL_CTRL_EN | \
BIT_SYS_WAKEPIN0_WEVENT_STS)
#define MARSK_WAKEPIN0_LOW_WAKE (BIT_SYS_WAKEPIN0_PIN_EN | \
BIT_SYS_WAKEPIN0_PULL_CTRL_EN | \
BIT_SYS_WAKEPIN0_WEVENT_STS)
/** @} */
/**************************************************************************//**
* @defgroup REG_SYS_GPIO_DSTBY_WAKE_CTRL1
* @{
*****************************************************************************/
#define BIT_SYS_BTCLKDET_MODE (0x00000001 << 27)
#define BIT_SYS_BTCLKDET_DEBOUNCE_EN (0x00000001 << 26)
#define BIT_SYS_BTCLKDET_TIM_SCAL (0x00000003 << 24)
#define BIT_SYS_WAKEPIN3_SHTDN_N (0x00000001 << 19)
#define BIT_SYS_WAKEPIN2_SHTDN_N (0x00000001 << 18)
#define BIT_SYS_WAKEPIN1_SHTDN_N (0x00000001 << 17)
#define BIT_SYS_WAKEPIN0_SHTDN_N (0x00000001 << 16)
#define BIT_SYS_WINT_DEBOUNCE_TIM_SCAL(x) (((x) & 0x3) << 8)
#define BIT_SYS_WAKEPIN3_WINT_DEBOUNCE_EN (0x00000001 << 3)
#define BIT_SYS_WAKEPIN2_WINT_DEBOUNCE_EN (0x00000001 << 2)
#define BIT_SYS_WAKEPIN1_WINT_DEBOUNCE_EN (0x00000001 << 1)
#define BIT_SYS_WAKEPIN0_WINT_DEBOUNCE_EN (0x00000001 << 0)
/** @} */
/**************************************************************************//**
* @defgroup REG_SYS_SLP_WAKE_EVENT_MSK0
* @{
*****************************************************************************/
#define BIT_SYSON_WEVT_BOR2_MSK (0x00000001 << 30) /*!< BOR2 wakeup */
#define BIT_SYSON_WEVT_GPIO_DSTBY_MSK (0x00000001 << 29) /*!< 1: enable Wakepin Wakeup DSTBY event */
#define BIT_SYSON_WEVT_A33_AND_A33GPIO_MSK (0x00000001 << 28) /*!< 1: enable REGU A33(deepsleep mode, A33 Timer & A33 wakepin) Wakeup event */
#define BIT_SYSON_WEVT_ADC_MSK (0x00000001 << 26) /*!< 1: enable ADC Wakeup event */
#define BIT_SYSON_WEVT_SDIO_MSK (0x00000001 << 14) /*!< 1: enable SDIO Wakeup event */
#define BIT_SYSON_WEVT_RTC_MSK (0x00000001 << 13) /*!< 1: enable RTC Wakeup event */
#define BIT_SYSON_WEVT_UART1_MSK (0x00000001 << 12) /*!< 1: enable UART1 Wakeup event */
#define BIT_SYSON_WEVT_UART0_MSK (0x00000001 << 11) /*!< 1: enable UART0 Wakeup event */
#define BIT_SYSON_WEVT_I2C1_MSK (0x00000001 << 10) /*!< 1: enable I2C1 Wakeup event */
#define BIT_SYSON_WEVT_I2C0_MSK (0x00000001 << 9) /*!< 1: enable I2C0 Wakeup event */
#define BIT_SYSON_WEVT_WLAN_MSK (0x00000001 << 8) /*!< 1: enable WLAN Wakeup event */
#define BIT_SYSON_WEVT_I2C1_ADDRMATCH_MSK (0x00000001 << 7) /*!< 1:enable wakeup event of I2C1 RX address match */
#define BIT_SYSON_WEVT_I2C0_ADDRMATCH_MSK (0x00000001 << 6) /*!< 1:enable wakeup event of I2C0 RX address match */
#define BIT_SYSON_WEVT_USB_MSK (0x00000001 << 5) /*!< 1: enable wakeup event of usb resume from suspend mode */
#define BIT_SYSON_WEVT_GPIO_MSK (0x00000001 << 4) /*!< 1: enable GPIO Wakeup event */
#define BIT_SYSON_WEVT_CHIP_EN_MSK (0x00000001 << 3) /*!< 1: enable chip en wakeup event */
#define BIT_SYSON_WEVT_OVER_CURRENT_MSK (0x00000001 << 2) /*!< 1: enable OCP wakeup event, REGU OVER_CURRENT */
#define BIT_SYSON_WEVT_GTIM_MSK (0x00000001 << 1) /*!< 1: enable Gtimer 4/5 Wakeup SYSON event */
#define BIT_SYSON_WEVT_SYSTIM_MSK (0x00000001 << 0) /*!< 1: enable SYS Timer(ANA Timer, deepstandby mode) Wakeup SYSON event */
/** @} */
/**************************************************************************//**
* @defgroup REG_SYS_SLP_WAKE_EVENT_STATUS0
* @{
*****************************************************************************/
#define BIT_SYSON_WEVT_BOR2_STS (0x00000001 << 30)
#define BIT_SYSON_WEVT_GPIO_DSTBY_STS (0x00000001 << 29)
#define BIT_SYSON_WEVT_A33_STS (0x00000001 << 28)
#define BIT_SYSON_WEVT_ADC_STS (0x00000001 << 26)
#define BIT_SYSON_WEVT_SDIO_STS (0x00000001 << 14)
#define BIT_SYSON_WEVT_RTC_STS (0x00000001 << 13)
#define BIT_SYSON_WEVT_UART1_STS (0x00000001 << 12)
#define BIT_SYSON_WEVT_UART0_STS (0x00000001 << 11)
#define BIT_SYSON_WEVT_I2C1_STS (0x00000001 << 10)
#define BIT_SYSON_WEVT_I2C0_STS (0x00000001 << 9)
#define BIT_SYSON_WEVT_WLAN_STS (0x00000001 << 8)
#define BIT_SYSON_WEVT_I2C1_ADDRMATCH_STS (0x00000001 << 7)
#define BIT_SYSON_WEVT_I2C0_ADDRMATCH_STS (0x00000001 << 6)
#define BIT_SYSON_WEVT_USB_STS (0x00000001 << 5)
#define BIT_SYSON_WEVT_GPIO_STS (0x00000001 << 4)
#define BIT_SYSON_WEVT_CHIP_EN_STS (0x00000001 << 3)
#define BIT_SYSON_WEVT_OVER_CURRENT_STS (0x00000001 << 2)
#define BIT_SYSON_WEVT_GTIM_STS (0x00000001 << 1)
#define BIT_SYSON_WEVT_SYSTIM_STS (0x00000001 << 0)
/** @} */
/**************************************************************************//**
* @defgroup REG_SYS_SNF_WAKE_EVENT_MSK0
* @{
*****************************************************************************/
#define BIT_SYSON_SNFEVT_WIFI_MSK (0x00000001 << 1) /*!< 1: enable wlan power on wakeup event interrupt; 0: Disable */
#define BIT_SYSON_SNFEVT_ADC_MSK (0x00000001 << 0) /*!< 1: enable ADC Wakeup SYSON event from GTIM3 interrupt under oneshot mode ; 0: disable the event to wakeup system */
/** @} */
/**************************************************************************//**
* @defgroup REG_SYS_SNF_WAKE_EVENT_STATUS
* @{
*****************************************************************************/
#define BIT_SYSON_SNFEVT_WIFI_STS (0x00000001 << 1) /*!< 1: indicate wlan power on wakeup status */
#define BIT_SYSON_SNFEVT_ADC_STS (0x00000001 << 0) /*!< 1: indicate ADC wakeup event status */
/** @} */
/**************************************************************************//**
* @defgroup REG_SYS_PWRMGT_CTRL
* @{
*****************************************************************************/
#define BIT_SYSON_PMCOPT_BKPOFIMK2 (0x00000001 << 18) /*!< Enable wakeup interrupt to break power off flow during power off stage2 */
#define BIT_SYSON_PMCOPT_BKPOFIMK1 (0x00000001 << 17) /*!< Enable wakeup interrupt to break power off flow during power off stage1 */
#define BIT_SYSON_PMCOPT_BKPOFIMK0 (0x00000001 << 16) /*!< Enable wakeup interrupt to break power off flow during power off stage0 */
#define BIT_SYSON_BYPASS_SNZ_SLP (0x00000001 << 8) /*!< If WIFI WOWLAN open we should open it, or SOC will sleep when WIFI active */
#define BIT_SYSON_PM_CMD_SLP (0x00000001 << 2) /*!< 1: command SYSON SM to enter sleep state, when PMC finishes the process, this bit will be auto clear to 0 */
#define BIT_SYSON_PM_CMD_DSTBY (0x00000001 << 1) /*!< 1: command SYSON SM to enter deep standby state,when PMC finishes the process, this bit will be auto clear to 0 */
#define BIT_SYSON_PM_CMD_DSLP (0x00000001 << 0) /*!< 1: command SYSON SM to enter deep sleep state,when PMC finishes the process, this bit will be auto clear to 0 */
/** @} */
/**************************************************************************//**
* @defgroup REG_SYS_PWRMGT_OPTION
* @{
*****************************************************************************/
#define BIT_SYSON_PMOPT_NORM_SYSCLK_SEL (0x00000001 << 30) /*!< 1: select system PLL clock as CPU clock when enter into active mode; 0: select ANA clock */
#define BIT_SYSON_PMOPT_NORM_SYSPLL_EN (0x00000001 << 29) /*!< 1: enable syspem PLL when enter into active mode; 0: disable SYSPLL */
#define BIT_SYSON_PMOPT_NORM_XTAL_EN (0x00000001 << 28) /*!< 1: enable XTAL when enter into active mode; 0: disable XTAL */
#define BIT_SYSON_PMOPT_NORM_EN_PWM (0x00000001 << 26) /*!< 1: power enable SWR/LDO output heavy loading current mode when enter into power mode */
#define BIT_SYSON_PMOPT_SNZ_MEM2_EN (0x00000001 << 24) /*!< 1: enable MEM2 when enter into snooze mode */
#define BIT_SYSON_PMOPT_SNZ_MEM1_EN (0x00000001 << 23) /*!< 1: enable MEM1 when enter into snooze mode */
#define BIT_SYSON_PMOPT_SNZ_MEM0_EN (0x00000001 << 22) /*!< 1: enable MEM0 when enter into snooze mode */
#define BIT_SYSON_PMOPT_SNZ_SYSPLL_EN (0x00000001 << 21) /*!< 1: enable syspem PLL when enter into snooze mode, wifi not use, adc use */
#define BIT_SYSON_PMOPT_SNZ_XTAL_EN (0x00000001 << 20) /*!< 1: enable XTAL when enter into snooze mode, wifi not use, adc use */
#define BIT_SYSON_PMOPT_SNZ_EN_SOC (0x00000001 << 19) /*!< 1: power enable SOC platform when enter into snooze mode */
#define BIT_SYSON_PMOPT_SNZ_EN_PWM (0x00000001 << 18) /*!< 1: power enable SWR/LDO output heavy loading current mode when enter into snooze mode, wifi use it when close BIT_SYSON_PMOPT_SLP_EN_PWM*/
#define BIT_SYSON_PMOPT_SNZ_EN_SWR (0x00000001 << 17) /*!< 1: power enable SWR/LDO 1.2V when enter into snooze mode, wifi use it when close BIT_SYSON_PMOPT_SLP_EN_SWR*/
#define BIT_SYSON_PMOPT_SLP_MEM2_EN (0x00000001 << 16) /*!< 1: enable MEM2 when enter into sleep mode, 64k */
#define BIT_SYSON_PMOPT_SLP_MEM1_EN (0x00000001 << 15) /*!< 1: enable MEM1 when enter into sleep mode, 64k */
#define BIT_SYSON_PMOPT_SLP_MEM0_EN (0x00000001 << 14) /*!< 1: enable MEM0 when enter into sleep mode, 128k */
#define BIT_SYSON_PMOPT_SLP_SYSPLL_EN (0x00000001 << 13) /*!< 1: enable syspem PLL when enter into sleep mode; 0: disable SYSPLL */
#define BIT_SYSON_PMOPT_SLP_XTAL_EN (0x00000001 << 12) /*!< 1: enable XTAL when enter into sleep mode; 0: disable XTAL */
#define BIT_SYSON_PMOPT_SLP_EN_SOC (0x00000001 << 11) /*!< 1: power enable SOC platform when enter into sleep mode; 0: power off SoC domain */
#define BIT_SYSON_PMOPT_SLP_EN_PWM (0x00000001 << 10) /*!< 1: power enable SWR/LDO output heavy loading current mode when enter into sleep mode, wifi on can not */
#define BIT_SYSON_PMOPT_SLP_EN_SWR (0x00000001 << 9) /*!< 1: power enable BIG 1.2V LDO (SWR/LDO can cfg) when enter into sleep mode, just keep little LDO; wifi on can not */
#define BIT_SYSON_PMOPT_SLP_LPLDO_SEL (0x00000001 << 8) /*!< V12H LDO operation mode selection for sleep, 1: normal, 0: standby(low current mode), always-on power is here */
#define BIT_SYSON_PMOPT_DSTBY_LPLDO_SEL (0x00000001 << 0) /*!< V12H LDO operation mode selection for deep standby, 1: normal, 0: standby */
/* 0x74000100 */
#define BIT_SYSON_PMOPT_MASK (BIT_SYSON_PMOPT_NORM_EN_PWM | \
BIT_SYSON_PMOPT_NORM_XTAL_EN | \
BIT_SYSON_PMOPT_NORM_SYSPLL_EN | \
BIT_SYSON_PMOPT_NORM_SYSCLK_SEL | \
BIT_SYSON_PMOPT_SNZ_EN_SWR | \
BIT_SYSON_PMOPT_SNZ_EN_PWM | \
BIT_SYSON_PMOPT_SNZ_MEM0_EN | \
BIT_SYSON_PMOPT_SNZ_MEM1_EN | \
BIT_SYSON_PMOPT_SNZ_MEM2_EN)
/** @} */
/**************************************************************************//**
* @defgroup REG_SYS_PWRMGT_OPTION_EXT
* @{
*****************************************************************************/
#define BIT_SYSON_PMOPT_SLP_BYPS_WL (0x00000001 << 4) /*!< 1: CM4 can enter sleep mode with no regard of wlan's power state */
#define BIT_SYSON_PMOPT_SLP_REDUCE_VOL (0x00000001 << 3) /*!< 1: decrease SWR/LDO 1.2V voltage level when enter into sleep mode(decrease digital power); */
#define BIT_SYSON_PMOPT_SLP_ANACK_SEL (0x00000001 << 2) /*!< 1: set ANA clock to 4MHz when enter into power mode; */
#define BIT_SYSON_PMOPT_SLP_ANACK_EN (0x00000001 << 1) /*!< 1: enable syson register clock when enter into sleep mode; */
#define BIT_SYSON_PMOPT_SLP_SWR_ADJ (0x00000001 << 0) /*!< 1: decrease VD12H 1.2V voltage level when enter into sleep mode(decrease always on power, should better not use); */
/** @} */
/**************************************************************************//**
* @defgroup REG_SYS_DSLP_WEVENT
* @{
*****************************************************************************/
#define BIT_SYSON_DSLP_GPIO (0x00000001 << 2) /*!< REGU GPIO wake33 event */
#define BIT_SYSON_DSLP_WTIMER33 (0x00000001 << 0) /*!< REGU Timer33 wake event */
/** @} */
/** @} */
/**
* @}
*/
/**
* @}
*/
/* Other Definitions --------------------------------------------------------*/
#define REG_VDR_ANACK_CAL_CTRL 0xA0
#define NVIC_ICPR0_PS_MASK 0xFFFFFFFF
#ifdef CONFIG_CHIP_A_CUT
#define SOCPS_SET_REGUTIMER SOCPS_SetReguTimer_RAM
#else
#define SOCPS_SET_REGUTIMER SOCPS_SetReguTimer
#endif
#endif //_RTL8710B_PMC_H_
/******************* (C) COPYRIGHT 2016 Realtek Semiconductor *****END OF FILE****/

View file

@ -0,0 +1,234 @@
/**
******************************************************************************
* @file rtl8710b_sdio.h
* @author
* @version V1.0.0
* @date 2016-05-17
* @brief This file contains all the functions prototypes for the SDIO firmware
* library.
******************************************************************************
* @attention
*
* This module is a confidential and proprietary property of RealTek and
* possession or use of this module requires written permission of RealTek.
*
* Copyright(c) 2015, Realtek Semiconductor Corporation. All rights reserved.
******************************************************************************
*/
#ifndef _RTL8710B_SDIO_H_
#define _RTL8710B_SDIO_H_
/** @addtogroup AmebaZ_Periph_Driver
* @{
*/
/** @defgroup SDIO
* @brief SDIO driver modules
* @{
*/
/* Exported Types --------------------------------------------------------*/
/** @defgroup SDIO_Exported_Types SDIO Exported Types
* @{
*/
/**
* @brief SDIO Init structure definition
*/
typedef struct {
/* TXBD */
u32 TXBD_BAR; /*!< Specifies TXBD base address */
u32 TXBD_RING_SIZE; /*!< Specifies TXBD ring size, This parameter must be set to a value in the 0-0xFFFF range. */
u32 TX_BUFFER_SIZE; /*!< Specifies TX buffer size, This parameter must be set to a value in the 0-0xFF range. */
/* RXBD */
u32 RXBD_BAR; /*!< Specifies RXBD base address */
u32 RXBD_RING_SIZE; /*!< Specifies RXBD ring size, This parameter must be set to a value in the 0-0xFFFF range. */
u32 RXBD_FREE_TH; /*!< the threshold of free RX BD count to trigger interrupt */
} SDIO_InitTypeDef;
/**
* @}
*/
/* Exported constants --------------------------------------------------------*/
/** @defgroup SDIO_Exported_Constants SDIO Exported Constants
* @{
*/
/** @defgroup SDIO_MP_CMD_definitions The SDIO MP CMD definations
* @{
*/
#define SDIO_MP_START 1
#define SDIO_MP_STOP 2
#define SDIO_MP_LOOPBACK 3
#define SDIO_MP_STATUS 4
#define SDIO_MP_READ_REG8 5
#define SDIO_MP_READ_REG16 6
#define SDIO_MP_READ_REG32 7
#define SDIO_MP_WRITE_REG8 8
#define SDIO_MP_WRITE_REG16 9
#define SDIO_MP_WRITE_REG32 10
#define SDIO_MP_WAKEUP 11 // wakeup the SDIO task manually, for debugging
#define SDIO_MP_DUMP 12 // start/stop to dump the SDIO status periodically
#define SDIO_MP_CTX 13 // setup continue TX test
#define SDIO_MP_CRX 14 // setup continue RX test
#define SDIO_MP_CRX_DA 15 // setup continue RX with dynamic allocate RX Buf test
#define SDIO_MP_CRX_STOP 16 // setup continue RX test
#define SDIO_MP_DBG_MSG 17 // Debug message On/Off
/**
* @}
*/
/** @defgroup SDIO_RPWM_definitions The SDIO RPWM definations
* @{
*/
#define RPWM2_ACT_BIT (0x00000001 << 0) // Active
#define RPWM2_SLEEP_BIT 0 // Sleep
#define RPWM2_DSTANDBY_BIT (0x00000001 << 1) // Deep Standby
#define RPWM2_PG_BIT 0 // Power Gated
#define RPWM2_FBOOT_BIT (0x00000001 << 2) // fast reboot
#define RPWM2_NBOOT_BIT 0 // normal reboot
#define RPWM2_WKPIN_0_BIT (0x00000001 << 3) // enable GPIO wakeup pin 0
#define RPWM2_WKPIN_1_BIT (0x00000001 << 4) // enable GPIO wakeup pin 1
#define RPWM2_WKPIN_2_BIT (0x00000001 << 5) // enable GPIO wakeup pin 2
#define RPWM2_WKPIN_3_BIT (0x00000001 << 6) // enable GPIO wakeup pin 3
#define RPWM2_WKPIN_0_LV_BIT (0x00000001 << 7) // GPIO wakeup pin 0 wakeup level
#define RPWM2_WKPIN_1_LV_BIT (0x00000001 << 8) // GPIO wakeup pin 1 wakeup level
#define RPWM2_WKPIN_2_LV_BIT (0x00000001 << 9) // GPIO wakeup pin 2 wakeup level
#define RPWM2_WKPIN_3_LV_BIT (0x00000001 << 10) // GPIO wakeup pin 3 wakeup level
#define RPWM2_CG_BIT (0x00000001 << 11) // Clock Gated
#define RPWM2_ACK_BIT (0x00000001 << 14) // Acknowledge
#define RPWM2_TOGGLE_BIT (0x00000001 << 15) // Toggle bit
/**
* @}
*/
/** @defgroup SDIO_CPWM2_definitions The SDIO CPWM2 definations
* @{
*/
#define CPWM2_ACT_BIT (0x00000001 << 0) // Active
#define CPWM2_DSTANDBY_BIT (0x00000001 << 1) // Deep Standby
#define CPWM2_FBOOT_BIT (0x00000001 << 2) // fast reboot
#define CPWM2_INIC_FW_RDY_BIT (0x00000001 << 3) // is the iNIC FW(1) or Boot FW(0)
#define CPWM2_TOGGLE_BIT (0x00000001 << 15) // Toggle bit
/**
* @}
*/
/** @defgroup SDIO_CPWM1_definitions The SDIO CPWM1 definations
* @{
*/
#define CPWM1_TOGGLE_BIT (0x00000001 << 7) // Toggle bit
/**
* @}
*/
/** @defgroup SDIO_EVENT_definitions The SDIO EVENT definations
* @{
*/
#define SDIO_EVENT_RX_PKT_RDY (0x00000001 << 1) // A new SDIO packet ready
#define SDIO_EVENT_DUMP (0x00000001 << 3) // SDIO status dump periodically Enable
#define SDIO_EVENT_EXIT (0x00000001 << 27) // Request to exit the SDIO task
#define SDIO_EVENT_MP_STOPPED (0x00000001 << 28) // The SDIO task is stopped
#define SDIO_EVENT_IRQ_STOPPED (0x00000001 << 29) // The SDIO task is stopped
#define SDIO_EVENT_TX_STOPPED (0x00000001 << 30) // The SDIO task is stopped
#define SDIO_EVENT_RX_STOPPED (0x00000001 << 31) // The SDIO task is stopped
/**
* @}
*/
/**
* @}
*/
/** @defgroup SDIO_Exported_Functions SDIO Exported Functions
* @{
*/
_LONG_CALL_ void SDIO_StructInit(SDIO_InitTypeDef* SDIO_InitStruct);
_LONG_CALL_ void SDIO_Init(SDIO_InitTypeDef* SDIOInit_Struct);
_LONG_CALL_ void SDIO_INTClear(void);
_LONG_CALL_ VOID SDIO_INTConfig(u16 IntMask, u32 NewState);
_LONG_CALL_ u8 SDIO_RPWM1_Get(void);
_LONG_CALL_ u16 SDIO_RPWM2_Get(void);
_LONG_CALL_ void SDIO_CPWM1_Set(u8 Val);
_LONG_CALL_ void SDIO_CPWM2_Set(u16 Val, u32 Newstate);
_LONG_CALL_ u16 SDIO_RXBD_RPTR_Get(void);
_LONG_CALL_ void SDIO_RXBD_WPTR_Set(u16 Val);
_LONG_CALL_ u16 SDIO_TXBD_WPTR_Get(void);
_LONG_CALL_ void SDIO_TXBD_RPTR_Set(u16 Val);
_LONG_CALL_ void SDIO_DMA_Reset(void);
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
#define HAL_SDIO_READ32(addr) HAL_READ32(SDIO_DEVICE_REG_BASE, addr)
#define HAL_SDIO_WRITE32(addr, value) HAL_WRITE32(SDIO_DEVICE_REG_BASE, addr, value)
#define HAL_SDIO_READ16(addr) HAL_READ16(SDIO_DEVICE_REG_BASE, addr)
#define HAL_SDIO_WRITE16(addr, value) HAL_WRITE16(SDIO_DEVICE_REG_BASE, addr, value)
#define HAL_SDIO_READ8(addr) HAL_READ8(SDIO_DEVICE_REG_BASE, addr)
#define HAL_SDIO_WRITE8(addr, value) HAL_WRITE8(SDIO_DEVICE_REG_BASE, addr, value)
/* Registers Definitions --------------------------------------------------------*/
#define REG_SPDIO_TXBD_ADDR 0xA0 // 4 Bytes
#define REG_SPDIO_TXBD_SIZE 0xA4 // 4 Bytes
#define REG_SPDIO_TXBD_WPTR 0xA8 // 2 Bytes
#define REG_SPDIO_TXBD_RPTR 0xAC // 2 Bytes
#define REG_SPDIO_RXBD_ADDR 0xB0 // 4 Bytes
#define REG_SPDIO_RXBD_SIZE 0xB4 // 2 Bytes
#define REG_SPDIO_RXBD_C2H_WPTR 0xB6 // 2 Bytes
#define REG_SPDIO_RXBD_C2H_RPTR 0xB8 // 2 Bytes
#define REG_SPDIO_HCI_RX_REQ 0xBA // 1 Byte
#define REG_SPDIO_CPU_RST_DMA 0xBB // 1 Byte
#define REG_SPDIO_RX_REQ_ADDR 0xBC // 2 Bytes
#define REG_SPDIO_CPU_INT_MASK 0xC0 // 2 Bytes
#define REG_SPDIO_CPU_INT_STAS 0xC2 // 2 Bytes
#define REG_SPDIO_CCPWM 0xC4 // 1 Byts
#define REG_SPDIO_CPU_IND 0xC5 // 1 Byte
#define REG_SPDIO_CCPWM2 0xC6 // 2 Bytes
#define REG_SPDIO_CPU_H2C_MSG 0xC8 // 4 Bytes
#define REG_SPDIO_CPU_C2H_MSG 0xCC // 4 Bytes
#define REG_SPDIO_CRPWM 0xD0 // 1 Bytes
#define REG_SPDIO_CRPWM2 0xD2 // 2 Bytes
#define REG_SPDIO_AHB_DMA_CTRL 0xD4 // 4 Bytes
#define REG_SPDIO_RXBD_CNT 0xD8 // 4 Bytes
#define REG_SPDIO_TX_BUF_UNIT_SZ 0xD9 // 1 Bytes
#define REG_SPDIO_RX_BD_FREE_CNT 0xDA // 2 Bytes
#define REG_SPDIO_CPU_H2C_MSG_EXT 0xDC // 4 Bytes
#define REG_SPDIO_CPU_C2H_MSG_EXT 0xE0 // 4 Bytes
/******************** Bits definition for REG_SPDIO_CPU_RST_DMA register *******************/
#define BIT_CPU_RST_SDIO_DMA BIT(7)
/******************** Bits definition for REG_SPDIO_CPU_INT_MASK/REG_SPDIO_CPU_INT_STAS register *******************/
#define BIT_TXFIFO_H2C_OVF BIT(0)
#define BIT_H2C_BUS_RES_FAIL BIT(1)
#define BIT_H2C_DMA_OK BIT(2)
#define BIT_C2H_DMA_OK BIT(3)
#define BIT_H2C_MSG_INT BIT(4)
#define BIT_RPWM1_INT BIT(5)
#define BIT_RPWM2_INT BIT(6)
#define BIT_SDIO_RST_CMD_INT BIT(7)
#define BIT_RXBD_FLAG_ERR_INT BIT(8)
#define BIT_RX_BD_AVAI_INT BIT(9)
#define BIT_HOST_WAKE_CPU_INT BIT(10)
#define SDIO_INIT_INT_MASK (BIT_H2C_DMA_OK | BIT_C2H_DMA_OK | \
BIT_H2C_MSG_INT | BIT_RPWM1_INT | \
BIT_RPWM2_INT |BIT_H2C_BUS_RES_FAIL | \
BIT_RXBD_FLAG_ERR_INT)
/******************** Bits definition for REG_SPDIO_CPU_IND register *******************/
#define BIT_SYSTEM_TRX_RDY_IND BIT(0)
/******************** Bits definition for REG_SPDIO_HCI_RX_REQ register *******************/
#define BIT_HCI_RX_REQ BIT(0)
#endif /* #ifndef _RTL8710B_SDIO_H_ */

View file

@ -0,0 +1,33 @@
#ifndef _HAL_SOCPS_H_
#define _HAL_SOCPS_H_
typedef struct
{
u32 Module;
u32 Status;
} PWRCFG_TypeDef;
typedef struct
{
u32 Module;
u32 Status;
u32 Polarity; /* 1 is high, 0 is low */
} WAKEPIN_TypeDef;
extern const PWRCFG_TypeDef sleep_pwrmgt_config[];
extern const PWRCFG_TypeDef sleep_wevent_config[];
extern const WAKEPIN_TypeDef sleep_wakepin_config[];
extern const PWRCFG_TypeDef dstandby_wevent_config[];
extern const WAKEPIN_TypeDef dstandby_wakepin_config[];
extern const PWRCFG_TypeDef dsleep_wevent_config[];
extern const WAKEPIN_TypeDef dsleep_wakepin_config[];
extern void SOCPS_SleepPG(void);
extern void SOCPS_InitSYSIRQ(void);
extern void SOCPS_SleepDeInit(void);
extern void SOCPS_SleepInit(void);
extern void SOCPS_DstandbyInit(void);
extern void SOCPS_DsleepInit(void);
#endif //_HAL_SOCPS_H_

View file

@ -0,0 +1,195 @@
#ifndef __INC_RTL8710B_SYS_ON_BIT_H
#define __INC_RTL8710B_SYS_ON_BIT_H
/* REG_SYS_PWR_ISO_CTRL 0x0000 */
#define BIT_SYS_PWR_SOC_EN BIT(2)
#define BIT_SYS_PWR_RET_MEM_EN BIT(1)
#define BIT_SYS_PWR_PEON_EN BIT(0)
/* REG_SYS_ISO_CTRL 0x0002 */
#define BIT_SYS_ISO_SYSPLL BIT(23)
#define BIT_SYS_ISO_32K BIT(21)
#define BIT_SYS_ISO_MEM2 BIT(20)
#define BIT_SYS_ISO_MEM1 BIT(19)
#define BIT_SYS_ISO_SOC BIT(18)
#define BIT_SYS_ISO_RET_MEM BIT(17)
#define BIT_SYS_ISO_PEON BIT(16)
/* REG_SYS_FUNC_EN 0x0008 */
#define BIT_SYS_AMACRO_EN BIT(31)
#define BIT_SYS_PWRON_TRAP_SHTDN_N BIT(30)
#define BIT_SYS_FEN_SIC_MST BIT(25)
#define BIT_SYS_FEN_SIC BIT(24)
#define BIT_SOC_SYSPEON_EN BIT(4)
#define BIT_SYS_FEN_EELDR BIT(0)
/* REG_SYS_REGU_CTRL0 0x0040 */
#define BIT_SHIFT_SYS_REGU_LDO25M_ADJ 20
#define BIT_MASK_SYS_REGU_LDO25M_ADJ 0xf
#define BIT_SYS_REGU_ANACK_4M_SEL BIT(18)
#define BIT_SYS_REGU_PC_EF_EN BIT(17)
#define BIT_SYS_REGU_LDOH12_SLP_EN BIT(16)
#define BIT_SHIFT_SYS_REGU_LDOH12_ADJ 12
#define BIT_MASK_SYS_REGU_LDOH12_ADJ 0xf
#define BIT_SHIFT_SYS_REGU_LDO25E_ADJ 8
#define BIT_MASK_SYS_REGU_LDO25E_ADJ 0xf
#define BIT_SYS_REGU_DSLEPM_EN BIT(7)
#define BIT_SYS_REGU_PC_33V_EN BIT(3)
#define BIT_SYS_REGU_PC_EF25_EN BIT(2)
#define BIT_SYS_REGU_LDO25M_EN BIT(1)
#define BIT_SYS_REGU_LDO25E_EN BIT(0)
/* REG_SYS_SWR_CTRL0 0x0048 */
#define BIT_SHIFT_SYS_SWR12_COMP_R2 30
#define BIT_MASK_SYS_SWR12_COMP_R2 0x3
#define BIT_SHIFT_SYS_SWR12_COMP_R1 28
#define BIT_MASK_SYS_SWR12_COMP_R1 0x3
#define BIT_SHIFT_SYS_SWR12_COMP_C3 26
#define BIT_MASK_SYS_SWR12_COMP_C3 0x3
#define BIT_SHIFT_SYS_SWR12_COMP_C2 24
#define BIT_MASK_SYS_SWR12_COMP_C2 0x3
#define BIT_SHIFT_SYS_SWR12_COMP_C1 22
#define BIT_MASK_SYS_SWR12_COMP_C1 0x3
#define BIT_SYS_SWR12_COMP_TYPE_L BIT(21)
#define BIT_SYS_SWR12_FPWM_MD BIT(20)
#define BIT_SHIFT_SYS_SPSLDO_VOL 17
#define BIT_MASK_SYS_SPSLDO_VOL 0x7
#define BIT_SHIFT_SYS_SWR12_IN 14
#define BIT_MASK_SYS_SWR12_IN 0x7
#define BIT_SHIFT_SYS_SWR12_STD 12
#define BIT_MASK_SYS_SWR12_STD 0x3
#define BIT_SHIFT_SYS_SWR12_VOL 8
#define BIT_MASK_SYS_SWR12_VOL 0xf
#define BIT_SYS_SWR_EN BIT(1)
#define BIT_SYS_SWR_LDO_EN BIT(0)
/* REG_SYS_SWR_CTRL1 0x004C */
#define BIT_SYS_SW12_PFM_SEL BIT(25)
#define BIT_SYS_SW12_AUTO_ZCD_L BIT(24)
#define BIT_SYS_SW12_AUTO_MODE BIT(23)
#define BIT_SYS_SW12_LDOF_L BIT(22)
#define BIT_SYS_SW12_OCPS_L BIT(21)
#define BIT_SHIFT_SYS_SW12_TBOX 17
#define BIT_MASK_SYS_SW12_TBOX 0x3
#define BIT_SHIFT_SYS_SW12_NONOVRLAP_DLY 15
#define BIT_MASK_SYS_SW12_NONOVRLAP_DLY 0x3
#define BIT_SYS_SW12_CLAMP_DUTY BIT(14)
#define BIT_SYS_SWR12_BYPASS_SSR BIT(13)
#define BIT_SYS_SWR12_ZCDOUT_EN BIT(12)
#define BIT_SYS_SWR12_POW_ZCD BIT(11)
#define BIT_SYS_SW12_AREN BIT(10)
#define BIT_SHIFT_SYS_SWR12_OCP_CUR 7
#define BIT_MASK_SYS_SWR12_OCP_CUR 0x7
#define BIT_SYS_SWR12_OCP_EN BIT(6)
#define BIT_SHIFT_SYS_SWR12_SAWTOOTH_CF_L 4
#define BIT_MASK_SYS_SWR12_SAWTOOTH_CF_L 0x3
#define BIT_SHIFT_SYS_SWR12_SAWTOOTH_CFC_L 2
#define BIT_MASK_SYS_SWR12_SAWTOOTH_CFC_L 0x3
#define BIT_SHIFT_SYS_SWR12_COMP_R3 0
#define BIT_MASK_SYS_SWR12_COMP_R3 0x3
/* REG_SYS_PINMUX_CTRL 0x00A4 */
#define BIT_SWD_PU_EN BIT(12) /*!< SWD pinmux use REG_SYS_PINMUX_CTRL enable */
#define BIT_SWD_S1_PU BIT(11) /*!< SWD S1 PU */
#define BIT_SWD_S0_PU BIT(10) /*!< SWD S0 PU */
#define BIT_SDIO_S1_PU BIT(9) /*!< SDIO S1 PU: GPIOA_6 ~ GPIOA_11 */
#define BIT_SDIO_S0_PU BIT(8) /*!< SDIO S0 PU: GPIOA_18 ~ GPIOA_23 */
#define BIT_SIC_PIN_EN BIT(0) /*!< 1: Enable SIC PINMUX function; 0: disable */
/* REG_SYS_DEBUG_REG 0x00BC */
#define BIT_SHIFT_SYS_DBG_VALUE 0
#define BIT_MASK_SYS_DBG_VALUE 0xffffffffL
/* REG_SYS_EEPROM_CTRL0 0x00E0 */
#define BIT_MASK_EFUSE_UNLOCK (0xff << 24)
#define BIT_SYS_EFUSE_LDALL BIT(16)
#define BIT_MASK_SYS_EEPROM_MD (0x3 << 6)
#define BIT_SYS_AUTOLOAD_SUS BIT(5)
#define BIT_SYS_EEPROM_SEL BIT(4)
/* REG_SYS_EEPROM_CTRL1 0x00E4 */
#define BIT_MASK_SYS_EEPROM_VPD 0xffffffffL
/* REG_SYS_EFUSE_CTRL 0x00E8 */
#define BIT_SYS_EF_RWFLAG (0x00000001 << 31)
#define BIT_MASK_SYS_EF_PGPD (0x00000007 << 28)
#define BIT_MASK_SYS_EF_RDT (0x0000000f << 20)
#define BIT_MASK_SYS_EF_PGTS (0x0000000f << 20)
#define BIT_SYS_EF_ALDEN (0x00000001 << 18)
#define BIT_MASK_SYS_EF_ADDR (0x000003ff << 8)
#define BIT_MASK_SYS_EF_DATA (0x000000ff)
/* REG_SYS_EFUSE_TEST 0x00EC */
#define BIT_SYS_EF_CRES_SEL (0x00000001 << 26)
#define BIT_MASK_SYS_EF_SCAN_START (0x000001ff << 16)
#define BIT_MASK_SYS_EF_SCAN_END (0x0000000f << 12)
#define BIT_SYS_EF_FORCE_PGMEN (0x00000001 << 11)
#define BIT_SYS_EF_TRPT (0x00000001 << 7)
#define BIT_MASK_SYS_EF_SCAN_TTHD (0x0000007f)
/* REG_SYS_PERI_MONITOR 0x0134 */
#define BIT_RTC_DIV_XTAL 0x07FF0000//1221 [26:16]
#define BIT_RTC_PEN ((u32)(0x00000001 << 12))
#define BIT_RTC_DIV_XTAL_EN ((u32)(0x00000001 << 11))
#define BIT_RTC_CK_SEL ((u32)(0x00000001 << 10))
#define BIT_RTC_CK_EN ((u32)(0x00000001 << 9))
#define BIT_RTC_EN ((u32)(0x00000001 << 8))
//================= SYSON Register Address Definition =====================//
#define REG_SYS_PWR_ISO_CTRL 0x0000 /*!< 0x00: REG_SYS_PWR_CTRL, 0x02: REG_SYS_ISO_CTRL */
#define REG_SYS_FUNC_EN 0x0008
#define REG_SYS_CLK_CTRL0 0x0010
#define REG_SYS_CLK_CTRL1 0x0014
#define REG_SYS_EFUSE_SYSCFG0 0x0020 /*!< BYTE0x00~0x03 */
#define REG_SYS_EFUSE_SYSCFG1 0x0024 /*!< BYTE0x04~0x07 */
#define REG_SYS_EFUSE_SYSCFG2 0x0028 /*!< BYTE0x08~0x0B */
#define REG_SYS_EFUSE_SYSCFG3 0x002C /*!< BYTE0x0C~0x0F */
#define REG_SYS_EFUSE_SYSCFG4 0x0030 /*!< BYTE0x10~0x13 */
#define REG_SYS_EFUSE_SYSCFG5 0x0034 /*!< BYTE0x14~0x17 */
#define REG_SYS_EFUSE_SYSCFG6 0x0038 /*!< BYTE0x18~0x1B */
#define REG_SYS_EFUSE_SYSCFG7 0x003C
#define REG_SYS_REGU_CTRL0 0x0040
#define REG_SYS_SWR_CTRL0 0x0048
#define REG_SYS_SWR_CTRL1 0x004C
#define REG_SYS_XTAL_CTRL0 0x0060
#define REG_SYS_XTAL_CTRL1 0x0064
#define REG_SYS_XTAL_CTRL2 0x0068
#define REG_SYS_SYSPLL_CTRL0 0x0070
#define REG_SYS_SYSPLL_CTRL1 0x0074
#define REG_SYS_SYSPLL_CTRL2 0x0078
#define REG_SYS_SYSPLL_CTRL3 0x007C
#define REG_SYS_ANA_TIM_CTRL 0x0090
#define REG_SYS_DSLP_TIM_CTRL 0x0094
#define REG_SYS_DSLP_TIM_CAL_CTRL 0x0098
#define REG_SYS_PINMUX_CTRL 0x00A4
#define REG_SYS_GPIO_DSTBY_WAKE_CTRL0 0x00A8
#define REG_SYS_GPIO_DSTBY_WAKE_CTRL1 0x00AC
#define REG_SYS_DEBUG_REG 0x00BC
#define REG_SYS_EEPROM_CTRL0 0x00E0
#define REG_SYS_EEPROM_CTRL1 0x00E4
#define REG_SYS_EFUSE_CTRL 0x00E8
#define REG_SYS_EFUSE_TEST 0x00EC
#define REG_OSC32K_CTRL 0x00F0 /* AmebaZ move to 0xf0 */
#define REG_OSC32K_RCAL 0x00F4 /* AmebaZ Add */
#define REG_SYS_DSTBY_INFO0 0x00F8
#define REG_SYS_DSTBY_INFO1 0x00FC
#define REG_SYS_SLP_WAKE_EVENT_MSK0 0x0100
#define REG_SYS_SLP_WAKE_EVENT_MSK1 0x0104
#define REG_SYS_SLP_WAKE_EVENT_STATUS0 0x0108
#define REG_SYS_SLP_WAKE_EVENT_STATUS1 0x010C
#define REG_SYS_SNF_WAKE_EVENT_MSK0 0x0110
#define REG_SYS_SNF_WAKE_EVENT_STATUS 0x0114
#define REG_SYS_PWRMGT_CTRL 0x0118
#define REG_SYS_PWRMGT_OPTION 0x0120
#define REG_SYS_PWRMGT_OPTION_EXT 0x0124
#define REG_SYS_DSLP_WEVENT 0x0130
#define REG_SYS_PERI_MONITOR 0x0134
#define REG_SYS_NORESET_FF 0x0138
#define REG_SYS_SYSTEM_CFG0 0x01F0
#define REG_SYS_SYSTEM_CFG1 0x01F4
#define REG_SYS_SYSTEM_CFG2 0x01F8
#endif //__INC_RTL8710B_SYS_ON_BIT_H

View file

@ -0,0 +1,481 @@
/**
******************************************************************************
* @file rtl8710b_usb.h
* @author
* @version V1.0.0
* @date 2016-05-17
* @brief This file contains all the functions prototypes for the USOC firmware
* library.
******************************************************************************
* @attention
*
* This module is a confidential and proprietary property of RealTek and
* possession or use of this module requires written permission of RealTek.
*
* Copyright(c) 2016, Realtek Semiconductor Corporation. All rights reserved.
******************************************************************************
*/
#ifndef _RTL8710B_USOC_H_
#define _RTL8710B_USOC_H_
/** @addtogroup AmebaZ_Periph_Driver
* @{
*/
/** @defgroup USOC
* @brief USOC driver modules
* @{
*/
/** @addtogroup USOC
* @verbatim
*****************************************************************************************
* Introduction
*****************************************************************************************
* USOC:
* - Base Address: USOC_REG
* - Clock domains: USOC domain use 62.5M divided by system clock. SIE domain uses 30M UTMI clock
* - DMA: use descriptor ring, default ring size is 8
* - IRQ: USB_IRQ
* - Interrupt mitigation
* - Error handling
*
*****************************************************************************************
* How to use USOC in iNIC mode
*****************************************************************************************
* To use the USOC in iNIC mode, the following steps are mandatory:
*
* 1. USOC power on using USOC_POWER_On().
*
* 2. Init TXBD and RXBD
*
* 3. Disable USOC using USOC_Cmd(USOC_REG, DISABLE).
*
* 4. Config USOC work mode using USOC_MODE_Cfg(USOC_REG, USB_INIC_MODE).
*
* 5. Call USOC_Init(USOC_REG, &USOCInit_Struct) to configure USOC register with the
* corresponding configuration.
*
* 6. To configure interrupts using USOC_INTCfg() function.
*
* 7. Activate the USOC peripheral using USOC_Cmd(USOC_REG, ENABLE) function
*
*****************************************************************************************
* How to use USOC in dongle mode
*****************************************************************************************
* To use USOC dongle mode, the following steps are mandatory:
*
* 1. Enable WL clock and Lx Bus.
*
* 2. USOC power on using USOC_POWER_On().
*
* 3. Disable USOC using USOC_Cmd(USOC_REG, DISABLE).
*
* 4. Open register(WLON) access channel using USOC_CH_Cmd(USOC_REG, USOC_CH2, ENABLE).
*
* 5. Config USOC work mode using USOC_MODE_Cfg(USOC_REG, USB_DONGLE_MODE).
*
* @note All other functions can be used separately to modify, if needed,
* a specific feature of the USOC
*
*****************************************************************************************
* @endverbatim
*/
/* Exported types ------------------------------------------------------------*/
/** @defgroup USOC_Exported_Types USOC Exported Types
* @{
*/
/**
* @brief USOC Init structure definition
*/
typedef struct {
/* TXBD */
u32 TXBD_BAR; /*!< Specifies TXBD base address */
u32 TXBD_RING_SIZE; /*!< Specifies TXBD ring size
This parameter must be set to a value in the 0-32 range. */
u32 TX_BUFFER_SIZE; /*!< Specifies TX buffer size
In iNIC mode, this parameter must be set to a value in the 0-1536 range. */
u32 TX_BLK_SIZE; /*!< Specifies AHB TX block size
This parameter must be set to a value in the 0-15 range. */
u32 TX_MIT_TIME; /*!< Specifies TX time mitigation
This parameter must be set to a value in the 0-65535 range. */
u32 TX_MIT_PKT_CNT; /*!< Specifies TX packet count mitigation
This parameter must be set to a value in the 0-63 range. */
/* RXBD */
u32 RXBD_BAR; /*!< Specifies RXBD base address */
u32 RXBD_RING_SIZE; /*!< Specifies RXBD ring size
This parameter must be set to a value in the 0-32 range. */
u32 RX_BUFFER_SIZE; /*!< Specifies RX buffer size
In iNIC mode, this parameter must be set to a value in the 0-1536 range. */
u32 RX_BLK_SIZE; /*!< Specifies AHB RX block size
This parameter must be set to a value in the 0-15 range. */
u32 RX_MIT_TIME; /*!< Specifies RX time mitigation
This parameter must be set to a value in the 0-65535 range. */
u32 RX_MIT_PKT_CNT; /*!< Specifies RX packet count mitigation
This parameter must be set to a value in the 0-63 range. */
} USOC_InitTypeDef;
/**
* @brief USOC TXBD structure definition
*/
typedef struct {
u32 pktSize:14; /*!< bit[0:13], specifies tx packet size */
u32 status:2; /*!< bit[14:15], specifies the txbd status
This parameter can be set to 00(init), or 01(ready), or 10(ok), or 11(err) */
u32 seqNum:16; /*!< bit[16:31], specifies txbd sequence number */
u32 address; /*!< Specifies the TX buffer physical address
@note This parameter must be 64-bytes aligned */
}USOC_TX_BD, *PUSOC_TX_BD;
/**
* @brief USOC RXBD structure definition
*/
typedef struct {
u32 pktSize:14; /*!< bit[0:13], specifies rx packet size */
u32 status:2; /*!< bit[14:15], specifies the rxbd status
This parameter can be set to 00(init), or 01(ready), or 10(ok), or 11(err) */
u32 seqNum:16; /*!< bit[16:31], specifies rxbd sequence number */
u32 address; /*!< Specifies the RX buffer physical address
@note This parameter must be 64-bytes aligned */
} USOC_RX_BD, *PUSOC_RX_BD;
/**
* @}
*/
/* Exported constants --------------------------------------------------------*/
/** @defgroup USOC_Exported_Constants USOC Exported Constants
* @{
*/
/** @defgroup USOC_TXBD_definitions The TX Buffer Descriptor format
* @{
*/
#define TXBD_STAT_INIT 0
#define TXBD_STAT_RDY 1
#define TXBD_STAT_OK 2
#define TXBD_STAT_ERR 3
#define USOC_TXBD_SIZE 8
/**
* @}
*/
/** @defgroup USOC_RXBD_definitions The RX Buffer Descriptor format
* @{
*/
#define RXBD_STAT_INIT 0
#define RXBD_STAT_RDY 1
#define RXBD_STAT_OK 2
#define RXBD_STAT_ERR 3
#define USOC_RXBD_SIZE 8
/**
* @}
*/
/** @defgroup USOC_Mode_definitions
* @{
*/
#define USB_INIC_MODE 0 /*!< INIC */
#define USB_DONGLE_MODE 1 /*!< WIFI dongle mode */
#define USB_AINST_MODE 2 /*!< AUTO install */
/**
* @}
*/
/** @defgroup USOC_Chan_definitions
* @{
*/
#define USOC_CH0 0 /*!< iTDE */
#define USOC_CH1 1 /*!< iRDE */
#define USOC_CH2 2 /*!< iREG */
/**
* @}
*/
/** @defgroup USOC_TX_Ring_definitions
* @{
*/
#define USOC_TXBD_RING_SIZE 8
#define USOC_TX_BUFFER_SIZE 1536
#define USOC_TX_BLK_SIZE 6
#define USOC_TX_BUFFER_SIZE_ALIGN (USOC_TX_BUFFER_SIZE+(1 << USOC_TX_BLK_SIZE))
/**
* @}
*/
/** @defgroup USOC_RX_Ring_definitions
* @{
*/
#define USOC_RXBD_RING_SIZE 8
#define USOC_RX_BUFFER_SIZE 1536
#define USOC_RX_BLK_SIZE 6
#define USOC_RX_BUFFER_SIZE_ALIGN (USOC_RX_BUFFER_SIZE+(1 << USOC_RX_BLK_SIZE))
/**
* @}
*/
/** @defgroup USOC_INTR_MIT_definitions
* @{
*/
#define USOC_INTR_TX_MIT_TIME 625
#define USOC_INTR_RX_MIT_TIME 625
#define USOC_INTR_TX_MIT_PKT_CNT 4
#define USOC_INTR_RX_MIT_PKT_CNT 4
/**
* @}
*/
/** @defgroup USOC_STUCK_TIME_definitions
* @{
*/
#define USOC_TX_STUCK_TIME 4096/*!< Specifies TX DMA stuck time, must be set to a value in the 0-65535 range. */
#define USOC_RX_STUCK_TIME 4096/*!< Specifies RX DMA stuck time, must be set to a value in the 0-65535 range. */
/**
* @}
*/
/**
* @}
*/
/** @defgroup USOC_Exported_Functions USOC Exported Functions
* @{
*/
_LONG_CALL_ VOID USOC_Cmd(USOC_REG_TypeDef * usoc_reg, u32 NewStatus);
_LONG_CALL_ VOID USOC_PHY_Cmd(USOC_REG_TypeDef * usoc_reg, u32 NewStatus);
_LONG_CALL_ VOID USOC_MODE_Cfg(USOC_REG_TypeDef * usoc_reg, u32 mode);
_LONG_CALL_ VOID USOC_TXBD_SWIDX_Cfg(USOC_REG_TypeDef * usoc_reg, u32 index);
_LONG_CALL_ u32 USOC_TXBD_SWIDX_Get(USOC_REG_TypeDef * usoc_reg);
_LONG_CALL_ VOID USOC_RXBD_SWIDX_Cfg(USOC_REG_TypeDef * usoc_reg, u32 index);
_LONG_CALL_ u32 USOC_RXBD_SWIDX_Get(USOC_REG_TypeDef * usoc_reg);
_LONG_CALL_ u32 USOC_TXBD_HWIDX_Get(USOC_REG_TypeDef * usoc_reg);
_LONG_CALL_ u32 USOC_RXBD_HWIDX_Get(USOC_REG_TypeDef * usoc_reg);
_LONG_CALL_ VOID USOC_INTCfg(USOC_REG_TypeDef * usoc_reg, u32 mask);
_LONG_CALL_ VOID USOC_INTClr(USOC_REG_TypeDef * usoc_reg, u32 mask);
_LONG_CALL_ u32 USOC_INTGet(USOC_REG_TypeDef * usoc_reg);
_LONG_CALL_ VOID USOC_StructInit(USOC_InitTypeDef* USOCInit_Struct);
_LONG_CALL_ VOID USOC_Init(USOC_REG_TypeDef * usoc_reg, USOC_InitTypeDef* USOCInit_Struct);
_LONG_CALL_ VOID USOC_POWER_On(VOID);
_LONG_CALL_ VOID USOC_CH_Cmd(USOC_REG_TypeDef * usoc_reg, u32 ch, u32 NewStatus);
_LONG_CALL_ VOID USOC_SW_RST(USOC_REG_TypeDef * usoc_reg);
_LONG_CALL_ VOID USOC_TXSTUCK_Cfg(USOC_REG_TypeDef * usoc_reg, u32 NewStatus, u32 TVal);
_LONG_CALL_ VOID USOC_RXSTUCK_Cfg(USOC_REG_TypeDef * usoc_reg, u32 NewStatus, u32 RVal);
/**
* @}
*/
/* Registers Definitions --------------------------------------------------------*/
/**************************************************************************//**
* @defgroup USOC_Register_Definitions USOC Register Definitions
* @{
*****************************************************************************/
/**************************************************************************//**
* @defgroup REG_USOC_CR
* @{
*****************************************************************************/
#define BIT_CR_INIC_MODE_EN ((u32)0x00000001 << 0) /*!< enable inic mode(usoc) */
#define BIT_CR_AUTO_LOAD_DONE ((u32)0x00000001 << 1) /*!< indicate SIE autoload done. HW autoclear. */
#define BIT_CR_USB_RF_EN ((u32)0x00000001 << 2) /*!< CM4 read SIE EN */
#define BIT_CR_USB_PHY_EN ((u32)0x00000001 << 3) /*!< enable USB PHY */
#define BIT_CR_SIE_RERUN ((u32)0x00000001 << 4) /*!< Rerun USB SIE. HW autoclear. */
#define BIT_CR_WLAN_USB_EN ((u32)0x00000001 << 5) /*!< enable SIE dongle mode */
#define BIT_CR_INIC_USB_EN ((u32)0x00000001 << 6) /*!< enable SIE iNIC mode */
#define BIT_CR_AINST_USB_EN ((u32)0x00000001 << 7) /*!< enable SIE autoinstall mode */
#define BIT_CR_USB1D1_EN ((u32)0x00000001 << 8) /*!< enable SIE USB 1.1 */
#define BIT_CR_RST_SIE_TX ((u32)0x00000001 << 9) /*!< SIE TX software reset. Active low. */
#define BIT_CR_RST_SIE_RX ((u32)0x00000001 << 10) /*!< SIE RX software reset. Active low. */
#define BIT_CR_SIE_LOAD_FAIL ((u32)0x00000001 << 11) /*!< SIE autoload fail */
/** @} */
/**************************************************************************//**
* @defgroup CLK_RST_CTRL
* @{
*****************************************************************************/
#define BIT_RST_ITDE ((u32)0x00000001 << 24)
#define BIT_RST_IRDE ((u32)0x00000001 << 25)
#define BIT_RST_TX_HW_IDX ((u32)0x00000001 << 26)
#define BIT_RST_RX_HW_IDX ((u32)0x00000001 << 27)
#define BIT_RST_TX_IF ((u32)0x00000001 << 28)
#define BIT_RST_RX_IF ((u32)0x00000001 << 29)
#define BIT_RST_AHB_AUX ((u32)0x00000001 << 30)
#define BIT_RST_UTMI_AUX ((u32)0x00000001 << 31)
#define USOC_SW_RST_MASK (BIT_RST_ITDE | BIT_RST_IRDE | \
BIT_RST_TX_HW_IDX | BIT_RST_RX_HW_IDX | \
BIT_RST_TX_IF | BIT_RST_RX_IF | \
BIT_RST_UTMI_AUX)
/** @} */
/**************************************************************************//**
* @defgroup CHANN_CTRL
* @{
*****************************************************************************/
#define BIT_PRI_CH0_CFG ((u32)0x00000007 << 0)
#define BIT_PRI_CH1_CFG ((u32)0x00000007 << 4)
#define BIT_PRI_CH2_CFG ((u32)0x00000007 << 8)
#define BIT_EN_CH0 ((u32)0x00000001 << 3) /*!< enable iTDE */
#define BIT_EN_CH1 ((u32)0x00000001 << 7) /*!< enable iRDE */
#define BIT_EN_CH2 ((u32)0x00000001 << 11) /*!< enable iREG */
#define BIT_TX_BLK_SZ_CFG(x) ((u32)((x) & 0x0000000f) << 16)
#define BIT_RX_BLK_SZ_CFG(x) ((u32)((x) & 0x0000000f) << 20)
/** @} */
/**************************************************************************//**
* @defgroup BUFFER_SIZE
* @{
*****************************************************************************/
#define BIT_TXBUF_SIZE_CFG(x) ((u32)((x) & 0x00000fff) << 0)
#define BIT_RXBUF_SIZE_CFG(x) ((u32)((x) & 0x00000fff) << 16)
/** @} */
/**************************************************************************//**
* @defgroup RING_SIZE
* @{
*****************************************************************************/
#define BIT_TXBD_RING_SZ_CFG(x) ((u32)((x) & 0x000000ff) << 0)
#define BIT_RXBD_RING_SZ_CFG(x) ((u32)((x) & 0x000000ff) << 8)
#define BIT_MASK_TXBD_SW_IDX ((u32)0x000000ff)
#define BIT_MASK_RXBD_SW_IDX ((u32)0x000000ff)
#define BIT_MASK_TXBD_HW_IDX ((u32)0x000000ff)
#define BIT_MASK_RXBD_HW_IDX ((u32)0x000000ff)
/** @} */
/**************************************************************************//**
* @defgroup REG_USOC_INTR_MASK_or_REG_USOC_INTR_STAT
* @{
*****************************************************************************/
#define BIT_INTR_TX_PKT_OK ((u32)0x00000001 << 0)
#define BIT_INTR_RX_PKT_OK ((u32)0x00000001 << 1)
#define BIT_INTR_SIE_TX_FAIL ((u32)0x00000001 << 2)
#define BIT_INTR_SIE_RX_FAIL ((u32)0x00000001 << 3)
#define BIT_INTR_TX_TIMEOUT ((u32)0x00000001 << 4)
#define BIT_INTR_RX_TIMEOUT ((u32)0x00000001 << 5)
#define BIT_INTR_TX_BUS_ERR ((u32)0x00000001 << 6)
#define BIT_INTR_RX_BUS_ERR ((u32)0x00000001 << 7)
#define BIT_INTR_BAD_TX_BD ((u32)0x00000001 << 8)
#define BIT_INTR_BAD_RX_BD ((u32)0x00000001 << 9)
#define BIT_INTR_NO_TX_BD ((u32)0x00000001 << 10)
#define BIT_INTR_NO_RX_BD ((u32)0x00000001 << 11)
#define BIT_INTR_TX_AB_WERR ((u32)0x00000001 << 16)
#define BIT_INTR_TX_AB_RERR ((u32)0x00000001 << 17)
#define BIT_INTR_TX_MB_WERR ((u32)0x00000001 << 18)
#define BIT_INTR_TX_MB_RERR ((u32)0x00000001 << 19)
#define BIT_INTR_TX_DB_WERR ((u32)0x00000001 << 20)
#define BIT_INTR_TX_DB_RERR ((u32)0x00000001 << 21)
#define BIT_INTR_RX_AB_WERR ((u32)0x00000001 << 24)
#define BIT_INTR_RX_AB_RERR ((u32)0x00000001 << 25)
#define BIT_INTR_RX_MB_WERR ((u32)0x00000001 << 26)
#define BIT_INTR_RX_MB_RERR ((u32)0x00000001 << 27)
#define BIT_INTR_RX_SB_WERR ((u32)0x00000001 << 28)
#define BIT_INTR_RX_SB_RERR ((u32)0x00000001 << 29)
#define USOC_INIT_INTR_MASK (BIT_INTR_TX_PKT_OK | BIT_INTR_RX_PKT_OK | \
BIT_INTR_SIE_TX_FAIL | BIT_INTR_SIE_RX_FAIL | \
BIT_INTR_TX_TIMEOUT | BIT_INTR_RX_TIMEOUT| \
BIT_INTR_TX_BUS_ERR | BIT_INTR_RX_BUS_ERR | \
BIT_INTR_NO_TX_BD | BIT_INTR_NO_RX_BD | \
BIT_INTR_BAD_TX_BD |BIT_INTR_BAD_RX_BD)
/** @} */
/**************************************************************************//**
* @defgroup INTR_TX_MITIGATION
* @{
*****************************************************************************/
#define BIT_TX_MIT_TIME_CFG(x) ((u32)((x) & 0x0000ffff) << 0)
#define BIT_TX_MIT_PKT_CNT_CFG(x) ((u32)((x) & 0x0000003f) << 16)
#define BIT_TX_MIT_EN ((u32)0x00000001 << 31)
/** @} */
/**************************************************************************//**
* @defgroup INTR_RX_MITIGATION
* @{
*****************************************************************************/
#define BIT_RX_MIT_TIME_CFG(x) ((u32)((x) & 0x0000ffff) << 0)
#define BIT_RX_MIT_PKT_CNT_CFG(x) ((u32)((x) & 0x0000003f) << 16)
#define BIT_RX_MIT_EN ((u32)0x00000001 << 31)
/** @} */
/**************************************************************************//**
* @defgroup REG_TX_STUCK_TIMER
* @{
*****************************************************************************/
#define BIT_TX_STUCK_TIME_CFG(x) ((u32)((x) & 0x0000ffff) << 0)
#define BIT_TX_STUCK_TIMER_EN ((u32)0x00000001 << 16)
/** @} */
/**************************************************************************//**
* @defgroup REG_RX_STUCK_TIMER
* @{
*****************************************************************************/
#define BIT_RX_STUCK_TIME_CFG(x) ((u32)((x) & 0x0000ffff) << 0)
#define BIT_RX_STUCK_TIMER_EN ((u32)0x00000001 << 16)
/** @} */
/**************************************************************************//**
* @defgroup REG_OTG_PWCSEQ_PWC
* @{
*****************************************************************************/
#define BIT_PWC_USBD_EN ((u32)0x00000001 << 0)
#define BIT_PWC_UPLV_EN ((u32)0x00000001 << 1)
#define BIT_PWC_UPHV_EN ((u32)0x00000001 << 2)
/** @} */
/**************************************************************************//**
* @defgroup REG_OTG_PWCSEQ_ISO
* @{
*****************************************************************************/
#define BIT_ISO_USBD_EN ((u32)0x00000001 << 0)
#define BIT_ISO_USBA_EN ((u32)0x00000001 << 1)
/** @} */
/**************************************************************************//**
* @defgroup REG_OTG_PWCSEQ_OTG
* @{
*****************************************************************************/
#define BIT_UPLL_CKRDY ((u32)0x00000001 << 5)
#define BIT_USBOTG_EN ((u32)0x00000001 << 8)
#define BIT_USBPHY_EN ((u32)0x00000001 << 9)
/** @} */
/** @} */
/**
* @}
*/
/**
* @}
*/
#endif //_RTL8710B_USOC_H_
/******************* (C) COPYRIGHT 2016 Realtek Semiconductor *****END OF FILE****/

View file

@ -0,0 +1,78 @@
#ifndef __INC_RTL8711B_WL_ON_H
#define __INC_RTL8711B_WL_ON_H
/* this is a subset of hal_com_reg.h */
/* BIT_WL_PMC_OFFMAC 0x0020 */
#define BIT_WL_PMC_OFFMAC (0x00000001 << 1) /*!< Auto FSM to Turn On, include clock, isolation, power control for MAC only
(auto set by ICFG, and clear when Power Ready) */
#define BIT_WL_APMC_ONMAC (0x00000001 << 0) /*!< Auto FSM to Turn On, include clock, isolation, power control for MAC only */
/* REG_WL_RF_PSS 0x005c */
#define BIT_AFE_POWER_MODE_SEL (0x00000001 << 8) /*!< AFE power mode selection:1: LDO mode 0: Power-cut mode */
#define BIT_SEL_LDO_RF (0x00000001 << 2) /*!< Power source selection1: LDO mode (power source is 3.3V,VD33PAD); 0: Power Cut mode (Power source is 1.2V,VDTR). */
#define BIT_SEL_LDO_SYN (0x00000001 << 1) /*!< Power source selection1: LDO mode (power source is 3.3V,VD33SYN); 0: Power Cut mode (Power source is 1.2V,VDSYN). */
#define BIT_SEL_LDO_BUF (0x00000001 << 0) /*!< Power source selection1: LDO mode (power source is 3.3V,VD33SYN); 0: Power Cut mode (Power source is 1.2V,VDSYN). */
/* REG_USB_INDIRECT_CTRL 0x006c */
#define BIT_USB_HOST_INT_REQ (0x00000001 << 31) /*!< For USB doggle mode, USB Host write this bit to 1 will trigger interrupt to CM4. After CM4 finishes handling this interrupt , CM4 will clear this bit to 0 */
//#define BIT_USB_HOST_INT_TYPE (0x00000001 << 30) /*!< 0: read efuse, 1: write efuse, 2: host cmd */
#define BIT_USB_HOST_CMD (0x0000001F << 24) /*!< host cmd val */
/* REG_USB_SIE_IMR 0x0078 */
#define BIT_EFUSE_RD_MSK_CM4 (0x00000001 << 23) /*!< USB host indirect read efuse interrupt mask for cm4 */
#define BIT_USB_SUS_MSK_CM4 (0x00000001 << 22) /*!< USB suspend interrupt mask for cm4 */
#define BIT_USB_RES_MSK_CM4 (0x00000001 << 21) /*!< USB resume interrupt mask for cm4 */
#define BIT_SE0_RST_MSK_CM4 (0x00000001 << 20) /*!< SE0 reset interrupt mask for cm4 */
#define BIT_SIE_ACK_DONE_MSK_CM4 (0x00000001 << 19) /*!< SIE ACK done interrupt mask for cm4 */
#define BIT_SIE_NAK_DONE_MSK_CM4 (0x00000001 << 18) /*!< SIE NAK done interrupt mask for cm4 */
#define BIT_LPM_RSM_MSK_CM4 (0x00000001 << 17) /*!< SIE resume from LPM interrupt mask for cm4 */
#define BIT_LPM_ACT_MSK_CM4 (0x00000001 << 16) /*!< SIE enter LPM interrupt mask for cm4 */
#define BIT_EFUSE_RD_MSK_DW8051 (0x00000001 << 7) /*!< USB host indirect read efuse interrupt mask for dw8051 */
#define BIT_USB_SUS_MSK_DW8051 (0x00000001 << 6) /*!< USB suspend interrupt mask for dw8051 */
#define BIT_USB_RES_MSK_DW8051 (0x00000001 << 5) /*!< USB resume interrupt mask for dw8051 */
#define BIT_SE0_RST_MSK_DW8051 (0x00000001 << 4) /*!< SE0 reset interrupt mask for dw8051 */
#define BIT_SIE_ACK_DONE_MSK_DW8051 (0x00000001 << 3) /*!< SIE ACK done interrupt mask for dw8051 */
#define BIT_SIE_NAK_DONE_MSK_DW8051 (0x00000001 << 2) /*!< SIE NAK done interrupt mask for dw8051 */
#define BIT_LPM_RSM_MSK_DW8051 (0x00000001 << 1) /*!< SIE resume from LPM interrupt mask for dw8051 */
#define BIT_LPM_ACT_MSK_DW8051 (0x00000001 << 0) /*!< SIE enter LPM interrupt mask for dw8051 */
/* REG_USB_SIE_INT 0x007c */
#define BIT_USB_CMD_INT ((u32)(0x00000001 << 7)) /*!< USB host indirect read/write efuse or host cmd interrupt */
#define BIT_USB_SUS_INT ((u32)(0x00000001 << 6)) /*!< USB suspend interrupt */
#define BIT_USB_RES_INT ((u32)(0x00000001 << 5)) /*!< USB resume interrupt */
#define BIT_SE0_RST_INT ((u32)(0x00000001 << 4)) /*!< SE0 reset interrupt */
#define BIT_SIE_ACK_DONE_INT ((u32)(0x00000001 << 3)) /*!< SIE ACK done interrupt */
#define BIT_SIE_NAK_DONE_INT ((u32)(0x00000001 << 2)) /*!< SIE NAK done interrupt */
#define BIT_LPM_RSM_INT ((u32)(0x00000001 << 1)) /*!< SIE resume from LPM interrupt */
#define BIT_LPM_ACT_INT ((u32)(0x00000001 << 0)) /*!< IE enter LPM interrupt */
/* REG_USB_PWR_OPT 0x0088 */
#define BIT_CM4_WAKE_USB ((u32)(0x00000001 << 6)) /*!< R/W 0 cm4 wakeup usb device, 1: wakeup 0: not wakeup */
#define BIT_HOST_WAKE_DEV_EN ((u32)(0x00000001 << 5)) /*!< R/W 0 usb host wake device function enable, 1: Enable, 0:Disable */
#define BIT_HOST_WAKE_DEV ((u32)(0x00000001 << 4)) /*!< R/W 0 usb host wake device, 1: wake */
#define BIT_USB_LPS_BLOCK ((u32)(0x00000001 << 3)) /*!< R/W 0 Block USB RX for wlan is in LPS, 1: Block RX ; 0: Not block */
#define BIT_USB_LPM_NY ((u32)(0x00000001 << 2)) /*!< R/W 0 USB LPM Not Yet */
#define BIT_USB_SUS_DIS ((u32)(0x00000001 << 1)) /*!< R/W 0 Disable USB enter suspend, 1: Disable, 0: enable */
#define BIT_USB_LPMACT_EN ((u32)(0x00000001 << 0)) /*!< R/W 0 Enable USB enter LPM , 1: Enable, 0: Disable */
/* REG_SYS_CFG_8710B 0xF0 */
#define BIT_USB_DOGGLE_MODE ((u32)(0x00000001 << 1)) /*!< 1: enable usb host access wifi mac, this bit should set by host driver */
#define BIT_MCLK_VLD ((u32)(0x00000001 << 0)) /*!< 1: MAC clock ready flag */
#define REG_WL_PMC_CTRL 0x0020
#define REG_WL_RF_PSS 0x005C /*!< select RF power source: LDO:3.3V, PC: 1.2V*/
#define REG_SYS_CFG_8710B 0x00F0
#define REG_USB_INDIRECT_CTRL 0x006C
#define REG_USB_SIE_IMR 0x0078
#define REG_USB_SIE_INT 0x007c
#define REG_WL_PMC_ISR_8711B 0x0084
#define REG_USB_PWR_OPT 0x0088
#define REG_USB_HOST_RW_DATA 0x009C
#define REG_USB_HOST_RW_ADDR 0x00F8
#endif //__INC_RTL8711B_WL_ON_H

View file

@ -0,0 +1,344 @@
/**
******************************************************************************
* @file rtl8711b_adc.h
* @author
* @version V1.0.0
* @date 2016-05-17
* @brief This file contains all the functions prototypes for the ADC firmware
* library.
******************************************************************************
* @attention
*
* This module is a confidential and proprietary property of RealTek and
* possession or use of this module requires written permission of RealTek.
*
* Copyright(c) 2016, Realtek Semiconductor Corporation. All rights reserved.
******************************************************************************
*/
#ifndef _RTL8710B_ADC_H_
#define _RTL8710B_ADC_H_
/** @addtogroup AmebaZ_Periph_Driver
* @{
*/
/** @defgroup ADC
* @brief ADC driver modules
* @{
*/
/** @addtogroup ADC
* @verbatim
*****************************************************************************************
* Introduction
*****************************************************************************************
* ADC:
* - Base Address: ADC
* - Channel: 4
* - 0 internal ADC channel (reserved for internal thermal meter output)
* - 1&3 (GPIOA19&GPIOA20) external ADC channel (normal ADC, power < 3.3V)
* - 2 (VBAT) external ADC VBAT channel (batery voltage measurement, power < 5V, 1/4 voltage will be get)
* - Sample rate: max frequency up to 1MHz per channel, configurable
* - Resolution: 12 bit, but when there is only set of output(audio mode), resolution is 16bit
* - Analog signal sampling: support 0 ~ 3.3V
* - IRQ: ADC_IRQ
* - Support one shot mode for power save
* - GDMA source handshake interface: 12
*
*****************************************************************************************
* One shot mode
*****************************************************************************************
* Timer trigger one shot sampling
* ADC does one single conversion
*
*****************************************************************************************
* How to use ADC in interrupt mode
*****************************************************************************************
* To use ADC in interrupt mode, the following steps are mandatory:
*
* 1. Enable the ADC interface clock:
* RCC_PeriphClockCmd(APBPeriph_ADC, APBPeriph_ADC_CLOCK, ENABLE);
*
* 2. Fill the ADC_InitStruct with the desired parameters.
*
* 3. Init Hardware use step2 parameters.
* ADC_Init(ADC_InitTypeDef* ADC_InitStruct)
*
* 4. Clear ADC interrupt:
* ADC_INTClear()
*
* 5. To configure interrupts:
* ADC_INTConfig(IntrMSK, ENABLE)
*
* 6. Activate the ADC:
* ADC_Cmd(ENABLE).
*
* @note1 If use ADC compare mode, call ADC_SetComp(ChanIdx, ADCCompTD, ADCCompCtrl) to configure
*
* @note2 If power save needed, call ADC_SetOneShot(ENABLE, Period, InterruptThresh) to enable ADC one
* shot mode(2*Period ms interval will set)
*
*****************************************************************************************
* How to use ADC in DMA mode
*****************************************************************************************
* To use ADC in DMA mode, the following steps are mandatory:
*
* 1. Enable the ADC interface clock:
* RCC_PeriphClockCmd(APBPeriph_ADC, APBPeriph_ADC_CLOCK, ENABLE);
*
* 2. Fill the ADC_InitStruct with the desired parameters.
*
* 3. Init Hardware use step2 parameters.
* ADC_Init(ADC_InitTypeDef* ADC_InitStruct)
*
* 4. Disable ADC interrupts:
* ADC_INTConfig(IntrMSK,DISABLE)
*
* 5. Clear ADC interrupt:
* ADC_INTClear()
*
* 6. GDMA related configurations(source address/destination address/block size etc.).
*
* 7. Configure GDMA with the corresponding configuration.
* GDMA_Init()
*
* 8. Enable the GDMA:
* GDMA_Cmd().
*
* 9. Activate the ADC peripheral:
* ADC_Cmd(ENABLE).
*
*****************************************************************************************
* @endverbatim
*/
/* Exported types ------------------------------------------------------------*/
/** @defgroup ADC_Exported_Types ADC Exported Types
* @{
*/
/**
* @brief ADC Init structure definition
*/
typedef struct {
u32 ADC_CompOnly; /*!< Specifies ADC compare mode only enable (without FIFO enable)
This parameter can be set to ENABLE or DISABLE */
u32 ADC_OneShotEn; /*!< Specifies ADC one-shot mode enable
This parameter can be set to ENABLE or DISABLE */
u32 ADC_OverWREn; /*!< Specifies ADC overwrite mode enable
This parameter can be set to ENABLE or DISABLE */
u32 ADC_Endian; /*!< Specifies ADC endian selection, but actually it's for 32-bit ADC data swap control
This parameter can be set to 1'b0: no swap, 'b1: swap the upper 16-bit and the lower 16-bit */
u32 ADC_BurstSz; /*!< Specifies ADC DMA operation threshold
This parameter must range from 1 to 32 dword.
@note This parameter had better not set too big */
u32 ADC_OneShotTD; /*!< Specifies ADC one shot mode threshold
This parameter must range from 1 to 32 dword.
@note This parameter had better not set too big */
u32 ADC_SampleClk; /*!< ADC Sample clock, This parameter can be a value of @ref ADC_SampleClk_Definitions */
u32 ADC_DbgSel; /*!< Specifies ADC select debug mode, can be @ref ADC_DBG_Select, user dont set this parameter. */
} ADC_InitTypeDef;
/**
* @}
*/
/* Exported constants --------------------------------------------------------*/
/** @defgroup ADC_Exported_Constants ADC Exported Constants
* @{
*/
/** @defgroup ADC_Chn_Selection
* @{
*/
#define ADC0_SEL ((u8)0x00)
#define ADC1_SEL ((u8)0x01)
#define ADC2_SEL ((u8)0x02)
#define ADC3_SEL ((u8)0x03)
#define IS_ADC_CHN_SEL(SEL) (((SEL) == ADC0_SEL) || \
((SEL) == ADC1_SEL) || \
((SEL) == ADC2_SEL) || \
((SEL) == ADC3_SEL))
/**
* @}
*/
/** @defgroup ADC_SampleClk_Definitions
* @{
*/
#define ADC_SAMPLE_CLK_2_1P5625M ((u32)0x00000000)
#define ADC_SAMPLE_CLK_2_3P1250M ((u32)0x00000001)
#define ADC_SAMPLE_CLK_2_6P2500M ((u32)0x00000002)
#define ADC_SAMPLE_CLK_2_12P500M ((u32)0x00000003)
#define IS_ADC_SAMPLE_CLK(CLK) (((CLK) == ADC_SAMPLE_CLK_2_1P5625M) || \
((CLK) == ADC_SAMPLE_CLK_2_3P1250M) || \
((CLK) == ADC_SAMPLE_CLK_2_6P2500M) || \
((CLK) == ADC_SAMPLE_CLK_2_12P500M))
/**
* @}
*/
/** @defgroup ADC_Data_Endian
* @{
*/
#define ADC_DATA_ENDIAN_LITTLE ((u32)0x00000000)
#define ADC_DATA_ENDIAN_BIG ((u32)0x00000001)
#define IS_ADC_DATA_ENDIAN(ENDIAN) (((ENDIAN) == ADC_DATA_ENDIAN_LITTLE) || \
((ENDIAN) == ADC_DATA_ENDIAN_BIG))
/**
* @}
*/
/** @defgroup ADC_Compare_Set
* @{
*/
#define ADC_COMP_SMALLER_THAN ((u32)0x00000000)
#define ADC_COMP_GREATER_THAN ((u32)0x00000001)
/**
* @}
*/
/** @defgroup ADC_DBG_Select
* @{
*/
#define ADC_DBG_ADC_POWER ((u32)0x00000000)
#define ADC_DBG_ADC_ONESHOT ((u32)0x00000001)
#define ADC_DBG_ADC_FIFO ((u32)0x00000002)
#define ADC_DBG_ADC_DATA ((u32)0x00000003)
#define ADC_DBG_ADC_CTRL ((u32)0x00000004)
#define ADC_DBG_ADC_RST ((u32)0x00000005)
/**
* @}
*/
/**
* @}
*/
/** @defgroup ADC_Exported_Functions ADC Exported Functions
* @{
*/
_LONG_CALL_ void ADC_Init(ADC_InitTypeDef* ADC_InitStruct);
_LONG_CALL_ void ADC_InitStruct(ADC_InitTypeDef *ADC_InitStruct);
_LONG_CALL_ u32 ADC_Read(void);
_LONG_CALL_ u32 ADC_GetISR(void);
_LONG_CALL_ void ADC_Cmd(u32 ADCEn);
_LONG_CALL_ void ADC_INTConfig(u32 IntrMSK, u32 NewState);
_LONG_CALL_ void ADC_INTClear(void);
_LONG_CALL_ void ADC_INTClearPendingBits(u32 Mask);
_LONG_CALL_ void ADC_SetAnalog(ADC_InitTypeDef* ADC_InitStruct);
_LONG_CALL_ void ADC_SetComp(u8 ChanIdx, u16 ADCCompTD, u16 ADCCompCtrl);
_LONG_CALL_ void ADC_SetOneShot(u32 NewState, u32 PeriodMs, u32 InterruptThresh);
_LONG_CALL_ void ADC_ReceiveBuf(u32 *pBuf);
_LONG_CALL_ void ADC_SetAudio(u32 NewState);
_LONG_CALL_ u32 ADC_RXGDMA_Init(GDMA_InitTypeDef *GDMA_InitStruct, void *CallbackData, IRQ_FUN CallbackFunc, u8* pDataBuf, u32 DataLen);
/**
* @}
*/
/* Registers Definitions --------------------------------------------------------*/
/**************************************************************************//**
* @defgroup ADC_Register_Definitions ADC Register Definitions
* @{
*****************************************************************************/
/**************************************************************************//**
* @defgroup ADC_CTL
* @{
*****************************************************************************/
#define BIT_ADC_ONESHOT ((u32)0x00000001 << 1)
/** @} */
/**************************************************************************//**
* @defgroup ADC_INTR_EN
* @{
*****************************************************************************/
#define BIT_ADC_AWAKE_CPU_EN ((u32)0x00000001 << 7)
#define BIT_ADC_FIFO_RD_ERR_EN ((u32)0x00000001 << 6)
#define BIT_ADC_FIFO_RD_REQ_EN ((u32)0x00000001 << 5)
#define BIT_ADC_FIFO_FULL_EN ((u32)0x00000001 << 4)
#define BIT_ADC_COMP_3_EN ((u32)0x00000001 << 3)
#define BIT_ADC_COMP_2_EN ((u32)0x00000001 << 2)
#define BIT_ADC_COMP_1_EN ((u32)0x00000001 << 1)
#define BIT_ADC_COMP_0_EN ((u32)0x00000001 << 0)
/** @} */
/**************************************************************************//**
* @defgroup ADC_INTR_STATUS
* @{
*****************************************************************************/
#define BIT_ADC_FIFO_THRESHOLD ((u32)0x00000001 << 7)
#define BIT_ADC_FIFO_RD_ERR ((u32)0x00000001 << 6)
#define BIT_ADC_FIFO_RD_REQ ((u32)0x00000001 << 5)
#define BIT_ADC_FIFO_FULL ((u32)0x00000001 << 4)
#define BIT_ADC_COMP_3 ((u32)0x00000001 << 3)
#define BIT_ADC_COMP_2 ((u32)0x00000001 << 2)
#define BIT_ADC_COMP_1 ((u32)0x00000001 << 1)
#define BIT_ADC_COMP_0 ((u32)0x00000001 << 0)
/** @} */
/**************************************************************************//**
* @defgroup ADC_POWER
* @{
*****************************************************************************/
#define BIT_ADC_FIFO_ON_ST ((u32)0x00000001 << 11)
#define BIT_ADC_ISO_MANUAL ((u32)0x00000001 << 3)
#define BIT_ADC_PWR33_MANUAL ((u32)0x00000001 << 2)
#define BIT_ADC_PWR12_MANUAL ((u32)0x00000001 << 1)
#define BIT_ADC_PWR_AUTO ((u32)0x00000001 << 0)
/** @} */
/**************************************************************************//**
* @defgroup ADC_ANAPAR_AD0
* @{
*****************************************************************************/
#define BIT_ADC_SAMPLE_CLK ((u32)0x00000003 << 14)
#define BIT_ADC_DEM_EN ((u32)0x00000001 << 3)
#define BIT_ADC_CHOP_EN ((u32)0x00000001 << 2)
#define BIT_ADC_AUDIO_EN ((u32)0x00000001 << 1)
#define BIT_ADC_EN_MANUAL ((u32)0x00000001 << 0)
/** @} */
/**************************************************************************//**
* @defgroup ADC_ANAPAR_AD1
* @{
*****************************************************************************/
#define BIT_ADC_DECIMATION_FILTER_ORDER ((u32)0x00000001 << 12) /*!< decimation filter order, 0: order3, 1: order4 */
#define BIT_ADC_DOWN_SAMPLE_RATE ((u32)0x00000007 << 18) /*!< ADC Factor, down sample rate, 000: 25M/2^7, 001: 25M/2^8 */
#define BIT_ADC_EXT_VREF_EN ((u32)0x00000001 << 2)
#define BIT_ADC_FEEDBK_CAPACITY_VAL ((u32)0x00000001 << 1)
#define BIT_ADC_DIGITAL_RST_BAR ((u32)0x00000001 << 0)
/** @} */
/** @} */
/**
* @}
*/
/**
* @}
*/
/* Other Definitions --------------------------------------------------------*/
extern u32 ADC_AnaparAd[6];
#endif /* _RTL8710B_ADC_H_ */
/******************* (C) COPYRIGHT 2016 Realtek Semiconductor *****END OF FILE****/

View file

@ -0,0 +1,68 @@
/**
******************************************************************************
* @file rtl8711b_cache.h
* @author
* @version V1.0.0
* @date 2016-05-17
* @brief This file contains all the functions prototypes for the flash cache firmware
* library.
******************************************************************************
* @attention
*
* This module is a confidential and proprietary property of RealTek and
* possession or use of this module requires written permission of RealTek.
*
* Copyright(c) 2016, Realtek Semiconductor Corporation. All rights reserved.
******************************************************************************
*/
#ifndef _RTL8710B_CACHE_H_
#define _RTL8710B_CACHE_H_
/** @addtogroup AmebaZ_Platform
* @{
*/
/** @defgroup CACHE
* @brief CACHE modules
* @{
*/
/** @addtogroup CACHE
* @verbatim
*****************************************************************************************
* Introduction
*****************************************************************************************
* -just support read cache.
* -32K bytes.
* -used for flash read and XIP.
*
*****************************************************************************************
* how to use
*****************************************************************************************
* Cache_Enable: enable/disable cache
* Cache_Flush: flush cache, you should Cache_Flush after flash write or flash erase
*****************************************************************************************
* @endverbatim
*/
/* Exported functions --------------------------------------------------------*/
/** @defgroup CACHE_Exported_Functions FLash Cache Exported Functions
* @{
*/
_LONG_CALL_ void Cache_Enable(u32 Enable);
_LONG_CALL_ void Cache_Flush(void);
_LONG_CALL_ void Cache_Debug(u32 PrintLog);
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
#endif //_RTL8710B_CACHE_H_
/******************* (C) COPYRIGHT 2016 Realtek Semiconductor *****END OF FILE****/

View file

@ -0,0 +1,507 @@
/*
* Routines to access hardware
*
* Copyright (c) 2013 Realtek Semiconductor Corp.
*
* This module is a confidential and proprietary property of RealTek and
* possession or use of this module requires written permission of RealTek.
*/
#ifndef __HAL_CRYPTO_RAM_H__
#define __HAL_CRYPTO_RAM_H__
// IPSecEngine
#define CRYPTO_MAX_DESP 8
#define CRYPTO_MAX_MSG_LENGTH 32000
#define CRYPTO_MD5_DIGEST_LENGTH 16
#define CRYPTO_SHA1_DIGEST_LENGTH 20
#define CRYPTO_SHA2_DIGEST_LENGTH 32
#define CRYPTO_MAX_DIGEST_LENGTH 32 // SHA256 Digest length : 32
#define CRYPTO_MAX_KEY_LENGTH 32 // MAX is AES-256 : 32 byte, 3DES : 24 byte
#define CRYPTO_PADSIZE 64
#define CRYPTO_AUTH_PADDING 64
typedef enum _SHA2_TYPE_ {
SHA2_NONE = 0,
SHA2_224 = 224/8,
SHA2_256 = 256/8,
SHA2_384 = 384/8,
SHA2_512 = 512/8
} SHA2_TYPE;
/**************************************************************************
* Definition for Parameters
**************************************************************************/
#define HAL_CRYPTO_WRITE32(addr, value32) HAL_WRITE32(CRYPTO_REG_BASE, (addr), (value32))
#define HAL_CRYPTO_WRITE16(addr, value16) HAL_WRITE16(CRYPTO_REG_BASE, (addr), (value16))
#define HAL_CRYPTO_WRITE8(addr, value8) HAL_WRITE8(CRYPTO_REG_BASE, (addr), (value8))
#define HAL_CRYPTO_READ32(addr) HAL_READ32(CRYPTO_REG_BASE, (addr))
#define HAL_CRYPTO_READ16(addr) HAL_READ16(CRYPTO_REG_BASE, (addr))
#define HAL_CRYPTO_READ8(addr) HAL_READ8(CRYPTO_REG_BASE, (addr))
#define REG_IPSSDAR (0x00) // IPSec Source Descriptor Starting Address Register
#define REG_IPSDDAR (0x04) // IPSec Destination Descriptor Starting Address Register
#define REG_IPSCSR (0x08) // IPSec Command/Status Register
#define REG_IPSCSDD (0x10) // IPSec CheckSum of Decrypted Data
#define REG_IPSCTR (0x0C) // IPSec Control Register
/**************************************************************************
* Type definition for AES KEY
**************************************************************************/
//
// For AES key calculation
//
#define CIPHER_AES_MAXNR 14
#define CIPHER_AES_BLOCK_SIZE 16
enum _CIPHER_AES_KEYlEN
{
_CIPHER_AES_KEYLEN_NONE = 0,
_CIPHER_AES_KEYLEN_128BIT = 1,
_CIPHER_AES_KEYLEN_192BIT = 2,
_CIPHER_AES_KEYLEN_256BIT = 3,
};
typedef struct {
u32 rd_key[4 *(CIPHER_AES_MAXNR + 1)];
int rounds;
} RTL_SW_AES_KEY;
/**************************************************************************
* Data Structure for Descriptor
**************************************************************************/
#define _LITTLE_ENDIAN
#if (SYSTEM_ENDIAN==PLATFORM_LITTLE_ENDIAN)
typedef struct __rtl_crypto_source_s
{
// offset 0 :
u32 sbl:15;
// u32 resv2:1;
u32 isSHA2:1;
u32 md5:1;
u32 hmac:1;
//u32 auth_type:3; // hmac:1 + md5:2
u32 ctr:1;
u32 cbc:1;
u32 trides:1;
u32 aeskl:2;
u32 kam:3;
u32 ms:2;
u32 resv1:1;
u32 fs:1;
u32 eor:1;
u32 own:1;
// offset 1 :
u32 enl:15;
u32 resv4:1;
u32 a2eo:8;
u32 resv3:5;
u32 sha2:3;
// offset 2:
u32 resv6:16;
u32 apl:8;
u32 resv5:8;
// offset 3:
u32 sdbp;
}RTL_CRYPTO_SOURCE_T;
typedef struct __rtl_crypto_dest_s
{
u32 dbl:15;
u32 resv1:15;
u32 eor:1;
u32 own:1;
u32 ddbp;
u32 resv2;
u32 icv[5+4]; // also set with IPSCTR's DDLEN
} RTL_CRYPTO_DEST_T;
#else // SYSTEM_ENDIAN -> BIG_ENDIAN
typedef struct __rtl_crypto_source_s
{
u32 own:1;
u32 eor:1;
u32 fs:1;
u32 resv1:1;
u32 ms:2;
u32 kam:3;
u32 aeskl:2;
u32 trides:1;
u32 cbc:1;
u32 ctr:1;
u32 auth_type:3; // hmac:1 + md5:2
// u32 resv2:1;
u32 sbl:15;
u32 resv3:8;
u32 a2eo:8;
u32 resv4:1;
u32 enl:15;
u32 resv5:8;
u32 apl:8;
u32 resv6:16;
u32 sdbp;
} RTL_CRYPTO_SOURCE_T;
typedef struct __rtl_crypto_dest_s
{
u32 own:1;
u32 eor:1;
u32 resv1:15;
u32 dbl:15;
u32 ddbp;
u32 resv2;
u32 icv[5]; // changint with DDLEN
} RTL_CRYPTO_DEST_T;
#endif // SYSTEM_ENDIAN
/**************************************************************************
* Data Structure for Cipher Adapter
**************************************************************************/
typedef struct _HAL_CRYPTO_ADAPTER_
{
u8 isInit; // 0: not init, 1: init
u8 dma_mode; // 2: 64 bytes;
u8 sawb_mode; // 0: disable sawb, 1:enable sawb
u8 desc_num; // total number of source/destination description
u8 mode_select;
u32 cipher_type;
u8 des;
u8 trides;
u8 aes;
u8 isDecrypt;
u32 auth_type;
u8 isHMAC;
u8 isMD5;
u8 isSHA1;
u8 isSHA2;
SHA2_TYPE sha2type;
u32 lenAuthKey;
const u8* pAuthKey;
u8 authKey[CRYPTO_MAX_DIGEST_LENGTH];
u32 digestlen;
// AES calculation
RTL_SW_AES_KEY aes_key;
u32 lenCipherKey;
const u8* pCipherKey;
u32 a2eo, enl, apl;
u8 decryptKey[CRYPTO_MAX_KEY_LENGTH];
u8 pad_to_align_1[16]; //pad to make g_IOPAD align 32
u8 g_IOPAD[CRYPTO_PADSIZE*2+32];
u8 *ipad;
u8 *opad;
u8 pad_to_align_2[24]; //pad to make g_authPadding align 32
u8 g_authPadding[CRYPTO_AUTH_PADDING*2+32];
// Source Descriptor
u8 idx_srcdesc;
RTL_CRYPTO_SOURCE_T *g_ipssdar;
RTL_CRYPTO_SOURCE_T g_src_buf[CRYPTO_MAX_DESP];
// Destination Descriptor
u8 idx_dstdesc;
RTL_CRYPTO_DEST_T *g_ipsddar;
RTL_CRYPTO_DEST_T g_dst_buf[CRYPTO_MAX_DESP];
u8 pad_to_align_3[16]; //pad to make _HAL_CRYPTO_ADAPTER_ size 1280
} HAL_CRYPTO_ADAPTER, *PHAL_CRYPTO_ADAPTER ;
/**************************************************************************
* Definition for value and type
**************************************************************************/
/* IPSec Command/Status Register */
#define IPS_SDUEIP (1<<15) /* Source Descriptor Unavailable Error Interrupt Pending */
#define IPS_SDLEIP (1<<14) /* Source Descriptor Length Error Interrupt Pending */
#define IPS_DDUEIP (1<<13) /* Destination Descriptor Unavailable Error Interrupt Pending */
#define IPS_DDOKIP (1<<12) /* Destination Descriptor OK Interrupt Pending */
#define IPS_DABFIP (1<<11) /* Data Address Buffer Interrupt Pending */
#define IPS_FIX_DMA_FAI (1<<3)
#define IPS_RDMA_IDLE (1<<2)
#define IPS_POLL (1<<1) /* Descriptor Polling. Set 1 to kick crypto engine to fetch source descriptor. */
#define IPS_SRST (1<<0) /* Software reset, write 1 to reset */
/* IPSec Control Register */
#define IPS_CHKSUM_EN (1<<28) /* Enable check sum calculation of decryption data*/
//#define IPS_DDLEN_72 (7<<24) /* Destination Descriptor Length : address offset to 72 : for SHA-512 */
#define IPS_DDLEN_20 (3<<24) /* Destination Descriptor Length : Length is 20*DW : for SHA-1/MD5 */
#define IPS_DDLEN_16 (2<<24) /* Destination Descriptor Length : Length is 16*DW : for SHA-1/MD5 */
#define IPS_DDLEN_12 (1<<24) /* Destination Descriptor Length : Length is 12*DW : for SHA-1/MD5 */
#define IPS_DDLEN_8 (0<<24) /* Destination Descriptor Length : Length is 8*DW : for SHA-1/MD5 */
#define IPS_SDUEIE (1<<15) /* Source Descriptor Unavailable Error Interrupt Enable */
#define IPS_SDLEIE (1<<14) /* Source Descriptor Length Error Interrupt Enable */
#define IPS_DDUEIE (1<<13) /* Destination Descriptor Unavailable Error Interrupt Enable */
#define IPS_DDOKIE (1<<12) /* Destination Descriptor OK Interrupt Enable */
#define IPS_DABFIE (1<<11) /* Data Address Buffer Interrupt Enable */
#define IPS_LXBIG (1<<9) /* Lx bus data endian*/
#define IPS_LBKM (1<<8) /* Loopback mode enable */
#define IPS_SAWB (1<<7) /* Source Address Write Back */
#define IPS_CKE (1<<6) /* Clock enable */
#define IPS_DMBS_MASK (0x7<<3) /* Mask for Destination DMA Maximum Burst Size */
#define IPS_DMBS_16 (0x0<<3) /* 16 Bytes */
#define IPS_DMBS_32 (0x1<<3) /* 32 Bytes */
#define IPS_DMBS_64 (0x2<<3) /* 64 Bytes */
#define IPS_DMBS_128 (0x3<<3) /* 128 Bytes */
#define IPS_SMBS_MASK (0x7<<0) /* Mask for SourceDMA Maximum Burst Size */
#define IPS_SMBS_16 (0x0<<0) /* 16 Bytes */
#define IPS_SMBS_32 (0x1<<0) /* 32 Bytes */
#define IPS_SMBS_64 (0x2<<0) /* 64 Bytes */
#define IPS_SMBS_128 (0x3<<0) /* 128 Bytes */
// MS(0:27-26) Mode Select
#define _MS_TYPE_CRYPT (0)
#define _MS_TYPE_AUTH (1)
#define _MS_TYPE_AUTH_THEN_CRYPT (2)
#define _MS_TYPE_CRYPT_THEN_AUTH (3)
// modeCrypto
#define _MD_NOCRYPTO ((u32)-1)
#define _MD_CBC (u32)(0)
#define _MD_ECB (u32)(2)
#define _MD_CTR (u32)(3)
#define _MASK_CRYPTOECRYPT (u32)(1<<7)
#define _MASK_CRYPTOTHENAUTH (u32)(1<<6)
#define _MASK_CRYPTOAES (u32)(1<<5)
#define _MASK_CRYPTO3DESDES (u32)(1<<4)
#define _MASK_CBCECBCTR ((u32)((1<<0)|(1<<1)))
//#define _MASK_ECBCBC (1<<1)
// modeAuth
#define _MD_NOAUTH ((u32)-1)
#define _MASK_AUTHSHA2 (1<<0)
#define _MASK_AUTHSHA1MD5 (1<<1)
#define _MASK_AUTHHMAC (1<<2)
#define _MASK_AUTH_IOPAD_READY (1<<3)
#define MAX_PKTLEN (1<<14)
//Bit 0: 0:DES 1:3DES
//Bit 1: 0:CBC 1:ECB
//Bit 2: 0:Decrypt 1:Encrypt
#define DECRYPT_CBC_DES 0x00
#define DECRYPT_CBC_3DES 0x01
#define DECRYPT_ECB_DES 0x02
#define DECRYPT_ECB_3DES 0x03
#define ENCRYPT_CBC_DES 0x04
#define ENCRYPT_CBC_3DES 0x05
#define ENCRYPT_ECB_DES 0x06
#define ENCRYPT_ECB_3DES 0x07
#define RTL8651_CRYPTO_NON_BLOCKING 0x08
#define RTL8651_CRYPTO_GENERIC_DMA 0x10
#define DECRYPT_CBC_AES 0x20
#define DECRYPT_ECB_AES 0x22
#define DECRYPT_CTR_AES 0x23
#define ENCRYPT_CBC_AES 0x24
#define ENCRYPT_ECB_AES 0x26
#define ENCRYPT_CTR_AES 0x27
//Bit 0: 0:MD5 1:SHA1
//Bit 1: 0:Hash 1:HMAC
#define HASH_MD5 0x00
#define HASH_SHA1 0x01
#define HMAC_MD5 0x02
#define HMAC_SHA1 0x03
#define REG32(reg) (*((volatile u32 *)(reg)))
#define READ_MEM32(reg) REG32(reg)
#define WRITE_MEM32(reg,val) REG32(reg)=(val)
// address macro
#define KUSEG 0x00000000
#define KSEG0 0x80000000
#define KSEG1 0xa0000000
#define KSEG2 0xc0000000
#define KSEG3 0xe0000000
#define CPHYSADDR(a) ((int)(a) & 0x1fffffff)
#define CKSEG0ADDR(a) (CPHYSADDR(a) | KSEG0)
#define CKSEG1ADDR(a) (CPHYSADDR(a) | KSEG1)
#define CKSEG2ADDR(a) (CPHYSADDR(a) | KSEG2)
#define CKSEG3ADDR(a) (CPHYSADDR(a) | KSEG3)
#define PHYSICAL_ADDRESS(x) (x)//CPHYSADDR(x)
#define UNCACHED_ADDRESS(x) (x)//CKSEG1ADDR(x)
#define CACHED_ADDRESS(x) (x)//CKSEG0ADDR(x)
enum _MODE_SELECT
{
_MS_CRYPTO = 0,
_MS_AUTH = 1,
_MS_AUTH_THEN_DECRYPT = 2,
_MS_ENCRYPT_THEN_AUTH = 3,
};
//
// AUTH Type
//
#define AUTH_TYPE_NO_AUTH ((u32)-1)
#define AUTH_TYPE_MASK_FUNC 0x3 // bit 0, bit 1
#define AUTH_TYPE_MD5 0x2
#define AUTH_TYPE_SHA1 0x0
#define AUTH_TYPE_SHA2 0x1
#define AUTH_TYPE_MASK_HMAC 0x4 // bit 2
#define AUTH_TYPE_HMAC_MD5 (AUTH_TYPE_MD5 | AUTH_TYPE_MASK_HMAC)
#define AUTH_TYPE_HMAC_SHA1 (AUTH_TYPE_SHA1 | AUTH_TYPE_MASK_HMAC)
#define AUTH_TYPE_HMAC_SHA2 (AUTH_TYPE_SHA2 | AUTH_TYPE_MASK_HMAC)
#define AUTH_TYPE_MASK_SHA2 0x30 // bit 3,4
#define AUTH_TYPE_SHA2_224 0x10
#define AUTH_TYPE_SHA2_256 0x20
//
// Cipher Type
//
#define CIPHER_TYPE_NO_CIPHER ((u32)-1)
#define CIPHER_TYPE_DES_CBC 0x0
#define CIPHER_TYPE_DES_ECB 0x2
#define CIPHER_TYPE_3DES_CBC 0x10
#define CIPHER_TYPE_3DES_ECB 0x12
#define CIPHER_TYPE_AES_CBC 0x20
#define CIPHER_TYPE_AES_ECB 0x22
#define CIPHER_TYPE_AES_CTR 0x23
#define CIPHER_TYPE_MODE_ENCRYPT 0x80
#define CIPHER_TYPE_MASK_FUNC 0x30 // 0x00 : DES, 0x10: 3DES, 0x20: AES
#define CIPHER_TYPE_FUNC_DES 0x00
#define CIPHER_TYPE_FUNC_3DES 0x10
#define CIPHER_TYPE_FUNC_AES 0x20
#define CIPHER_TYPE_MASK_BLOCK 0x7 // 0x0 : CBC, 0x2: ECB, 0x3: CTR
#define CIPHER_TYPE_BLOCK_CBC 0x0
#define CIPHER_TYPE_BLOCK_ECB 0x2
#define CIPHER_TYPE_BLOCK_CTR 0x3
//
// Data Structure
//
/**************************************************************************
* Data Structure for IPSec Engine
**************************************************************************/
/*
* ipsec engine supports scatter list: your data can be stored in several segments those are not continuous.
* Each scatter points to one segment of data.
*/
typedef struct rtl_ipsecScatter_s {
u32 len;
void* ptr;
} rtl_ipsecScatter_t;
// static inline function / macros
static inline
u32 __rtl_cpu_to_be32(u32 val)
{
asm volatile(
"rev %0, %0"
: "=r" (val)
: "0" (val));
return val;
}
//
// ROM global variables
extern const u32 __AES_Te4[];
extern const u32 __AES_rcon[];
//
// ROM Function mapping
//
#define __rtl_cryptoEngine_init CRYPTO_Init
#define __rtl_cryptoEngine_exit CRYPTO_DeInit
#define __rtl_cryptoEngine_reset CRYPTO_Reset
#define __rtl_cryptoEngine_set_security_mode CRYPTO_SetSecurityMode
#define __rtl_cryptoEngine CRYPTO_Process
#define __rtl_crypto_cipher_init CRYPTO_CipherInit
#define __rtl_crypto_cipher_encrypt CRYPTO_CipherEncrypt
#define __rtl_crypto_cipher_decrypt CRYPTO_CipherDecrypt
//
// ROM functions
//
extern _LONG_CALL_ void CRYPTO_AlignToBe32(u32 *pData, int bytes4_num );
extern _LONG_CALL_ void CRYPTO_MemDump(const u8 *start, u32 size, char * strHeader);
extern _LONG_CALL_ int CRYPTO_Init(HAL_CRYPTO_ADAPTER *pIE);
extern _LONG_CALL_ int CRYPTO_DeInit(HAL_CRYPTO_ADAPTER *pIE);
extern _LONG_CALL_ int CRYPTO_Reset(HAL_CRYPTO_ADAPTER *pIE);
extern _LONG_CALL_ int CRYPTO_SetSecurityMode(HAL_CRYPTO_ADAPTER *pIE,
IN const u32 mode_select, IN const u32 cipher_type, IN const u32 auth_type,
IN const void* pCipherKey, IN const u32 lenCipherKey,
IN const void* pAuthKey, IN const u32 lenAuthKey);
extern _LONG_CALL_ int CRYPTO_Process(HAL_CRYPTO_ADAPTER *pIE,
IN const u8 *message, IN const u32 msglen,
IN const u8 *pIv, IN const u32 ivlen,
IN const u32 a2eo, OUT void *pResult);
extern _LONG_CALL_ int CRYPTO_CipherInit(HAL_CRYPTO_ADAPTER *pIE,
IN const u32 cipher_type,
IN const u8* key, IN const u32 keylen);
extern _LONG_CALL_ int CRYPTO_CipherEncrypt(HAL_CRYPTO_ADAPTER *pIE,
IN const u32 cipher_type,
IN const u8* message, IN const u32 msglen,
IN const u8* piv, IN const u32 ivlen,
OUT u8* pResult);
extern _LONG_CALL_ int CRYPTO_CipherDecrypt(HAL_CRYPTO_ADAPTER *pIE,
IN const u32 cipher_type, IN const u8* message, IN const u32 msglen,
IN const u8* piv, IN const u32 ivlen,
OUT u8* pResult );
extern _LONG_CALL_ void CRYPTO_SetCheckSumEn(u32 checksum_en);
extern _LONG_CALL_ void CRYPTO_GetCheckSumData(u32* pChecksum);
#endif // __HAL_CRYPTO_RAM_H

View file

@ -0,0 +1,105 @@
/**
******************************************************************************
* @file rtl8711b_diag.h
* @author
* @version V1.0.0
* @date 2016-05-17
* @brief This file contains all the functions prototypes for UART LOG firmware
* library.
******************************************************************************
* @attention
*
* This module is a confidential and proprietary property of RealTek and
* possession or use of this module requires written permission of RealTek.
*
* Copyright(c) 2015, Realtek Semiconductor Corporation. All rights reserved.
******************************************************************************
*/
#ifndef _8710B_DIAG_H_
#define _8710B_DIAG_H_
/** @addtogroup AmebaZ_Platform
* @{
*/
/** @defgroup DIAG
* @brief DIAG driver modules
* @{
*/
/** @addtogroup DIAG
* @verbatim
*****************************************************************************************
* Introduction
*****************************************************************************************
* -Control API for LOGUART.
* -These API is used by system, user should not use these API if not needed.
* -LOGUART is UART2.
*
*****************************************************************************************
* pinmux
*****************************************************************************************
* -S0: GPIOA_16/17: QFN48, QFN68, QFN48-MCM.
* -S1: GPIOA_29/30: QFN32.
* -EFUSE 0x19[6]: 0: S1 PA29 & PA30, 1: S0 PA16 & PA17.
*
*****************************************************************************************
* @endverbatim
*/
/* Exported constants --------------------------------------------------------*/
/** @defgroup DIAG_Exported_Constants DIAG Exported Constants
* @{
*/
/**
* @}
*/
/* Exported functions --------------------------------------------------------*/
/** @defgroup DIAG_Exported_Functions DIAG Exported Functions
* @{
*/
_LONG_CALL_ void DIAG_UartInit(BOOL InitConsol);
_LONG_CALL_ void UartLogIrqHandle(void * Data);
_LONG_CALL_ void DIAG_UartReInit(IRQ_FUN IrqFun);
_LONG_CALL_ void LOGUART_PutChar(u8 c);
_LONG_CALL_ u8 LOGUART_GetChar(BOOL PullMode);
_LONG_CALL_ u32 LOGUART_GetIMR(void);
_LONG_CALL_ void LOGUART_SetIMR (u32 SetValue);
_LONG_CALL_ void LOGUART_WaitBusy(void);
#define DiagPutChar LOGUART_PutChar
#define DiagGetChar LOGUART_GetChar
#define DiagGetIsrEnReg LOGUART_GetIMR
#define DiagSetIsrEnReg LOGUART_SetIMR
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/* Other definations --------------------------------------------------------*/
typedef struct _COMMAND_TABLE_ {
const u8* cmd;
u16 ArgvCnt;
u32 (*func)(u16 argc, u8* argv[]);
const u8* msg;
}COMMAND_TABLE, *PCOMMAND_TABLE;
typedef u32 (*monitor_cmd_handler)(u16 argc, u8* argv[]);
extern COMMAND_TABLE UartLogRomCmdTable[];
#endif //_8710B_DIAG_H_
/******************* (C) COPYRIGHT 2016 Realtek Semiconductor *****END OF FILE****/

View file

@ -0,0 +1,258 @@
/**
******************************************************************************
* @file rtl8711b_efuse.h
* @author
* @version V1.0.0
* @date 2016-05-17
* @brief This file contains all the functions prototypes for the EFUSE firmware
* library.
******************************************************************************
* @attention
*
* This module is a confidential and proprietary property of RealTek and
* possession or use of this module requires written permission of RealTek.
*
* Copyright(c) 2015, Realtek Semiconductor Corporation. All rights reserved.
******************************************************************************
*/
#ifndef _8710B_EFUSE_H_
#define _8710B_EFUSE_H_
/** @addtogroup AmebaZ_Platform
* @{
*/
/** @defgroup EFUSE
* @brief EFUSE driver modules
* @{
*/
/** @addtogroup EFUSE
* @verbatim
*****************************************************************************************
* logical map (512B)
*****************************************************************************************
*
* 0x00~0x1F 32bytes system autoload
* 0x20~0xCF WIFI calibration data
* 0xD0~0x11F HCI CIS
* 0x130~0x13F SW/RF Reserved
* 0x160~0x17F 32bytes USER1
* 0x180~0x19F 32bytes USER2
* 0x1A0~0x1Bf 32bytes USER3
* 0x1C0~0x1Df USB HCI
*
*****************************************************************************************
* physical map (256B)
*****************************************************************************************
*
* 0x00~0x7E 127bytes for logical efuse, user can read
* 0x80~0x9F 32bytes for user OTP, user can read
* 0xA0~0xAF 16bytes OTF KEY, can not read by user
* 0xB0~0xBF 16bytes RDP KEY, can not read by user
* 0xC0 1byte RDP EN, can not read by user
* 0xC1~0xD2 18bytes for Security section
* 0xD3 1byte JTAG ON/OFF
* 0xD4~0xEF 29bytes RF rsvd, user can read
* 0xF0~0xFF 16bytes RTK rsvd, user can read
*
*****************************************************************************************
* USER Section (3 * 32B)
*****************************************************************************************
* can be changed after write
*
* USER1 32B = 4 sections * 8B
* USER2 32B = 4 sections * 8B
* USER3 32B = 4 sections * 8B
*
*****************************************************************************************
* OTP Section (32B)
*****************************************************************************************
*
* can not be changed after write
*
* OTP 32B
*
*****************************************************************************************
* FW protection
*****************************************************************************************
*
* can not be changed after write
*
* OTF KEY: 16B, can not read
* RDP KEY: 16B, can not read
* RDP EN: 1B, can not read
* JTAG OFF: 1B
*
*****************************************************************************************
* @endverbatim
*/
/* Exported constants --------------------------------------------------------*/
/** @defgroup EFUSE_Exported_Constants EFUSE Exported Constants
* @{
*/
/** @defgroup EFUSE_LOGICAL_definitions
* @{
*/
#define EFUSE_MAP_LEN_8711B 512 /*!< logical map len in byte */
#define EFUSE_MAX_SECTION_8711B (EFUSE_MAP_LEN_8711B >> 3) /*!< logical map len in section */
#define PGPKT_DATA_SIZE 8 /*!< logical map section len */
/* logical EFUSE User area */
#define USER_SECTION (0x160 >> 3)/*!< user area section index */
/**
* @}
*/
/** @defgroup EFUSE_PHYSICAL_definitions
* @{
*/
#define OTP_SECTION 0x80 /*!< EFUSE OTP area: physical address */
#define OTP_SECTION_LEN 0x20 /*!< EFUSE OTP area: 32 bytes */
/* physical EFUSE len */
#define EFUSE_REAL_CONTENT_LEN_8711B 256
#define AVAILABLE_EFUSE_ADDR(addr) (addr < EFUSE_REAL_CONTENT_LEN_8711B)
/* physical EFUSE read forbid */
#define READ_FORBID_SECTION_START 0xA0 /*!< EFUSE Security area: physical start */
#define READ_FORBID_SECTION_END 0xD4 /*!< EFUSE Security area: physical end */
/* physical EFUSE write forbid */
#define LOGICAL_MAP_SECTION_LEN 0x7E /*!< logical mapping efuse len in physical address */
#define EFUSE_OOB_PROTECT_BYTES (EFUSE_REAL_CONTENT_LEN_8711B - LOGICAL_MAP_SECTION_LEN) // Security + RF + MAC + OTP
/**
* @}
*/
/** @defgroup EFUSE_CHIPID_definitions
* @{
*/
#define CHIPID_8710BN 0xFF /* PACKAGE_QFN32 */
#define CHIPID_8710BU 0xFE /* PACKAGE_QFN48_MCM */
#define CHIPID_8711BN 0xFD /* PACKAGE_QFN48 */
#define CHIPID_8711BG 0xFC /* PACKAGE_QFN68 */
#define CHIPID_8710BN_L0 0xFB /* PACKAGE_QFN32 L0 */
/**
* @}
*/
/** @defgroup EFUSE_VOLTAGE_definitions
* @{
*/
#define L25EOUTVOLTAGE 7
/**
* @}
*/
/**
* @}
*/
/* Exported functions --------------------------------------------------------*/
/** @defgroup EFUSE_Exported_Functions EFUSE Exported Functions
* @{
*/
/** @defgroup EFUSE_Physical_Address_functions
* @{
*/
_LONG_CALL_ extern void EFUSE_PowerSwitchROM(u8 bWrite, u8 PwrState, u8 L25OutVoltage);
_LONG_CALL_ extern u32 EFUSE_OneByteReadROM(u32 CtrlSetting, u16 Addr, u8 *Data, u8 L25OutVoltage);
_LONG_CALL_ extern u32 EFUSE_OneByteWriteROM(u32 CtrlSetting, u16 Addr, u8 Data, u8 L25OutVoltage);
_LONG_CALL_ extern u8 EFUSE_LogicalMap_Read(u8 *pbuf);
_LONG_CALL_ extern u8 EFUSE_LogicalMap_Write(u32 addr, u32 cnts, u8 *data);
u32 EFUSE_OneByteRead_ACUT(u32 CtrlSetting, u16 Addr, u8 *Data, u8 L25OutVoltage);
u8 EFUSE_LogicalMap_Read_ACUT(u8 *pbuf);
u8 EFUSE_LogicalMap_Write_Check(u32 addr, u32 cnts, u8 *data);
#define EFUSEPowerSwitch EFUSE_PowerSwitchROM
#define EFUSERead8 EFUSE_OneByteReadROM
#define EFUSEWrite8 EFUSE_OneByteWriteROM
/**
* @}
*/
/** @defgroup EFUSE_USER_Area_functions
* @{
*/
_LONG_CALL_ void EFUSE_USER1_Read(u8 *pContant);
_LONG_CALL_ void EFUSE_USER2_Read(u8 *pContant);
_LONG_CALL_ void EFUSE_USER3_Read(u8 *pContant);
_LONG_CALL_ u8 EFUSE_USER1_Write(u8 SectionIdx, u8 WordEnable, u8 *pContant);
_LONG_CALL_ u8 EFUSE_USER2_Write(u8 SectionIdx, u8 WordEnable, u8 *pContant);
_LONG_CALL_ u8 EFUSE_USER3_Write(u8 SectionIdx, u8 WordEnable, u8 *pContant);
u8 EFUSE_USER1_Write_ACUT(u8 SectionIdx, u8 WordEnable, u8 *pContant);
/**
* @}
*/
/** @defgroup EFUSE_OTP_Area_functions
* @{
*/
_LONG_CALL_ u32 EFUSE_OTP_Read1B(u32 CtrlSetting, u16 Addr, u8 *Data, u8 L25OutVoltage);
_LONG_CALL_ u32 EFUSE_OTP_Write1B(u32 CtrlSetting, u16 Addr, u8 Data, u8 L25OutVoltage);
_LONG_CALL_ void EFUSE_OTP_Read32B(u8 *pContant);
_LONG_CALL_ u32 EFUSE_OTP_Write32B(u8 *pContant);
u32 EFUSE_OTP_Write1B_ACUT(u32 CtrlSetting, u16 Addr, u8 Data, u8 L25OutVoltage);
u32 EFUSE_OTP_Write32B_ACUT(u8 *pContant);
/**
* @}
*/
/** @defgroup EFUSE_FW_Protection_functions
* @{
*/
_LONG_CALL_ void EFUSE_RDP_EN(void);
_LONG_CALL_ void EFUSE_RDP_KEY(u8 *RdpKey);
_LONG_CALL_ void EFUSE_OTF_KEY(u8 *OtfKey);
_LONG_CALL_ u32 EFUSE_JTAG_OFF(void);
u32 EFUSE_JTAG_OFF_ACUT(void);
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/* Other functions --------------------------------------------------------*/
#define EFUSE_POLL_TIMES 20000
/* physical map bit Macro */
/* 0xD3 */
#define EFUSE_PHYSICAL_JTAG_ON BIT(0) /* 0: JTAG OFF, default 1: JTAG ON */
extern u8 EFUSE_MAP[512];
#ifdef CONFIG_CHIP_A_CUT
#define EFUSE_JTAG_OFF_ROM EFUSE_JTAG_OFF_ACUT
#define EFUSE_OTP_Write32B_ROM EFUSE_OTP_Write32B_ACUT
#define EFUSE_OTP_Write1B_ROM EFUSE_OTP_Write1B_ACUT
#define EFUSE_USER1_Write_ROM EFUSE_USER1_Write_ACUT
#define EFUSE_LMAP_READ EFUSE_LogicalMap_Read_ACUT
#define EFUSE_LMAP_WRITE EFUSE_LogicalMap_Write_Check
#else
#define EFUSE_JTAG_OFF_ROM EFUSE_JTAG_OFF
#define EFUSE_OTP_Write32B_ROM EFUSE_OTP_Write32B
#define EFUSE_OTP_Write1B_ROM EFUSE_OTP_Write1B
#define EFUSE_USER1_Write_ROM EFUSE_USER1_Write
#define EFUSE_LMAP_READ EFUSE_LogicalMap_Read
#define EFUSE_LMAP_WRITE EFUSE_LogicalMap_Write
#endif
#endif //_8710B_EFUSE_H_
/******************* (C) COPYRIGHT 2016 Realtek Semiconductor *****END OF FILE****/

View file

@ -0,0 +1,456 @@
/**
******************************************************************************
* @file rtl8711b_flash.h
* @author
* @version V1.0.0
* @date 2016-05-17
* @brief This file contains all the functions prototypes for the Flash firmware
* library.
******************************************************************************
* @attention
*
* This module is a confidential and proprietary property of RealTek and
* possession or use of this module requires written permission of RealTek.
*
* Copyright(c) 2016, Realtek Semiconductor Corporation. All rights reserved.
******************************************************************************
*/
#ifndef _RTL8710B_SPI_FLASH_H
#define _RTL8710B_SPI_FLASH_H
#include "rtl8711b_flashclk.h"
/** @addtogroup AmebaZ_Periph_Driver
* @{
*/
/** @defgroup FLASH
* @brief SPI Flash driver modules
* @{
*/
/** @addtogroup FLASH
* @verbatim
*****************************************************************************************
* Introduction
*****************************************************************************************
* SPI_Flash_Controller is used to communicate with SPI_Flash.
* Support auto mode and user mode to access Flash.
* Support multi-channel(1/2/4)data bit to transmit/receive.
* Programmable feature:
* SPI channel number - Control channel bits of serial transfer.
* SPI Clock rate - Control the bit rate of serial transfer.
* Flash command registers - Flexible to set the different command codes for
* different flash vendors in automatic mode.
* Dummy cycles- Allow users to add dummy cycles in receiving data path for
* timing tuning or extra pipelining registers.
* Flash address size- Define the size of Flash to enable the slave select output
* in automatic mode.
*
*****************************************************************************************
* How to use SPI_Flash_Controller to Read/Program/Erase flash
*****************************************************************************************
* To use the SPI_Flash_Controller to Read/Program/Erase flash, you can follow the steps
* below:
*
* 1. call FLASH_ClockDiv(FLASH_CLK_DIV2P5) to set Flash Clock, then enable SPIC clock
* using RCC_PeriphClockCmd(APBPeriph_GTIMER, APBPeriph_GTIMER_CLOCK, ENABLE) function.
*
* 2. call PinCtrl(PERIPHERAL_SPI_FLASH,PinLocat,ON) to configure SPIC pinmux.
*
* 3. Fill the variable flash_init_para of type FLASH_InitTypeDef with default parameters
* using one of the following functions according to flash vendor:
* flash vendor Struct Init Function
* Winbond FLASH_StructInit(&flash_init_para)
* Gigadevice FLASH_StructInit_GD(&flash_init_para)
* Micron FLASH_StructInit_Micron(&flash_init_para)
* MXIC FLASH_StructInit_MXIC(&flash_init_para)
*
* Note: (1)We support 4 flash chip vendors above in SDK.
* (2)If the flash chip type is Gigadevic and flash size is more than 2MB,
* you must set the FLASH_cmd_wr_status2 parameter in flash_init_para
* according to spec, because the Write Status Register1 command is
* different from write Status Register2 command.
* (3)If it is Micron flash chip, it is mandatory to set dummy cycles to
* Nonvolatile Configuration Register of flash. The number of dummy cycles is
* determined by Clock Frequency and Bit Mode according to spec.
* (4)If the flash chip type is Micron N25q00aa, you must set FLASH_cmd_chip_e
* parameter according to spec because it is different from default setting.
*
* 4. Initialize SPIC to designated BitMode using FLASH_Init().
*
* 5. Enable Quad I/O by setting QuadEnable bit in FLASH status register.
*
* 6. Calibrate by calling the following function:
* FLASH_CalibrationNew(&flash_init_para, SpicQuadBitMode, FLASH_CLK_DIV2P5, 2, 2, 1).
*
* 7. Then you can Read/Program/Erase flash by calling corresponding functions.
* Remember to add flash_write_lock() function before those operations and
* flash_write_unlock() after them to protect them when FLASH XIP.
*
* Note: (1)If flash code has some updates when XIP, you need to flush cache by calling
* Cache_Flush() function.
* (2)When XIP, the flash initialization and calibration have already finished,
* you can Read/Program/Erase flash directly without excuting 1~6 steps described
* above.
* @endverbatim
*/
/* Exported types ------------------------------------------------------------*/
/** @defgroup FLASH_Exported_Types SPIC Exported Types
* @{
*/
/**
* @brief FLASH Init structure definition
*/
typedef struct {
u32 FLASH_Id; /*!< Specifies the flash vendor ID.
This parameter can be a value of @ref FLASH_VENDOR_ID_definitions */
u8 FLASH_cur_bitmode; /*!< Specifies the current bitmode of SPIC.
This parameter can be a value of @ref FLASH_BIT_Mode_definitions */
u8 FLASH_baud_rate; /*!< Specifies the spi_sclk divider value. The frequency of spi_sclk is derived from:
Frequency of spi_sclk = Frequency of oc_clk / (2 * FLASH_baud_rate) */
u8 FLASH_baud_boot; /*!< Specifies the spi_sclk divider value for rom boot. The frequency of spi_sclk is derived from:
Frequency of spi_sclk = Frequency of oc_clk / (2 * FLASH_baud_rate) */
u32 FLASH_cur_cmd; /*!< Specifies the current read cmd which is used to read data from flash
in current bitmode. */
/* status bits define */
u32 FLASH_QuadEn_bit; /*!< Specifies the QE bit in status register which is used to enable Quad I/O mode . */
u32 FLASH_Busy_bit; /*!< Specifies the WIP(Write in Progress) bit in status register which indicates whether
the device is busy in program/erase/write status register progress. */
u32 FLASH_WLE_bit; /*!< Specifies the WEL(Write Enable Latch) bit in status register which indicates whether
the device will accepts program/erase/write status register instructions*/
u32 FLASH_Status2_exist; /*!< Specifies whether this flash chip has Status Register2 or not.
This parameter can be 0/1. 0 means it doesn't have Status Register2, 1 means
it has Status Register2.*/
/* calibration data */
u8 FLASH_rd_sample_phase; /*!< Specifies the read sample phase obtained from calibration.*/
u8 FLASH_rd_dummy_cyle[3]; /*!< Specifies the read dummy cycle of different bitmode according to
flash datasheet*/
/* valid R/W command set */
u32 FLASH_rd_dual_o; /*!< Specifies dual data read cmd */
u32 FLASH_rd_dual_io; /*!< Specifies dual data/addr read cmd */
u32 FLASH_rd_quad_o; /*!< Specifies quad data read cmd */
u32 FLASH_rd_quad_io; /*!< Specifies quad data/addr read cmd */
u32 FLASH_wr_dual_i; /*!< Specifies dual data write cmd */
u32 FLASH_wr_dual_ii; /*!< Specifies dual data/addr write cmd */
u32 FLASH_wr_quad_i; /*!< Specifies quad data write cmd */
u32 FLASH_wr_quad_ii; /*!< Specifies quad data/addr write cmd */
u32 FALSH_dual_valid_cmd; /*!< Specifies valid cmd of dual bitmode to program/read flash in auto mode */
u32 FALSH_quad_valid_cmd; /*!< Specifies valid cmd of quad bitmode to program/read flash in auto mode */
/* other command set */
u8 FLASH_cmd_wr_en; /*!< Specifies the Write Enable(WREN) instruction which is for setting WEL bit*/
u8 FLASH_cmd_rd_id; /*!< Specifies the Read ID instruction which is for getting the identity of the flash divice.*/
u8 FLASH_cmd_rd_status; /*!< Specifies the Read Status Register instruction which is for getting the status of flash */
u8 FLASH_cmd_rd_status2; /*!< Specifies the Read Status Register2 instruction which is for getting the status2 of flash */
u8 FLASH_cmd_wr_status; /*!< Specifies the Write Status Register instruction which is for setting the status register of flash */
u8 FLASH_cmd_wr_status2; /*!< Specifies the Write Status Register2 instruction which is for setting the status register2 of flash.
In some flash chips, status2 write cmd != status1 write cmd,
like: GD25Q32C, GD25Q64C,GD25Q128C etc.*/
u8 FLASH_cmd_chip_e; /*!< Specifies the Erase Chip instruction which is for erasing the whole chip*/
u8 FLASH_cmd_block_e; /*!< Specifies the Erase Block instruction which is for erasing 64kB*/
u8 FLASH_cmd_sector_e; /*!< Specifies the Erase Sector instruction which is for erasing 4kB*/
u8 FLASH_cmd_pwdn_release; /*!< Specifies the Deep Power Down instruction which is for entering power down mode.*/
u8 FLASH_cmd_pwdn; /*!< Specifies the Release from Deep Power Down instruction
which is for exiting power down mode.*/
/* debug log */
u8 debug; /*!< Specifies whether or not to print debug log.*/
/* new calibration */
u8 phase_shift_idx; /*!< Specifies the phase shift idx in new calibration.*/
} FLASH_InitTypeDef;
/**
* @}
*/
/* Exported constants --------------------------------------------------------*/
/** @defgroup FLASH_Exported_Constants FLASH Exported Constants
* @{
*/
/** @defgroup FLASH_CLK_Div_definitions
* @{
*/
#define FLASH_CLK_DIV2P5 0
#define FLASH_CLK_DIV3P0 1
#define FLASH_CLK_DIV3P5 2
#define FLASH_CLK_DIV4P0 3
#define FLASH_CLK_DIV4P5 4
#define FLASH_CLK_DIV5P0 5
#define FLASH_CLK_DIV5P5 6
/**
* @}
*/
/** @defgroup FLASH_BIT_Mode_definitions
* @{
*/
#define SpicOneBitMode 0
#define SpicDualBitMode 1
#define SpicQuadBitMode 2
/**
* @}
*/
/** @defgroup FLASH_ERASE_Type_definitions
* @{
*/
#define EraseChip 0
#define EraseBlock 1
#define EraseSector 2
/**
* @}
*/
/** @defgroup FLASH_WAIT_Type_definitions
* @{
*/
#define WAIT_SPIC_BUSY 0
#define WAIT_FLASH_BUSY 1
#define WAIT_WRITE_DONE 2
#define WAIT_WRITE_EN 3
/**
* @}
*/
/** @defgroup WINBOND_W25Q16DV_Spec
* @{
*/
#define FLASH_CMD_WREN 0x06 //write enable
#define FLASH_CMD_WRDI 0x04 //write disable
#define FLASH_CMD_WRSR 0x01 //write status register
#define FLASH_CMD_RDID 0x9F //read idenfication
#define FLASH_CMD_RDSR 0x05 //read status register
#define FLASH_CMD_RDSR2 0x35 //read status register-2
#define FLASH_CMD_READ 0x03 //read data
#define FLASH_CMD_FREAD 0x0B //fast read data
#define FLASH_CMD_RDSFDP 0x5A //Read SFDP
#define FLASH_CMD_RES 0xAB //Read Electronic ID
#define FLASH_CMD_REMS 0x90 //Read Electronic Manufacturer & Device ID
#define FLASH_CMD_DREAD 0x3B //Double Output Mode command
#define FLASH_CMD_SE 0x20 //Sector Erase
#define FLASH_CMD_BE 0xD8 //0x52 //64K Block Erase
#define FLASH_CMD_CE 0x60 //Chip Erase(or 0xC7)
#define FLASH_CMD_PP 0x02 //Page Program
#define FLASH_CMD_DP 0xB9 //Deep Power Down
#define FLASH_CMD_RDP 0xAB //Release from Deep Power-Down
#define FLASH_CMD_2READ 0xBB // 2 x I/O read command
#define FLASH_CMD_4READ 0xEB // 4 x I/O read command
#define FLASH_CMD_QREAD 0x6B // 1I / 4O read command
#define FLASH_CMD_4PP 0x32 //quad page program //this is diff with MXIC
#define FLASH_CMD_FF 0xFF //Release Read Enhanced
#define FLASH_CMD_REMS2 0x92 // read ID for 2x I/O mode //this is diff with MXIC
#define FLASH_CMD_REMS4 0x94 // read ID for 4x I/O mode //this is diff with MXIC
#define FLASH_CMD_RDSCUR 0x48 // read security register //this is diff with MXIC
#define FLASH_CMD_WRSCUR 0x42 // write security register //this is diff with MXIC
#define FLASH_DM_CYCLE_2O 0x08
#define FLASH_DM_CYCLE_2IO 0x04
#define FLASH_DM_CYCLE_4O 0x08
#define FLASH_DM_CYCLE_4IO 0x06
#define FLASH_STATUS_BUSY ((u32)0x00000001)
#define FLASH_STATUS_WLE ((u32)0x00000002)
/**
* @}
*/
/** @defgroup FLASH_VENDOR_ID_definitions
* @{
*/
#define FLASH_ID_OTHERS 0
#define FLASH_ID_MXIC 1
#define FLASH_ID_WINBOND 2
#define FLASH_ID_MICRON 3
#define FLASH_ID_EON 4
#define FLASH_ID_GD 5
#define FLASH_ID_BOHONG 6
/**
* @}
*/
/** @defgroup FLASH_MANUFACTURER_ID_definitions
* @{
*/
#define MANUFACTURER_ID_MXIC 0xC2
#define MANUFACTURER_ID_WINBOND 0xEF
#define MANUFACTURER_ID_MICRON 0x20
#define MANUFACTURER_ID_BOHONG 0x68
#define MANUFACTURER_ID_GD 0xC8
#define MANUFACTURER_ID_EON 0x1C
/**
* @}
*/
/**
* @}
*/
/* Exported functions --------------------------------------------------------*/
/** @defgroup FLASH_Exported_Functions FLASH Exported Functions
* @{
*/
_LONG_CALL_ void FLASH_Erase(u32 EraseType, u32 Address);
_LONG_CALL_ void FLASH_SetStatus(u8 Cmd, u32 Len, u8* Status);
_LONG_CALL_ void FLASH_SetStatusBits(u32 SetBits, u32 NewState);
_LONG_CALL_ void FLASH_WaitBusy(u32 WaitType);
_LONG_CALL_ void FLASH_WriteEn(void);
_LONG_CALL_ void FLASH_TxCmd(u8 cmd, u8 DataPhaseLen, u8* pData);
_LONG_CALL_ void FLASH_RxCmd(u8 cmd, u32 read_len, u8* read_data);
_LONG_CALL_ void FLASH_StructInit(FLASH_InitTypeDef* FLASH_InitStruct);
_LONG_CALL_ void FLASH_StructInit_Micron(FLASH_InitTypeDef* FLASH_InitStruct);
_LONG_CALL_ void FLASH_StructInit_MXIC(FLASH_InitTypeDef* FLASH_InitStruct);
_LONG_CALL_ void FLASH_StructInit_GD(FLASH_InitTypeDef* FLASH_InitStruct);
_LONG_CALL_ u8 FLASH_Init(u8 SpicBitMode);
_LONG_CALL_ void FLASH_SetSpiMode(FLASH_InitTypeDef *FLASH_InitStruct, u8 SpicBitMode);
_LONG_CALL_ void FLASH_DeepPowerDown(u32 NewState);
_LONG_CALL_ void FLASH_TxData12B(u32 StartAddr, u8 DataPhaseLen, u8* pData);
_LONG_CALL_ void FLASH_RxData(u8 cmd, u32 StartAddr, u32 read_len, u8* read_data);
_LONG_CALL_ u32 FLASH_Calibration(FLASH_InitTypeDef* FLASH_InitStruct, u8 SpicBitMode, u8 LineDelay);
_LONG_CALL_ u32 FLASH_ClockDiv(u8 Div);
_LONG_CALL_ u32 FLASH_CalibrationNew(FLASH_InitTypeDef* FLASH_InitStruct, u8 SpicBitMode, u8 Div, u8 CalStep, u8 LineDelay, u8 StartIdx);
_LONG_CALL_ u32 FLASH_CalibrationNewCmd(u32 NewStatus);
_LONG_CALL_ u32 FLASH_CalibrationPhaseIdx(u8 phase_idx);
_LONG_CALL_ u32 FLASH_CalibrationPhase(u8 phase_int, u8 phase_sel);
_LONG_CALL_ u32 FLASH_Calibration500MPSCmd(u32 NewStatus);
_LONG_CALL_ u32 FLASH_CalibrationInit(u8 CalibrationEnd);
/**
* @}
*/
/** @defgroup FLASH_Exported_XIP_Functions FLASH Exported XIP Functions
* @note these functions will lock cpu when exec to forbit XIP, and flush cache after exec
* @{
*/
void FLASH_Write_Lock(void);
void FLASH_Write_Unlock(void);
void FLASH_RxCmdXIP(u8 cmd, u32 read_len, u8* read_data);
void FLASH_SetStatusXIP(u8 Cmd, u32 Len, u8* Status);
void FLASH_SetStatusBitsXIP(u32 SetBits, u32 NewState);
void FLASH_TxData12BXIP(u32 StartAddr, u8 DataPhaseLen, u8* pData);
void FLASH_TxData256BXIP(u32 StartAddr, u32 DataPhaseLen, u8* pData);
void FLASH_EraseXIP(u32 EraseType, u32 Address);
void FLASH_EreaseDwordsXIP(u32 address, u32 dword_num);
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/* Registers Definitions --------------------------------------------------------*/
/******************** Bits definition for SPIC_CTRLR0 register *******************/
#define BIT_CMD_CH(x) (((x) & 0x00000003) << 20)
#define BIT_DATA_CH(x) (((x) & 0x00000003) << 18)
#define BIT_ADDR_CH(x) (((x) & 0x00000003) << 16)
#define BIT_TMOD(x) (((x) & 0x00000003) << 8)
#define BIT_SCPOL (0x00000001 << 7)
#define BIT_SCPH (0x00000001 << 6)
/******************** Bits definition for SPIC_CTRLR1 register *******************/
#define BIT_NDF(x) ((x) & 0xfff)
/******************** Bits definition for SPIC_SSIENR register *******************/
#define BIT_ATCK_CMD (0x00000001 << 1)
#define BIT_SPIC_EN (0x00000001)
/******************** Bits definition for SPIC_SER register *******************/
#define BIT_SER (0x00000001)
/******************** Bits definition for SPIC_BAUDR register *******************/
#define BIT_SCKDV(x) ((x) & 0xffff)
/******************** Bits definition for SPIC_SR register *******************/
#define BIT_TXE (0x00000001 << 5)
#define BIT_RFF (0x00000001 << 4)
#define BIT_RFNE (0x00000001 << 3)
#define BIT_TFE (0x00000001 << 2)
#define BIT_TFNF (0x00000001 << 1)
#define BIT_BUSY (0x00000001)
/******************** Bits definition for SPIC_IMR register *******************/
#define BIT_TXSIM (0x00000001 << 9)
#define BIT_ACEIM (0x00000001 << 8)
#define BIT_BYEIM (0x00000001 << 7)
#define BIT_WBEIM (0x00000001 << 6)
#define BIT_FSEIM (0x00000001 << 5)
#define BIT_RXFIM (0x00000001 << 4)
#define BIT_RXOIM (0x00000001 << 3)
#define BIT_RXUIM (0x00000001 << 2)
#define BIT_TXOIM (0x00000001 << 1)
#define BIT_TXEIM (0x00000001)
/******************** Bits definition for SPIC_ISR register *******************/
#define BIT_TXSIS (0x00000001 << 9)
#define BIT_ACEIS (0x00000001 << 8)
#define BIT_BYEIS (0x00000001 << 7)
#define BIT_WBEIS (0x00000001 << 6)
#define BIT_FSEIS (0x00000001 << 5)
#define BIT_RXFIS (0x00000001 << 4)
#define BIT_RXOIS (0x00000001 << 3)
#define BIT_RXUIS (0x00000001 << 2)
#define BIT_TXOIS (0x00000001 << 1)
#define BIT_TXEIS (0x00000001)
/******************** Bits definition for SPIC_RISR register *******************/
#define BIT_ACEIR (0x00000001 << 8)
#define BIT_BYEIR (0x00000001 << 7)
#define BIT_WBEIR (0x00000001 << 6)
#define BIT_FSEIR (0x00000001 << 5)
#define BIT_RXFIR (0x00000001 << 4)
#define BIT_RXOIR (0x00000001 << 3)
#define BIT_RXUIR (0x00000001 << 2)
#define BIT_TXOIR (0x00000001 << 1)
#define BIT_TXEIR (0x00000001)
/******************** Bits definition for SPIC_CTRLR2 register *******************/
#define BIT_FIFO_ENTRY(x) (((x) & 0x0000000f) << 4)
#define BIT_WR_SEQ (0x00000001 << 3)
#define BIT_WPN_DNUM (0x00000001 << 2) /* Indicate the WPn input pin of SPI Flash is connected to, 0(default): WP=spi_sout[2], 1:WP=spi_sout[3]. */
#define BIT_WPN_SET (0x00000001 << 1) /* To implement write protect function. spi_wen_out and the bit of spi_sout which connects to WPN would be initial to 0. */
#define BIT_SO_DUM (0x00000001) /* SO input pin of SPI Flash, 0: SO connects to spi_sout[0]. 1(default): SO connects to spi_sout[1].*/
/******************** Bits definition for SPIC_ADDR_LENGTH register *******************/
#define BIT_ADDR_PHASE_LENGTH(x) ((x) & 0x00000003)
/******************** Bits definition for SPIC_AUTO_LENGTH register *******************/
#define BIT_CS_H_WR_DUM_LEN(x) (((x) & 0x0000000f) << 28)
#define BIT_CS_H_RD_DUM_LEN(x) (((x) & 0x00000003) << 26)
#define BIT_AUTO_DUM_LEN(x) (((x) & 0x000000ff) << 18)
#define BIT_AUTO_ADDR_LENGTH(x) (((x) & 0x00000003) << 16)
#define BIT_RD_DUMMY_LENGTH(x) (((x) & 0x0000ffff))
/******************** Bits definition for SPIC_VALID_CMD register *******************/
#define BIT_WR_BLOCKING (0x00000001 << 9)
#define BIT_WR_QUAD_II (0x00000001 << 8)
#define BIT_WR_QUAD_I (0x00000001 << 7)
#define BIT_WR_DUAL_II (0x00000001 << 6)
#define BIT_WR_DUAL_I (0x00000001 << 5)
#define BIT_RD_QUAD_IO (0x00000001 << 4)
#define BIT_RD_QUAD_O (0x00000001 << 3)
#define BIT_RD_DUAL_IO (0x00000001 << 2)
#define BIT_RD_DUAL_I (0x00000001 << 1)
#define BIT_FRD_SINGEL (0x00000001)
/* Other definations --------------------------------------------------------*/
extern FLASH_InitTypeDef flash_init_para;
extern u32 SpicCalibrationPattern[2];
#endif //_RTL8710B_SPI_FLASH_H
/******************* (C) COPYRIGHT 2016 Realtek Semiconductor *****END OF FILE****/

View file

@ -0,0 +1,36 @@
/**
******************************************************************************
* @file rtl8711b_flashclk.h
* @author
* @version V1.0.0
* @date 2016-05-17
* @brief This file contains all the functions prototypes for the Flash Clock firmware
* library.
******************************************************************************
* @attention
*
* This module is a confidential and proprietary property of RealTek and
* possession or use of this module requires written permission of RealTek.
*
* Copyright(c) 2016, Realtek Semiconductor Corporation. All rights reserved.
******************************************************************************
*/
#ifndef _RTL8710B_FLASH_CLK_H
#define _RTL8710B_FLASH_CLK_H
/* Other definations --------------------------------------------------------*/
typedef struct {
u8 phase_int;
u8 phase_frac;
} FLASH_CLK_Phase;
typedef struct {
u16 div_sel;
u8 div_int;
u8 div_frac;
} FLASH_CLK_Div;
extern u8 NEW_CALIBREATION_END[];
#endif //_RTL8710B_FLASH_CLK_H
/******************* (C) COPYRIGHT 2016 Realtek Semiconductor *****END OF FILE****/

View file

@ -0,0 +1,578 @@
/**
******************************************************************************
* @file rtl8711b_gdma.h
* @author
* @version V1.0.0
* @date 2016-05-17
* @brief This file contains all the functions prototypes for the GDMA firmware
* library.
******************************************************************************
* @attention
*
* This module is a confidential and proprietary property of RealTek and
* possession or use of this module requires written permission of RealTek.
*
* Copyright(c) 2016, Realtek Semiconductor Corporation. All rights reserved.
******************************************************************************
*/
#ifndef _RTL8710B_GDMA_H_
#define _RTL8710B_GDMA_H_
/** @addtogroup AmebaZ_Periph_Driver
* @{
*/
/** @defgroup GDMA GDMA
* @{
*/
/** @addtogroup GDMA
* @verbatim
*****************************************************************************************
* Introduction
*****************************************************************************************
* Amebaz supports two GDMAs, GDMA0 and GDMA1. Each GDMA has six channels.
*
* GDMA0:
* - Base Address: GDMA0_REG_BASE
*
* - Channel index: 0~5
*
* - Block size range: 1~4095
*
* - Transfer Type and Flow Control:
* TTFCMemToMem (Memory to Memory)
* TTFCMemToPeri (Memory to Peripheral)
* TTFCPeriToMem (Peripheral to Memory)
* TTFCPeriToPeri (Peripheral to Peripheral)
*
* - Source and destination data width:
* TrWidthOneByte
* TrWidthTwoBytes
* TrWidthFourBytes
*
* - Source and destination burst transaction length:
* MsizeOne (One Byte)
* MsizeFour (Four Bytes)
* MsizeEight (Eight Bytes)
*
* - IRQ:
* GDMA0_CHANNEL0_IRQ
* GDMA0_CHANNEL1_IRQ
* GDMA0_CHANNEL2_IRQ
* GDMA0_CHANNEL3_IRQ
* GDMA0_CHANNEL4_IRQ
* GDMA0_CHANNEL5_IRQ
*
* - GDMA handshake interface with peripherals:
* 0: GDMA_HANDSHAKE_INTERFACE_UART0_TX
* 1: GDMA_HANDSHAKE_INTERFACE_UART0_RX
* 2: GDMA_HANDSHAKE_INTERFACE_UART1_TX
* 3: GDMA_HANDSHAKE_INTERFACE_UART1_RX
* 4: GDMA_HANDSHAKE_INTERFACE_SPI0_TX
* 5: GDMA_HANDSHAKE_INTERFACE_SPI0_RX
* 6: GDMA_HANDSHAKE_INTERFACE_SPI1_TX
* 7: GDMA_HANDSHAKE_INTERFACE_SPI1_RX
* 8: GDMA_HANDSHAKE_INTERFACE_I2C0_TX
* 9: GDMA_HANDSHAKE_INTERFACE_I2C0_RX
* 10: GDMA_HANDSHAKE_INTERFACE_I2C1_TX
* 11: GDMA_HANDSHAKE_INTERFACE_I2C1_RX
* 12: GDMA_HANDSHAKE_INTERFACE_ADC_RX
*
* GDMA1:
* - Base Address: GDMA1_REG_BASE
*
* - Channel index: 0~5
*
* - Block size range: 1~4095
*
* - Transfer Type and Flow Control:
* TTFCMemToMem (Memory to Memory)
* TTFCMemToPeri (Memory to Peripheral)
* TTFCPeriToMem (Peripheral to Memory)
* TTFCPeriToPeri (Peripheral to Peripheral)
*
* - Source and destination data width:
* TrWidthOneByte
* TrWidthTwoBytes
* TrWidthFourBytes
*
* - Source and destination burst transaction length:
* MsizeOne (One Byte)
* MsizeFour (Four Bytes)
* MsizeEight (Eight Bytes)
*
* - IRQ:
* GDMA1_CHANNEL0_IRQ
* GDMA1_CHANNEL1_IRQ
* GDMA1_CHANNEL2_IRQ
* GDMA1_CHANNEL3_IRQ
* GDMA1_CHANNEL4_IRQ
* GDMA1_CHANNEL5_IRQ
*
* - GDMA handshake interface with peripherals:
* 0: GDMA_HANDSHAKE_TIMER_CAPTURE_UP
* 1: GDMA_HANDSHAKE_TIMER_CAPTURE_CH0
* 2: GDMA_HANDSHAKE_TIMER_PWM_UP
* 3: GDMA_HANDSHAKE_TIMER_PWM_CH0
* 4: GDMA_HANDSHAKE_TIMER_PWM_CH1
* 5: GDMA_HANDSHAKE_TIMER_PWM_CH2
* 6: GDMA_HANDSHAKE_TIMER_PWM_CH3
* 7: GDMA_HANDSHAKE_TIMER_PWM_CH4
* 8: GDMA_HANDSHAKE_TIMER_PWM_CH5
*
*****************************************************************************************
* how to use GDMA
*****************************************************************************************
* To use the GDMA, the following steps are mandatory:
*
* 1. Allocate a GDMA channel using the follwoing function.
* GDMA_ChnlAlloc(u32 GDMA_Index, IRQ_FUN IrqFun, u32 IrqData, u32 IrqPriority)
*
* @note This function also includes the following operation:
* - register irq handler if use interrupt mode
* - enable NVIC interrupt
* - register the GDMA channel to use
* - enable GDMA peripheral clock
*
* 2. Program GDMA index, GDMA channel, data width, Msize, transfer direction, address increment mode,
* hardware handshake interface, reload control, interrupt type, block size, multi-block configuration
* and the source and destination address using the GDMA_Init() function.
*
* 3. Enable the corresponding interrupt using the function.
* GDMA_INTConfig() and register the uart irq handler if you need to use interrupt mode.
*
* @note This step is included in the "step 2"(GDMA_Init()).
*
* 4. Enable GDMA using function GDMA_Cmd().
*
*
* @endverbatim
*/
/* Exported Types --------------------------------------------------------*/
/** @defgroup GDMA_Exported_Types GDMA Exported Types
* @{
*/
/**
* @brief GDMA Init structure definition
*/
typedef struct {
u8 GDMA_Index; /*!< Specifies the GDMA index.
This parameter can be the value 0 or 1.
@note Amebaz supports two GDMAs, GDMA0 and GDMA1.*/
u8 GDMA_ChNum; /*!< Specifies the GDMA channel number.
This parameter can be the value 0 ~ 5.
@note Each GDMA supports six channels, channel0 ~ channel5.*/
u32 GDMA_DIR; /*!< Specifies the GDMA transmission direction.
This parameter can be a value of @ref GDMA_data_transfer_direction */
u32 GDMA_DstDataWidth; /*!< Specifies the GDMA destination transfer width.
This parameter can be a value of @ref GDMA_source_data_size */
u32 GDMA_SrcDataWidth; /*!< Specifies the GDMA transfer width.
This parameter can be a value of @ref GDMA_source_data_size */
u32 GDMA_DstInc; /*!< Specifies the GDMA destination address increment mode.
This parameter can be a value of @ref GDMA_incremented_mode */
u32 GDMA_SrcInc; /*!< Specifies the GDMA source address increment mode.
This parameter can be a value of @ref GDMA_incremented_mode */
u32 GDMA_DstMsize; /*!< Specifies the GDMA destination burst transaction length.
This parameter can be a value of @ref GDMA_Msize */
u32 GDMA_SrcMsize; /*!< Specifies the GDMA source burst transaction length.
This parameter can be a value of @ref GDMA_Msize */
u32 GDMA_SrcAddr; /*!< Specifies the GDMA source address.
This parameter can be a value of the memory or peripheral space address,
depending on the GDMA data transfer direction.If this address is configured,
GDMA will move data from here to the destination address space*/
u32 GDMA_DstAddr; /*!< Specifies the GDMA destination address.
This parameter can be a value of the memory or peripheral space address,
depending on the GDMA data transfer direction.If this address is configured,
GDMA will move data from here to the source address space*/
u16 GDMA_BlockSize; /*!< Specifies the GDMA block transfer size.
This parameter can be a value between 0 ~ 4095.
@note This parameter indicates the total number of single transactions for
every block transfer. The field for this parameter locates in CTLx[43:32], so
the value of this parameter must be no more than 0xffff.*/
u32 GDMA_IsrType; /*!< Specifies the GDMA interrupt types.
This parameter can be a value of @ref DMA_interrupts_definition */
u32 GDMA_ReloadSrc; /*!< Specifies the GDMA automatic source reload .
This parameter can be the 0 or 1.(0 : disable / 1 : enable).
@note if this value is setted 1, source address register can be automatically
reloaded from its initial value at the end of every block for multi-block transfers.
this parameter is only valid in multi block transmission mode*/
u32 GDMA_ReloadDst; /*!< Specifies the GDMA automatic destination reload .
This parameter can be the 0 or 1.(0 : disable / 1 : enable).
@note if this parameter is set 1, destination address register can be automatically
reloaded from its initial value at the end of every block for multi-block transfers.
this parameter is only valid in multi block transmission mode*/
u32 GDMA_LlpDstEn; /*!< Specifies the GDMA whether block chaining is enabled or disabled on the destination
side only.
@note this parameter is only valid in multi-block transmission mode*/
u32 GDMA_LlpSrcEn; /*!< Specifies the GDMA whether block chaining is enabled or disabled on the source
side only.
@note this parameter is only valid in multi-block transmission mode*/
u32 GDMA_SrcHandshakeInterface; /*!< Specifies the GDMA hardware handshaking interface for the source
peripheral of a GDMA channel.
This parameter can be a value of @ref DMA_HS_Interface_definition */
u32 GDMA_DstHandshakeInterface; /*!< Specifies the GDMA hardware handshaking interface for the destination
peripheral of a GDMA channel.
This parameter can be a value of @ref DMA_HS_Interface_definition */
u32 MuliBlockCunt; /*!< Specifies the GDMA Multi-block counter.
This parameter is used in multi-block transmission.*/
u32 MaxMuliBlock; /*!< Specifies the GDMA Max block number in Multi-block transmission.
This parameter is used in multi-block transmission.*/
} GDMA_InitTypeDef, *PGDMA_InitTypeDef;
/**
* @brief GDMA LLI ELE structure definition
*/
typedef struct {
u32 Sarx; /*!< Specifies the GDMA channel x Source Address Register (SARx) value field of a block descriptor
in block chaining.
This parameter stores the source address of the current block transfer.*/
u32 Darx; /*!< Specifies the GDMA channel x Destination Address Register(DARx) value field of a block descriptor
in block chaining.
This parameter stores the destination address of the current block transfer.*/
u32 Llpx; /*!< Specifies the GDMA channel x Linked List Pointer Register(LLPx) value field of a block descriptor
in block chaining.
This parameter is a address, which points to the next block descriptor.*/
u32 CtlxLow; /*!< Specifies the GDMA channel x Control Register(CTRx) Low 32 bit value field of a block descriptor
in block chaining.
This parameter stores the DMA control parameters of the current block transfer.*/
u32 CtlxUp; /*!< Specifies the GDMA channel x Control Register(CTRx) High 32 bit value field of a block descriptor
in block chaining.
This parameter stores the DMA control parameters of the current block transfer.*/
u32 Temp; /*!< Specifies the reserved GDMA channel x register value field of a block descriptor
in block chaining.*/
}GDMA_CH_LLI_ELE, *PGDMA_CH_LLI_ELE;
/**
* @brief GDMA CH LLI structure definition
*/
struct GDMA_CH_LLI {
GDMA_CH_LLI_ELE LliEle; /*!< Specifies the GDMA Linked List Item Element structure field of Linked List Item
in block chaining.
This structure variable stores the necessary parameters of a block descriptor.*/
u32 BlockSize; /*!< Specifies the GDMA block size of one block in block chaining.
This parameter indicates the block size of the current block transfer.*/
struct GDMA_CH_LLI *pNextLli; /*!< Specifies the GDMA Linked List Item pointer.
This parameter stores the address pointing to the next Linked List Item
in block chaining.*/
};
/**
* @}
*/
/** @defgroup GDMA_Exported_Constants GDMA Exported Constants
* @{
*/
/** @defgroup GDMA_data_transfer_direction GDMA Data Transfer Direction
* @{
*/
#define TTFCMemToMem ((u32)0x00000000)
#define TTFCMemToPeri ((u32)0x00000001)
#define TTFCPeriToMem ((u32)0x00000002)
#define TTFCPeriToPeri ((u32)0x00000003)
#define IS_GDMA_DIR(DIR) (((DIR) == TTFCMemToMem) || \
((DIR) == TTFCMemToPeri) || \
((DIR) == TTFCPeriToMem) ||\
((DIR) == TTFCPeriToPeri))
/**
* @}
*/
/** @defgroup GDMA_source_data_size GDMA Source Data Size
* @{
*/
#define TrWidthOneByte ((u32)0x00000000)
#define TrWidthTwoBytes ((u32)0x00000001)
#define TrWidthFourBytes ((u32)0x00000002)
#define IS_GDMA_DATA_SIZE(SIZE) (((SIZE) == TrWidthOneByte) || \
((SIZE) == TrWidthTwoBytes) || \
((SIZE) == TrWidthFourBytes))
/**
* @}
*/
/** @defgroup GDMA_Msize GDMA Msize
* @{
*/
#define MsizeOne ((u32)0x00000000)
#define MsizeFour ((u32)0x00000001)
#define MsizeEight ((u32)0x00000002)
#define IS_GDMA_MSIZE(SIZE) (((SIZE) == MsizeOne) || \
((SIZE) == MsizeFour) || \
((SIZE) == MsizeEight))
/**
* @}
*/
/** @defgroup GDMA_incremented_mode GDMA Source Incremented Mode
* @{
*/
#define IncType ((u32)0x00000000)
#define DecType ((u32)0x00000001)
#define NoChange ((u32)0x00000002)
#define IS_GDMA_IncMode(STATE) (((STATE) == IncType) || \
((STATE) == DecType) || \
((STATE) == NoChange))
/**
* @}
*/
/** @defgroup DMA_interrupts_definition DMA Interrupts Definition
* @{
*/
#define TransferType ((u32)0x00000001)
#define BlockType ((u32)0x00000002)
#define SrcTransferType ((u32)0x00000004)
#define DstTransferType ((u32)0x00000008)
#define ErrType ((u32)0x000000010)
#define IS_GDMA_CONFIG_IT(IT) ((((IT) & 0xFFFFFFF1) == 0x00) && ((IT) != 0x00))
/**
* @}
*/
/** @defgroup DMA_Reload_definition DMA Reload Definition
* @{
*/
#define CLEAN_RELOAD_SRC ((u32)0x00000001)
#define CLEAN_RELOAD_DST ((u32)0x00000002)
#define CLEAN_RELOAD_SRC_DST ((u32)0x00000003)
/**
* @}
*/
/** @defgroup GDMA0_HS_Interface_definition DMA HandShake Interface Definition
* @{
*/
#define GDMA_HANDSHAKE_INTERFACE_UART0_TX (0)
#define GDMA_HANDSHAKE_INTERFACE_UART0_RX (1)
#define GDMA_HANDSHAKE_INTERFACE_UART1_TX (2)
#define GDMA_HANDSHAKE_INTERFACE_UART1_RX (3)
#define GDMA_HANDSHAKE_INTERFACE_SPI0_TX (4)
#define GDMA_HANDSHAKE_INTERFACE_SPI0_RX (5)
#define GDMA_HANDSHAKE_INTERFACE_SPI1_TX (6)
#define GDMA_HANDSHAKE_INTERFACE_SPI1_RX (7)
#define GDMA_HANDSHAKE_INTERFACE_I2C0_TX (8)
#define GDMA_HANDSHAKE_INTERFACE_I2C0_RX (9)
#define GDMA_HANDSHAKE_INTERFACE_I2C1_TX (10)
#define GDMA_HANDSHAKE_INTERFACE_I2C1_RX (11)
#define GDMA_HANDSHAKE_INTERFACE_ADC_RX (12)
/**
* @}
*/
/** @defgroup GDMA1_HS_Interface_definition DMA HandShake Interface Definition
* @{
*/
#define GDMA_HANDSHAKE_TIMER_CAPTURE_UP (0)
#define GDMA_HANDSHAKE_TIMER_CAPTURE_CH0 (1)
#define GDMA_HANDSHAKE_TIMER_PWM_UP (2)
#define GDMA_HANDSHAKE_TIMER_PWM_CH0 (3)
#define GDMA_HANDSHAKE_TIMER_PWM_CH1 (4)
#define GDMA_HANDSHAKE_TIMER_PWM_CH2 (5)
#define GDMA_HANDSHAKE_TIMER_PWM_CH3 (6)
#define GDMA_HANDSHAKE_TIMER_PWM_CH4 (7)
#define GDMA_HANDSHAKE_TIMER_PWM_CH5 (8)
#define GDMA_HANDSHAKE_INTERFACE_I2C0_RX (9)
/**
* @}
*/
/**
* @}
*/
/** @defgroup GDMA_Exported_Functions GDMA Exported Functions
* @{
*/
_LONG_CALL_ void GDMA_StructInit(PGDMA_InitTypeDef GDMA_InitStruct);
_LONG_CALL_ void GDMA_Init(u8 GDMA_Index, u8 GDMA_ChNum, PGDMA_InitTypeDef GDMA_InitStruct);
_LONG_CALL_ void GDMA_SetLLP(u8 GDMA_Index, u8 GDMA_ChNum, u32 MultiBlockCount, struct GDMA_CH_LLI *pGdmaChLli);
_LONG_CALL_ void GDMA_Cmd(u8 GDMA_Index, u8 GDMA_ChNum, u32 NewState);
_LONG_CALL_ void GDMA_INTConfig(u8 GDMA_Index, u8 GDMA_ChNum, u32 GDMA_IT, u32 NewState);
_LONG_CALL_ u32 GDMA_ClearINTPendingBit(u8 GDMA_Index, u8 GDMA_ChNum, u32 GDMA_IT);
_LONG_CALL_ u32 GDMA_ClearINT(u8 GDMA_Index, u8 GDMA_ChNum);
_LONG_CALL_ void GDMA_ChCleanAutoReload(u8 GDMA_Index, u8 GDMA_ChNum, u32 CleanType);
_LONG_CALL_ void GDMA_SetSrcAddr(u8 GDMA_Index, u8 GDMA_ChNum, u32 SrcAddr);
_LONG_CALL_ u32 GDMA_GetSrcAddr(u8 GDMA_Index, u8 GDMA_ChNum);
_LONG_CALL_ u32 GDMA_GetDstAddr(u8 GDMA_Index, u8 GDMA_ChNum);
_LONG_CALL_ void GDMA_SetDstAddr(u8 GDMA_Index, u8 GDMA_ChNum, u32 DstAddr);
_LONG_CALL_ void GDMA_SetBlkSize(u8 GDMA_Index, u8 GDMA_ChNum, u32 BlkSize);
_LONG_CALL_ u32 GDMA_GetBlkSize(u8 GDMA_Index, u8 GDMA_ChNum);
_LONG_CALL_ BOOL GDMA_ChnlRegister (u8 GDMA_Index, u8 GDMA_ChNum);
_LONG_CALL_ void GDMA_ChnlUnRegister (u8 GDMA_Index, u8 GDMA_ChNum);
_LONG_CALL_ u8 GDMA_ChnlAlloc(u32 GDMA_Index, IRQ_FUN IrqFun, u32 IrqData, u32 IrqPriority);
_LONG_CALL_ void GDMA_ChnlFree(u8 GDMA_Index, u8 GDMA_ChNum);
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/* Register Address Offset Definitions --------------------------------------------------------*/
/******************** Address Offset Definition for GDMA Registers *******************/
#define REG_GDMA_CH_OFF (0x058) /*address space value between two DMA channels*/
#define REG_GDMA_CH_SAR (0x000) /*Source Address Register(SAR) address offset*/
#define REG_GDMA_CH_DAR (0x008) /*Destination Address Register(DAR) address offset*/
#define REG_GDMA_CH_LLP (0x010) /*Linked List Pointer(LLP) Register address offset*/
#define REG_GDMA_CH_CTL (0x018) /*Control Register(CTR) address offset*/
#define REG_GDMA_CH_SSTAT (0x020) /*Source Status(SSTAT) Register address offset*/
#define REG_GDMA_CH_DSTAT (0x028) /*Destination Status(DSTAT) Register address offset*/
#define REG_GDMA_CH_SSTATAR (0x030) /*Source Status Address(SSTATA) Register address offset*/
#define REG_GDMA_CH_DSTATAR (0x038) /*Destination Status Address(DSTATA) Register address offset*/
#define REG_GDMA_CH_CFG (0x040) /*Configuration(CFG) Register address offset*/
#define REG_GDMA_CH_SGR (0x048) /*Source Gather Register(SGR) address offset*/
#define REG_GDMA_CH_DSR (0x050) /*Destination Scatter Register(DSR) address offset*/
/********************** Address Offset Definition for Interrupt Raw Status Registers *******************/
#define REG_GDMA_RAW_INT_BASE (0x2C0) /*Base address for Interrupt Raw Status Registers*/
#define REG_GDMA_RAW_INT_TFR (0x2C0) /*address offset for DMA Transfer Complete Interrupt Raw Status Register(RawTfr)*/
#define REG_GDMA_RAW_INT_BLOCK (0x2c8) /*address offset for Block Transfer Complete Interrupt Raw Status Register(RawBlock)*/
#define REG_GDMA_RAW_INT_SRC_TRAN (0x2D0) /*address offset for Source Transaction Complete Interrupt Raw Status Register(RawSrcTran)*/
#define REG_GDMA_RAW_INT_DST_TRAN (0x2D8) /*address offset for Destination Transaction Complete Interrupt Raw Status Register(RawDstTran)*/
#define REG_GDMA_RAW_INT_ERR (0x2E0) /*address offset for Error Interrupt Raw Status Register(RawDstTran)*/
/********************** Address Offset Definition for Interrupt Status Registers *******************/
#define REG_GDMA_STATUS_INT_BASE (0x2E8) /*Base address for Interrupt Status Registers*/
#define REG_GDMA_STATUS_INT_TFR (0x2E8) /*address offset for DMA Transfer Complete Interrupt Status Register(StatusTfr)*/
#define REG_GDMA_STATUS_INT_BLOCK (0x2F0) /*address offset for Block Transfer Complete Interrupt Status Register(StatusBlock)*/
#define REG_GDMA_STATUS_INT_SRC_TRAN (0x2F8) /*address offset for Source Transaction Complete Interrupt Status Register(StatusSrcTran)*/
#define REG_GDMA_STATUS_INT_DST_TRAN (0x300) /*address offset for Destination Transaction Complete Interrupt Status Register(StatusDstTran)*/
#define REG_GDMA_STATUS_INT_ERR (0x308) /*address offset for Error Interrupt Status Register(StatusErr)*/
/********************** Address Offset Definition for Interrupt Mask Registers *******************/
#define REG_GDMA_MASK_INT_BASE (0x310) /*Base address for Interrupt Mask Registers*/
#define REG_GDMA_MASK_INT_TFR (0x310) /*address offset for DMA Transfer Complete Interrupt Mask Register(MaskTfr)*/
#define REG_GDMA_MASK_INT_BLOCK (0x318) /*address offset for Block Transfer Complete Interrupt Mask Register(MaskBlock)*/
#define REG_GDMA_MASK_INT_SRC_TRAN (0x320) /*address offset for Source Transaction Complete Interrupt Mask Register(MaskSrcTran)*/
#define REG_GDMA_MASK_INT_DST_TRAN (0x328) /*address offset for Destination Transaction Complete Interrupt Mask Register(MaskDstTran)*/
#define REG_GDMA_MASK_INT_INT_ERR (0x330) /*address offset for Error Interrupt Mask Register(MaskErr)*/
/********************** Address Offset Definition for Interrupt Clear Registers *******************/
#define REG_GDMA_CLEAR_INT_BASE (0x338) /*Base address for Interrupt Clear Registers*/
#define REG_GDMA_CLEAR_INT_TFR (0x338) /*address offset for DMA Transfer Complete Interrupt Clear Register(ClearTfr)*/
#define REG_GDMA_CLEAR_INT_BLOCK (0x340) /*address offset for Block Transfer Complete Interrupt Clear Register(ClearBlock)*/
#define REG_GDMA_CLEAR_INT_SRC_TRAN (0x348) /*address offset for Source Transaction Complete Interrupt Clear Register(ClearSrcTran)*/
#define REG_GDMA_CLEAR_INT_DST_TRAN (0x350) /*address offset for Destination Transaction Complete Interrupt Clear Register(ClearDstTran)*/
#define REG_GDMA_CLEAR_INT_ERR (0x358) /*address offset for Error Interrupt Clear Register(ClearErr)*/
/********************* Address Offset Definition for Combined Interrupt Status Register ***********/
#define REG_GDMA_STATUS_INT (0x360) /*address offset for Combined Interrupt Status Register*/
/********************** Address Offset Definition for Software Handshaking Registers *************/
#define REG_GDMA_REQ_SRC (0x368) /*address offset for Source Software Transaction Request Register(ReqSrcReg)*/
#define REG_GDMA_REQ_DST (0x370) /*address offset for Destination Software Transaction Request Register(ReqDstReg)*/
#define REG_GDMA_REQ_SGL_REQ (0x378) /*address offset for Single Source Transaction Request Register(SglReqSrcReg)*/
#define REG_GDMA_REQ_DST_REQ (0x380) /*address offset for Single Destination Transaction Request Register(SglReqDstReg)*/
#define REG_GDMA_REQ_LST_SRC (0x388) /*address offset for Last Source Transaction Request Register(LstSrcReg)*/
#define REG_GDMA_REQ_LST_DST (0x390) /*address offset for Last Destination Transaction Request Register(LstDstReg)*/
/********************** Address Offset Definition for Miscellaneous Registers *************/
#define REG_GDMA_DMAC_CFG (0x398) /*address offset for DMA Configuration Register(DmaCfgReg)*/
#define REG_GDMA_CH_EN (0x3A0) /*address offset for DMA Channel Enable Register(ChEnReg)*/
#define REG_GDMA_DMA_ID (0x3A8) /*address offset for DMA ID Register(DmaIdReg)*/
#define REG_GDMA_DMA_TEST (0x3B0) /*address offset for DMA Test Register(DmaTestReg)*/
#define REG_GDMA_DMA_COM_PARAMS6 (0x3C8) /*address offset for DMA Component Parameters Register 6(DMA_COMP_PARAMS_6)*/
#define REG_GDMA_DMA_COM_PARAMS5 (0x3D0) /*address offset for DMA Component Parameters Register 5(DMA_COMP_PARAMS_5)*/
#define REG_GDMA_DMA_COM_PARAMS4 (0x3D8) /*address offset for DMA Component Parameters Register 4(DMA_COMP_PARAMS_4)*/
#define REG_GDMA_DMA_COM_PARAMS3 (0x3E0) /*address offset for DMA Component Parameters Register 3(DMA_COMP_PARAMS_3)*/
#define REG_GDMA_DMA_COM_PARAMS2 (0x3E8) /*address offset for DMA Component Parameters Register 2(DMA_COMP_PARAMS_2)*/
#define REG_GDMA_DMA_COM_PARAMS1 (0x3F0) /*address offset for DMA Component Parameters Register 1(DMA_COMP_PARAMS_1)*/
#define REG_GDMA_DMA_COM_PARAMS0 (0x3F8) /*address offset for DMA Component ID Register. Bit[63:32]: DMA_COMP_VERSION
Bit[31:0]:DMA_COMP_TYPE*/
/* Registers Definitions ----------------------------------------------------------------*/
/******************** Bits definition for CTL register *******************/
#define BIT_CTLX_LO_INT_EN ((u32)(0x00000001 << 0)) /*Lower word Bit[0].Interrupt Enable Bit.*/
#define BIT_CTLX_LO_LLP_DST_EN ((u32)(0x00000001 << 27)) /*Lower word Bit[27].Block chaining is enabled on the destination side only*/
#define BIT_CTLX_LO_LLP_SRC_EN ((u32)(0x00000001 << 28)) /*Lower word Bit[28].Block chaining is enabled on the source side only*/
#define BIT_CTLX_LO_DST_TR_WIDTH ((u32)(0x00000007 << 1)) /*Lower word Bit[3:1].Destination Transfer Width*/
#define BIT_CTLX_LO_SRC_TR_WIDTH ((u32)(0x00000007 << 4)) /*Lower word Bit[6:4].Source Transfer Width*/
#define BIT_CTLX_LO_DINC ((u32)(0x00000003 << 7)) /*Lower word Bit[8:7].Destination Address Increment*/
#define BIT_CTLX_LO_SINC ((u32)(0x00000003 << 9)) /*Lower word Bit[10:9].Source Address Increment*/
#define BIT_CTLX_LO_DEST_MSIZE ((u32)(0x00000007 << 11)) /*Lower word Bit[13:11].Destination Burst Transaction Length*/
#define BIT_CTLX_LO_SRC_MSIZE ((u32)(0x00000007 << 14)) /*Lower word Bit[16:14].Source Burst Transaction Length*/
#define BIT_CTLX_LO_SRC_GATHER_EN ((u32)(0x00000001 << 17)) /*Lower word Bit[17].Source gather enable bit*/
#define BIT_CTLX_LO_DST_SCATTER_EN ((u32)(0x00000001 << 18)) /*Lower word Bit[18].Destination gather enable bit*/
#define BIT_CTLX_LO_TT_FC ((u32)(0x00000007 << 20)) /*Lower word Bit[22:20].Transfer Type and Flow Control*/
#define BIT_CTLX_LO_DMS ((u32)(0x00000003 << 23)) /*Lower word Bit[24:23].Destination Master Select*/
#define BIT_CTLX_LO_SMS ((u32)(0x00000003 << 25)) /*Lower word Bit[26:25].Source Master Select*/
#define BIT_CTLX_UP_DONE ((u32)(0x00000001 << 12)) /*Upper word Bit[12].Done bit*/
#define BIT_CTLX_UP_BLOCK_BS ((u32)(0x00000FFF << 0)) /*Upper word Bit[11:0].Block Transfer Size.*/
/******************** Bits definition for CFG register *******************/
#define BIT_CFGX_LO_RELOAD_SRC ((u32)(0x00000001 << 30)) /*Lower word Bit[30].Automatic Source Reload bit*/
#define BIT_CFGX_LO_RELOAD_DST ((u32)(0x00000001 << 31)) /*Lower word Bit[31].Automatic Destination Reload bit*/
#define BIT_CFGX_LO_SRC_PER ((u32)(0x0000000F << 7)) /*Upper word Bit[10:7].hardware handshaking interface for source peripheral*/
#define BIT_CFGX_LO_DEST_PER ((u32)(0x0000000F << 11)) /*Upper word Bit[14:11].hardware handshaking interface for destination peripheral*/
/* Other Definitions -------------------------------------------------------------------*/
#define MAX_GDMA_INDX (1)
#define MAX_GDMA_CHNL (5)
#define HAL_GDMAX_READ32(GDMA_Index, addr) HAL_READ32(GDMA0_REG_BASE+ (GDMA_Index*GDMA1_REG_OFF), addr)
#define HAL_GDMAX_WRITE32(GDMA_Index, addr, value) HAL_WRITE32((GDMA0_REG_BASE+ (GDMA_Index*GDMA1_REG_OFF)), addr, value)
#define GDMA_CH_MAX (0x06)
extern u8 GDMA_IrqNum[2][6];
#endif //_RTL8710B_GDMA_H_
/******************* (C) COPYRIGHT 2016 Realtek Semiconductor *****END OF FILE****/

View file

@ -0,0 +1,262 @@
/**
******************************************************************************
* @file rtl8711b_gpio.h
* @author
* @version V1.0.0
* @date 2016-05-17
* @brief This file contains all the functions prototypes for the GPIO firmware
* library.
******************************************************************************
* @attention
*
* This module is a confidential and proprietary property of RealTek and
* possession or use of this module requires written permission of RealTek.
*
* Copyright(c) 2016, Realtek Semiconductor Corporation. All rights reserved.
******************************************************************************
*/
#ifndef _RTL8711B_GPIO_H_
#define _RTL8711B_GPIO_H_
/** @addtogroup AmebaZ_Periph_Driver
* @{
*/
/** @defgroup GPIO
* @brief GPIO driver modules
* @{
*/
/** @addtogroup GPIO
* @verbatim
*****************************************************************************************
* Introduction
*****************************************************************************************
* GPIO:
* - Base Address: GPIO
* - Port number: support A/B/C/D four ports, AmebaZ only use A/B two ports
* - Pin number: 0 ~ 31(portA), 0 ~ 6(portB)
* - IRQ: GPIO_IRQ
* - Only portA can be configured to interrupt mode
*
*****************************************************************************************
* How to use GPIO in normal mode
*****************************************************************************************
* To use GPIO peripheral in normal mode, the following steps are mandatory:
*
* 1. Enable the GPIO interface clock using
* RCC_PeriphClockCmd(APBPeriph_GPIO, APBPeriph_GPIO_CLOCK, ENABLE);
*
* 2. Fill the GPIO_InitStruct with the desired parameters.
*
* 3. configure GPIO with the configuration(GPIO mode, pull up/down) of step2:
* GPIO_Init(&GPIO_InitStruct)
*
* 4. Read or write GPIO pin according to GPIO out/in mode using
* GPIO_ReadDataBit() or GPIO_WriteBit()
*
*****************************************************************************************
* How to use GPIO in interrupt mode
*****************************************************************************************
* To use GPIO in interrupt mode, the following steps are mandatory:
*
* 1. Enable the GPIO interface clock using
* RCC_PeriphClockCmd(APBPeriph_GPIO, APBPeriph_GPIO_CLOCK, ENABLE);
*
* 2. Fill the GPIO_InitStruct with the desired parameters.
*
* 3. configure GPIO with the configuration(GPIO mode, pull up/down) of step2:
* GPIO_Init(&GPIO_InitStruct)
*
* 4. Register a user interrupt handler:
* GPIO_UserRegIrq
*
* 5. Configure interrupt mode(trigger, polarity, debounce):
* GPIO_INTMode()
*
* 6. Enable the interrupt of a specified pin:
* GPIO_INTConfig()
*
* @note Only PortA can configure interrupt mode.
*
*****************************************************************************************
* How to use GPIO port (multiple GPIO pins)
*****************************************************************************************
* To use GPIO port, the following steps are mandatory:
*
* 1. Enable the GPIO interface clock using
* RCC_PeriphClockCmd(APBPeriph_GPIO, APBPeriph_GPIO_CLOCK, ENABLE);
*
* 2. Configure GPIO data direction(IN/OUT)
* GPIO_PortDirection()
*
* 3. Read or write GPIO pin according to GPIO out/in mode using
* GPIO_PortRead()
* GPIO_PortWrite()
*
*****************************************************************************************
* @endverbatim
*/
/* Exported types ------------------------------------------------------------*/
/** @defgroup GPIO_Exported_Types GPIO Exported Types
* @{
*/
/**
* @brief GPIO Init structure definition
*/
typedef struct {
u32 GPIO_Mode; /*!< Specifies the operating mode for the selected pins.
This parameter can be a value of @ref GPIO_Mode_parameter_definitions */
u32 GPIO_PuPd; /*!< Specifies the operating Pull-up/Pull down for the selected pins.
This parameter can be a value of @ref GPIO_Pull_parameter_definitions */
u32 GPIO_ITTrigger; /*!< Specifies interrupt mode is level or edge trigger
This parameter can be a value of @ref GPIO_INT_Trigger_parameter_definitions */
u32 GPIO_ITPolarity; /*!< Specifies interrupt mode is high or low active trigger
This parameter can be a value of @ref GPIO_INT_Polarity_parameter_definitions */
u32 GPIO_ITDebounce; /*!< Specifies enable or disable de-bounce for interrupt
This parameter can be a value of @ref GPIO_INT_Debounce_parameter_definitions*/
u32 GPIO_Pin; /*!< Specifies the selected pins.
This parameter contains two parts: Pin: [7:5]: port number; [4:0]: pin number */
} GPIO_InitTypeDef;
/**
* @}
*/
/* Exported constants --------------------------------------------------------*/
/** @defgroup GPIO_Exported_Constants GPIO Exported Constants
* @{
*/
/** @defgroup GPIO_Mode_parameter_definitions
* @{
*/
#define GPIO_Mode_IN 0x00 /*!< GPIO Input Mode */
#define GPIO_Mode_OUT 0x01 /*!< GPIO Output Mode */
#define GPIO_Mode_INT 0x02 /*!< GPIO Interrupt Mode */
/**
* @}
*/
/** @defgroup GPIO_Pull_parameter_definitions
* @{
*/
#define GPIO_PuPd_NOPULL 0x00 /*!< GPIO Interrnal HIGHZ */
#define GPIO_PuPd_DOWN 0x01 /*!< GPIO Interrnal Pull DOWN */
#define GPIO_PuPd_UP 0x02 /*!< GPIO Interrnal Pull UP */
#define GPIO_PuPd_SHUTDOWN 0x03 /*!< GPIO Interrnal PAD shutdown */
/**
* @}
*/
/** @defgroup GPIO_INT_Trigger_parameter_definitions
* @{
*/
#define GPIO_INT_Trigger_LEVEL 0x0 /*!< This interrupt is level trigger */
#define GPIO_INT_Trigger_EDGE 0x1 /*!< This interrupt is edge trigger */
#define IS_GPIOIT_LEVEL_TYPE(TYPE) (((TYPE) == GPIO_INT_Trigger_LEVEL)\
|| ((TYPE) == GPIO_INT_Trigger_EDGE))
/**
* @}
*/
/** @defgroup GPIO_INT_Polarity_parameter_definitions
* @{
*/
#define GPIO_INT_POLARITY_ACTIVE_LOW 0x0 /*!< Setting interrupt to low active: falling edge or low level */
#define GPIO_INT_POLARITY_ACTIVE_HIGH 0x1 /*!< Setting interrupt to high active: rising edge or high level */
#define IS_GPIOIT_POLARITY_TYPE(TYPE) (((TYPE) == GPIO_INT_POLARITY_ACTIVE_LOW)\
|| ((TYPE) == GPIO_INT_POLARITY_ACTIVE_HIGH))
/**
* @}
*/
/** @defgroup GPIO_INT_Debounce_parameter_definitions
* @{
*/
#define GPIO_INT_DEBOUNCE_DISABLE 0x0 /*!< Disable interrupt debounce */
#define GPIO_INT_DEBOUNCE_ENABLE 0x1 /*!< Enable interrupt debounce */
#define IS_GPIOIT_DEBOUNCE_TYPE(TYPE) (((TYPE) == GPIO_INT_DEBOUNCE_DISABLE)\
|| ((TYPE) == GPIO_INT_DEBOUNCE_ENABLE))
/**
* @}
*/
/** @defgroup GPIO_Pin_State_definitions
* @{
*/
#define GPIO_PIN_LOW 0 /*!< Pin state is low */
#define GPIO_PIN_HIGH 1 /*!< Pin state is high */
/**
* @}
*/
/** @defgroup GPIO_Port_definitions
* @{
*/
#define GPIO_PORT_A 0 /*!< Port number A */
#define GPIO_PORT_B 1 /*!< Port number B */
/**
* @}
*/
/** @defgroup GPIO_IRQ_Event_definitions
* @{
*/
#define HAL_IRQ_NONE 0 /*!< No interrupt event */
#define HAL_IRQ_RISE 1 /*!< Rising edge or high level interrupt event */
#define HAL_IRQ_FALL 2 /*!< Falling edge or low level interrupt event */
/**
* @}
*/
/**
* @}
*/
/** @defgroup GPIO_Exported_Functions GPIO Exported Functions
* @{
*/
_LONG_CALL_ void GPIO_WriteBit(u32 GPIO_Pin, u32 BitVal);
_LONG_CALL_ u32 GPIO_ReadDataBit(u32 GPIO_Pin);
_LONG_CALL_ void GPIO_DeInit(u32 GPIO_Pin);
_LONG_CALL_ void GPIO_UserRegIrq(u32 GPIO_Pin, VOID *IrqHandler, VOID *IrqData);
_LONG_CALL_ void GPIO_INTMode(u32 GPIO_Pin, u32 NewState, u32 GPIO_ITTrigger, u32 GPIO_ITPolarity, u32 GPIO_ITDebounce);
_LONG_CALL_ void GPIO_INTConfig(u32 GPIO_Pin, u32 NewState);
_LONG_CALL_ void GPIO_Init(GPIO_InitTypeDef *GPIO_InitStruct);
_LONG_CALL_ u32 GPIO_INTHandler(void *pData);
_LONG_CALL_ void GPIO_Direction(u32 GPIO_Pin, u32 data_direction);
_LONG_CALL_ u32 GPIO_PortRead(u32 GPIO_Port, u32 GPIO_Mask);
_LONG_CALL_ void GPIO_PortWrite(u32 GPIO_Port, u32 GPIO_Mask, u32 Port_State);
_LONG_CALL_ void GPIO_PortDirection(u32 GPIO_Port, u32 GPIO_Mask, u32 data_direction);
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
typedef void (*GPIO_IRQ_FUN)(VOID *Data, u32 Id);
typedef void (*GPIO_USER_IRQ_FUN)(u32 Id);
#endif // end of "#define _RTL8711B_GPIO_H_"
/******************* (C) COPYRIGHT 2016 Realtek Semiconductor *****END OF FILE****/

View file

@ -0,0 +1,660 @@
/**
******************************************************************************
* @file rtl8711b_i2c.h
* @author
* @version V1.0.0
* @date 2016-05-17
* @brief This file contains all the functions prototypes for the I2C firmware
* library.
******************************************************************************
* @attention
*
* This module is a confidential and proprietary property of RealTek and
* possession or use of this module requires written permission of RealTek.
*
* Copyright(c) 2016, Realtek Semiconductor Corporation. All rights reserved.
******************************************************************************
*/
#ifndef _RTL8710B_I2C_H_
#define _RTL8710B_I2C_H_
/** @addtogroup AmebaZ_Periph_Driver
* @{
*/
/** @addtogroup I2C I2C
* @{
*/
/** @addtogroup I2C
* @verbatim
*****************************************************************************************
* Introduction
*****************************************************************************************
* I2C0:
* - Base Address: I2C0_DEV
* - IPclk: 62.5Mhz
* - Speed: Standard (up to 100 kHz) and Fast (up to 400 kHz) Modes
* - Address: 7/10-bit Address Mode (Master and Slave0) and 7-bit Address Mode (Slave1)
* - SocPs: SleepMode (clock gating & power gating)
* - Slave: Slave0 and Slave1
* - IRQ: I2C0_IRQ
* - GDMA TX handshake interface: GDMA_HANDSHAKE_INTERFACE_I2C0_TX
* - GDMA RX handshake interface: GDMA_HANDSHAKE_INTERFACE_I2C0_RX
*
* I2C1: The same as I2C0 except following
* - Base Address: I2C1_DEV
* - IRQ: I2C1_IRQ
* - GDMA TX handshake interface: GDMA_HANDSHAKE_INTERFACE_I2C1_TX
* - GDMA RX handshake interface: GDMA_HANDSHAKE_INTERFACE_I2C1_RX
*
*****************************************************************************************
* PINMUX
*****************************************************************************************
* I2C0:
* - S0: PA_1(SCL)/PA_4(SDA).
* - S1: PA_22(SCL)/PA_19(SDA).
* - S2: PA_29(SCL)/PA_30(SDA).
*
* I2C1:
* - S0: PA_3(SCL)/PA_2(SDA).
* - S1: PA_18(SCL)/PA_23(SDA).
* - S2: PA_28(SCL)/PA_27(SDA).
*
*****************************************************************************************
* How to use Normal I2C
*****************************************************************************************
* To use the normal i2c mode, the following steps are mandatory:
*
* 1. Enable peripheral clock using the follwoing functions.
* RCC_PeriphClockCmd(APBPeriph_I2Cx, APBPeriph_I2Cx_CLOCK, ENABLE);
*
* 2. configure the I2C pinmux.
* Pinmux_Config(Pin_Num, PINMUX_FUNCTION_I2C)
*
* 3. Program Role, Address Mode, Speed Mode, I2C CLK, Slave address, Threshold, Feature Supports
* I2C_StructInit()
*
* 4. Init Hardware use step3 parameters:
* I2C_Init(I2C_TypeDef *I2Cx, I2C_InitTypeDef* I2C_InitStruct)
*
* 5. Enable the NVIC and the corresponding interrupt using following function if you need
* to use interrupt mode.
* I2C_INTConfig(): I2C IRQ Mask set
* InterruptRegister(): register the i2c irq handler
* InterruptEn(): Enable the NVIC interrupt
*
* 6. Enable i2c module using I2C_Cmd().
*
*****************************************************************************************
* How to use i2c in DMA mode
*****************************************************************************************
* To use the i2c in DMA mode, the following steps are mandatory:
*
* 1. Enable peripheral clock using the follwoing functions.
* RCC_PeriphClockCmd(APBPeriph_I2Cx, APBPeriph_I2Cx_CLOCK, ENABLE);
*
* 2. configure the I2C pinmux.
* Pinmux_Config(Pin_Num, PINMUX_FUNCTION_I2C)
*
* 3. Program Role, Address Mode, Speed Mode, I2C CLK, Slave address, Threshold, Feature Supports
* I2C_StructInit()
*
* 4. Init Hardware use step3 parameters:
* I2C_Init(I2C_TypeDef *I2Cx, I2C_InitTypeDef* I2C_InitStruct)
*
* 5. Enable i2c module using I2C_Cmd().
*
* 6. GDMA related configurations(source address/destination address/block size etc.)
* I2C_TXGDMA_Init():Init and Enable I2C TX GDMA
* I2C_RXGDMA_Init():Init and Enable I2C RX GDMA
*
* 7. I2C DMA Mode choose. The Control Register DMA mode is recommended more.
* I2C_DmaMode1Config():Configures the I2Cx Control Register DMA mode
* I2C_DmaMode2Config():Configures the I2Cx Discripter DMA mode
*
* 8. Active the I2C TX/RX DMA Request using I2C_DMAControl().
*
*****************************************************************************************
* How to use i2c in Sleep mode
*****************************************************************************************
* To use the i2c in Low Power mode, the following steps are mandatory:
*
* 1. Enable peripheral clock using the follwoing functions.
* RCC_PeriphClockCmd(APBPeriph_I2Cx, APBPeriph_I2Cx_CLOCK, ENABLE);
*
* 2. configure the I2C pinmux.
* Pinmux_Config(Pin_Num, PINMUX_FUNCTION_I2C)
*
* 3. Program Role, Address Mode, Speed Mode, I2C CLK, Slave address, Threshold, Feature Supports
* I2C_StructInit()
*
* 4. Init Hardware use step3 parameters:
* I2C_Init(I2C_TypeDef *I2Cx, I2C_InitTypeDef* I2C_InitStruct)
*
* 5. Enable the NVIC and the corresponding interrupt using following function if you need
* to use interrupt mode.
* I2C_INTConfig(): I2C IRQ Mask set
* InterruptRegister(): register the i2c irq handler
* InterruptEn(): Enable the NVIC interrupt
*
* 6. Enable address matching interrupts for wake up
* I2C_INTConfig(): I2C Addr match IRQ Mask set
* BIT_IC_INTR_MASK_M_ADDR_1_MATCH refer to refer to I2C Slave0 Address Match
* BIT_IC_INTR_MASK_M_ADDR_2_MATCH refer to refer to I2C Slave1 Address Match
*
* 7. Set wake up event using the follwoing functions.
* SOCPS_SetWakeEvent()
*
* 8. Set power ext option BIT_SYSON_PMOPT_SLP_ANACK_EN to Enable ANA clock and
* BIT_SYSON_PMOPT_SLP_ANACK_SEL to select 4M clock for power save mode, then hardware
* will automatically switch to the 4M clock when enter sleep state.
* SOCPS_PWROptionExt()
*
* 9. Clear address matching interrupts after address matching interrupts
* I2C_WakeUp()
*
* @note I2C0 and I2C1 are different in sleep mode
* I2C0 can only be wakeup from clockgate mode
* I2C1 can be wakeup from clockgate mode and powergate mode
*
*****************************************************************************************
* @endverbatim
*/
/* Exported types --------------------------------------------------------*/
/** @defgroup I2C_Exported_Types I2C Exported Types
* @{
*/
/**
* @brief I2C Init structure definition
*/
typedef struct {
u32 I2CIdx; /*!< Specifies the I2C Device Index.
This parameter can be a value of @ref I2C_Peripheral_definitions */
u32 I2CMaster; /*!< Specifies the I2C Role.
This parameter can be a value of @ref I2C_Role_definitions */
u32 I2CAddrMod; /*!< Specifies the I2C Addressing Mode.
This parameter can be a value of @ref I2C_Addr_Mode_definitions */
u32 I2CSpdMod; /*!< Specifies the I2C Speed Mode. Now the circuit don't support High Speed Mode.
This parameter can be a value of @ref I2C_Speed_Mode_definitions */
u32 I2CRXTL; /*!< Specifies the I2C RX FIFO Threshold. It controls the level of
entries(or above) that triggers the RX_FULL interrupt.
This parameter must be set to a value in the 0-255 range. A value of 0 sets
the threshold for 1 entry, and a value of 255 sets the threshold for 256 entry*/
u32 I2CTXTL; /*!< Specifies the I2C TX FIFO Threshold.It controls the level of
entries(or below) that triggers the TX_EMPTY interrupt.
This parameter must be set to a value in the 0-255 range. A value of 0 sets
the threshold for 0 entry, and a value of 255 sets the threshold for 255 entry*/
u32 I2CMstReSTR; /*!< Specifies the I2C Restart Support of Master. */
u32 I2CMstGC; /*!< Specifies the I2C General Call Support of Master. */
u32 I2CMstStartB; /*!< Specifies the I2C Start Byte Support of Master. */
u32 I2CSlvNoAck; /*!< Specifies the I2C Slave No Ack Support. */
u32 I2CSlvAckGC; /*!< Specifies the I2C Slave Acks to General Call. */
u32 I2CAckAddr; /*!< Specifies the I2C Target Address in I2C Master Mode or
Ack Address in I2C Slave0 Mode.
This parameter must be set to a value in the 0-127 range if the I2C_ADDR_7BIT
is selected or 0-1023 range if the I2C_ADDR_10BIT is selected. */
u32 I2CSlvSetup; /*!< Specifies the I2C SDA Setup Time. It controls the amount of time delay
introduced in the rising edge of SCL¡ªrelative to SDA changing¡ªby holding SCL low
when I2C Device operating as a slave transmitter, in units of ic_clk period.
This parameter must be set to a value in the 0-255 range. */
u32 I2CSdaHd; /*!< Specifies the I2C SDA Hold Time. It controls the amount of
hold time on the SDA signal after a negative edge of SCL in both master
and slave mode, in units of ic_clk period.
This parameter must be set to a value in the 0-0xFFFF range. */
u32 I2CClk; /*!< Specifies the I2C Bus Clock (in kHz). It is closely related to I2CSpdMod */
u32 I2CIPClk; /*!< Specifies the I2C IP Clock (in Hz). */
u32 I2CFilter; /*!< Specifies the I2C SCL/SDA Spike Filter. */
u32 I2CTxDMARqLv; /*!< Specifies the I2C TX DMA Empty Level. dma_tx_req signal is generated when
the number of valid data entries in the transmit FIFO is equal to or below the DMA
Transmit Data Level Register. The value of DMA Transmit Data Level Register is equal
to this value. This parameter must be set to a value in the 0-31 range. */
u32 I2CRxDMARqLv; /*!< Specifies the I2C RX DMA Full Level. dma_rx_req signal is generated when
the number of valid data entries in the transmit FIFO is equal to or above the DMA
Receive Data Level Register. The value of DMA Receive Data Level Register is equal to
this value+1. This parameter must be set to a value in the 0-31 range. */
u32 I2CDMAMod; /*!< Specifies the I2C DMA Mode.
This parameter can be a value of @ref I2C_DMA_Mode_definitions */
u32 I2CAckAddr1; /*!< Specifies the I2C Ack Address in I2C Slave1 Mode. I2C Slave1 only
support I2C_ADDR_7BIT mode. This parameter must be set to a value in the 0-127 range. */
}I2C_InitTypeDef;
/**
* @}
*/
/* Exported constants --------------------------------------------------------*/
/** @defgroup I2C_Exported_Constants I2C Exported Constants
* @{
*/
/** @defgroup I2C_Peripheral_definitions
* @{
*/
#define IS_I2C_ALL_PERIPH(PERIPH) (((PERIPH) == I2C0_DEV) || \
((PERIPH) == I2C1_DEV))
/**
* @}
*/
/** @defgroup I2C_Addr_Mode_definitions
* @{
*/
#define I2C_ADDR_7BIT ((u32)0x00000000)
#define I2C_ADDR_10BIT ((u32)0x00000001)
#define IS_I2C_ADDR_MODE(MODE) (((MODE) == I2C_ADDR_7BIT) || \
((MODE) == I2C_ADDR_10BIT))
/**
* @}
*/
/** @defgroup I2C_Speed_Mode_definitions
* @{
*/
#define I2C_SS_MODE ((u32)0x00000001)
#define I2C_FS_MODE ((u32)0x00000002)
#define I2C_HS_MODE ((u32)0x00000003)
#define IS_I2C_SPEED_MODE(MODE) (((MODE) == I2C_SS_MODE) || \
((MODE) == I2C_FS_MODE) || \
((MODE) == I2C_HS_MODE))
/**
* @}
*/
/** @defgroup I2C_Role_definitions
* @{
*/
#define I2C_SLAVE_MODE ((u32)0x00000000)
#define I2C_MASTER_MODE ((u32)0x00000001)
/**
* @}
*/
/** @defgroup I2C_DMA_Mode_definitions
* @{
*/
#define I2C_DMA_LEGACY ((u32)0x00000000)
#define I2C_DMA_REGISTER ((u32)0x00000001)
#define I2C_DMA_DESCRIPTOR ((u32)0x00000002)
#define IS_I2C_DMA_MODE(MODE) (((MODE) == I2C_DMA_LEGACY) || \
((MODE) == I2C_DMA_REGISTER) || \
((MODE) == I2C_DMA_DESCRIPTOR))
/**
* @}
*/
/** @defgroup I2C_DMA_DATA_LENGTH
* @{
*/
#define IS_I2C_DMA_DATA_LEN(LENGTH) ((LENGTH) <= 0xFF)
/**
* @}
*/
/**
* @}
*/
/* Exported functions --------------------------------------------------------*/
/** @defgroup I2C_Exported_Functions I2C Exported Functions
* @{
*/
/** @defgroup I2C_Exported_Normal_Functions I2C Exported Normal Functions
* @{
*/
_LONG_CALL_ void I2C_Init(I2C_TypeDef *I2Cx, I2C_InitTypeDef* I2C_InitStruct);
_LONG_CALL_ void I2C_Cmd(I2C_TypeDef *I2Cx, u8 NewState);
_LONG_CALL_ void I2C_ClearAllINT(I2C_TypeDef *I2Cx);
_LONG_CALL_ u32 I2C_GetRawINT(I2C_TypeDef *I2Cx);
_LONG_CALL_ u32 I2C_GetINT(I2C_TypeDef *I2Cx);
_LONG_CALL_ u8 I2C_CheckFlagState(I2C_TypeDef *I2Cx, u32 I2C_FLAG);
_LONG_CALL_ void I2C_INTConfig(I2C_TypeDef *I2Cx, u32 I2C_IT, u32 NewState);
_LONG_CALL_ void I2C_ClearINT(I2C_TypeDef *I2Cx, u32 INTrAddr);
_LONG_CALL_ void I2C_SetSpeed(I2C_TypeDef *I2Cx, u32 SpdMd, u32 I2Clk, u32 I2CIPClk);
_LONG_CALL_ void I2C_StructInit(I2C_InitTypeDef* I2C_InitStruct);
_LONG_CALL_ u8 I2C_ReceiveData(I2C_TypeDef *I2Cx);
_LONG_CALL_ void I2C_PinMuxInit(u8 I2CIdx, u8 PinMux);
_LONG_CALL_ void I2C_PinMuxDeInit(u8 I2CIdx, u8 PinMux);
/**
* @}
*/
/** @defgroup I2C_Exported_Master_Functions I2C Exported Master Functions
* @{
*/
_LONG_CALL_ void I2C_MasterSendNullData(I2C_TypeDef *I2Cx, u8* pBuf, u8 I2CCmd, u8 I2CStop, u8 I2CReSTR);
_LONG_CALL_ void I2C_MasterSend(I2C_TypeDef *I2Cx, u8* pBuf, u8 I2CCmd, u8 I2CStop, u8 I2CReSTR);
_LONG_CALL_ void I2C_MasterWrite(I2C_TypeDef *I2Cx, u8* pBuf, u8 len);
_LONG_CALL_ void I2C_MasterReadDW(I2C_TypeDef *I2Cx, u8* pBuf, u8 len);
_LONG_CALL_ u8 I2C_MasterRead(I2C_TypeDef *I2Cx, u8* pBuf, u8 len);
_LONG_CALL_ void I2C_MasterRepeatRead(I2C_TypeDef* I2Cx, u8* pWriteBuf, u8 Writelen, u8* pReadBuf, u8 Readlen);
_LONG_CALL_ void I2C_SetSlaveAddress(I2C_TypeDef *I2Cx, u16 Address);
/**
* @}
*/
/** @defgroup I2C_Exported_Slave_Functions I2C Exported Slave Functions
* @{
*/
_LONG_CALL_ void I2C_SlaveWrite(I2C_TypeDef *I2Cx, u8* pBuf, u8 len);
_LONG_CALL_ void I2C_SlaveRead(I2C_TypeDef *I2Cx, u8* pBuf, u8 len);
_LONG_CALL_ void I2C_SlaveSend(I2C_TypeDef *I2Cx, u8 Data);
/**
* @}
*/
/** @defgroup I2C_Exported_DMA_Functions I2C Exported DMA Functions
* @{
*/
_LONG_CALL_ void I2C_DMAControl(I2C_TypeDef *I2Cx, u32 DmaCtrl, u8 NewState);
_LONG_CALL_ void I2C_DmaMode1Config(I2C_TypeDef *I2Cx, u32 I2C_DmaCmd, u32 I2C_DmaBLen);
_LONG_CALL_ void I2C_DmaMode2Config(I2C_TypeDef *I2Cx, u32 I2C_DmaCmd, u32 I2C_DmaBLen);
_LONG_CALL_ BOOL I2C_TXGDMA_Init(u8 Index, GDMA_InitTypeDef *GDMA_InitStruct, void *CallbackData, IRQ_FUN CallbackFunc, u8 *pTxBuf, int TxCount);
_LONG_CALL_ BOOL I2C_RXGDMA_Init(u8 Index, GDMA_InitTypeDef *GDMA_InitStruct, void *CallbackData, IRQ_FUN CallbackFunc, u8 *pRxBuf, int RxCount);
/**
* @}
*/
/** @defgroup I2C_Exported_PowerSave_Functions I2C Exported PowerSave Functions
* @{
*/
_LONG_CALL_ void I2C_Sleep_Cmd(I2C_TypeDef *I2Cx, u32 NewStatus);
_LONG_CALL_ void I2C_WakeUp(I2C_TypeDef *I2Cx);
/**
* @}
*/
/**
* @}
*/
/* Registers Definitions --------------------------------------------------------*/
/**************************************************************************//**
* @defgroup I2C_Register_Definitions I2C Register Definitions
* @{
*****************************************************************************/
/**************************************************************************//**
* @defgroup IC_CON
* @{
*****************************************************************************/
#define BIT_CTRL_IC_CON_IC_SLAVE_DISABLE_1 ((u32)0x00000001 << 7)
#define BIT_CTRL_IC_CON_IC_SLAVE_DISABLE ((u32)0x00000001 << 6)
#define BIT_CTRL_IC_CON_IC_RESTART_EN ((u32)0x00000001 << 5)
#define BIT_CTRL_IC_CON_IC_10BITADDR_SLAVE ((u32)0x00000001 << 3)
#define BIT_CTRL_IC_CON_SPEED ((u32)0x00000003 << 1)
#define BIT_CTRL_IC_CON_MASTER_MODE ((u32)0x00000001)
/** @} */
/**************************************************************************//**
* @defgroup IC_TAR
* @{
*****************************************************************************/
#define BIT_CTRL_IC_TAR_IC_10BITADDR_MASTER ((u32)0x00000001 << 12)
#define BIT_CTRL_IC_TAR_SPECIAL ((u32)0x00000001 << 11)
#define BIT_CTRL_IC_TAR_GC_OR_START ((u32)0x00000001 << 10)
#define BIT_CTRL_IC_TAR ((u32)0x000003ff)
/** @} */
/**************************************************************************//**
* @defgroup IC_SAR
* @{
*****************************************************************************/
#define BIT_CTRL_IC_SAR ((u32)0x000003ff)
/** @} */
/**************************************************************************//**
* @defgroup IC_DATA_CMD
* @{
*****************************************************************************/
#define BIT_CTRL_IC_DATA_CMD_NULLDATA ((u32)0x00000001 << 11)
#define BIT_CTRL_IC_DATA_CMD_RESTART ((u32)0x00000001 << 10)
#define BIT_CTRL_IC_DATA_CMD_STOP ((u32)0x00000001 << 9)
#define BIT_CTRL_IC_DATA_CMD_CMD ((u32)0x00000001 << 8)
#define BIT_CTRL_IC_DATA_CMD_DAT ((u32)0x000000ff)
/** @} */
/**************************************************************************//**
* @defgroup IC_INTR_STAT
* @{
*****************************************************************************/
#define BIT_IC_INTR_STAT_R_DMA_I2C_DONE ((u32)0x00000001 << 15)
#define BIT_IC_INTR_STAT_R_ADDR_2_MATCH ((u32)0x00000001 << 13) /* refer to I2C Slave1 Address Match */
#define BIT_IC_INTR_STAT_R_ADDR_1_MATCH ((u32)0x00000001 << 12) /* refer to I2C Slave0 Address Match */
#define BIT_IC_INTR_STAT_R_GEN_CALL ((u32)0x00000001 << 11)
#define BIT_IC_INTR_STAT_R_START_DET ((u32)0x00000001 << 10)
#define BIT_IC_INTR_STAT_R_STOP_DET ((u32)0x00000001 << 9)
#define BIT_IC_INTR_STAT_R_ACTIVITY ((u32)0x00000001 << 8)
#define BIT_IC_INTR_STAT_R_RX_DONE ((u32)0x00000001 << 7)
#define BIT_IC_INTR_STAT_R_TX_ABRT ((u32)0x00000001 << 6)
#define BIT_IC_INTR_STAT_R_RD_REQ ((u32)0x00000001 << 5)
#define BIT_IC_INTR_STAT_R_TX_EMPTY ((u32)0x00000001 << 4)
#define BIT_IC_INTR_STAT_R_TX_OVER ((u32)0x00000001 << 3)
#define BIT_IC_INTR_STAT_R_RX_FULL ((u32)0x00000001 << 2)
#define BIT_IC_INTR_STAT_R_RX_OVER ((u32)0x00000001 << 1)
#define BIT_IC_INTR_STAT_R_RX_UNDER ((u32)0x00000001)
/** @} */
/**************************************************************************//**
* @defgroup IC_INTR_MASK
* @{
*****************************************************************************/
#define BIT_IC_INTR_MASK_M_DMA_I2C_DONE ((u32)0x00000001 << 15)
#define BIT_IC_INTR_MASK_M_ADDR_2_MATCH ((u32)0x00000001 << 13) /* refer to I2C Slave1 Address Match */
#define BIT_IC_INTR_MASK_M_ADDR_1_MATCH ((u32)0x00000001 << 12) /* refer to I2C Slave0 Address Match */
#define BIT_IC_INTR_MASK_M_GEN_CALL ((u32)0x00000001 << 11)
#define BIT_IC_INTR_MASK_M_START_DET ((u32)0x00000001 << 10)
#define BIT_IC_INTR_MASK_M_STOP_DET ((u32)0x00000001 << 9)
#define BIT_IC_INTR_MASK_M_ACTIVITY ((u32)0x00000001 << 8)
#define BIT_IC_INTR_MASK_M_RX_DONE ((u32)0x00000001 << 7)
#define BIT_IC_INTR_MASK_M_TX_ABRT ((u32)0x00000001 << 6)
#define BIT_IC_INTR_MASK_M_RD_REQ ((u32)0x00000001 << 5)
#define BIT_IC_INTR_MASK_M_TX_EMPTY ((u32)0x00000001 << 4)
#define BIT_IC_INTR_MASK_M_TX_OVER ((u32)0x00000001 << 3)
#define BIT_IC_INTR_MASK_M_RX_FULL ((u32)0x00000001 << 2)
#define BIT_IC_INTR_MASK_M_RX_OVER ((u32)0x00000001 << 1)
#define BIT_IC_INTR_MASK_M_RX_UNDER ((u32)0x00000001)
/** @} */
/**************************************************************************//**
* @defgroup IC_RAW_INTR_STAT
* @{
*****************************************************************************/
#define BIT_IC_RAW_INTR_STAT_DMA_I2C_DONE ((u32)0x00000001 << 15)
#define BIT_IC_RAW_INTR_STAT_ADDR_2_MATCH ((u32)0x00000001 << 13) /* refer to I2C Slave1 Address Match */
#define BIT_IC_RAW_INTR_STAT_ADDR_1_MATCH ((u32)0x00000001 << 12) /* refer to I2C Slave0 Address Match */
#define BIT_IC_RAW_INTR_STAT_GEN_CALL ((u32)0x00000001 << 11)
#define BIT_IC_RAW_INTR_STAT_START_DET ((u32)0x00000001 << 10)
#define BIT_IC_RAW_INTR_STAT_STOP_DET ((u32)0x00000001 << 9)
#define BIT_IC_RAW_INTR_STAT_ACTIVITY ((u32)0x00000001 << 8)
#define BIT_IC_RAW_INTR_STAT_RX_DONE ((u32)0x00000001 << 7)
#define BIT_IC_RAW_INTR_STAT_TX_ABRT ((u32)0x00000001 << 6)
#define BIT_IC_RAW_INTR_STAT_RD_REQ ((u32)0x00000001 << 5)
#define BIT_IC_RAW_INTR_STAT_TX_EMPTY ((u32)0x00000001 << 4)
#define BIT_IC_RAW_INTR_STAT_TX_OVER ((u32)0x00000001 << 3)
#define BIT_IC_RAW_INTR_STAT_RX_FULL ((u32)0x00000001 << 2)
#define BIT_IC_RAW_INTR_STAT_RX_OVER ((u32)0x00000001 << 1)
#define BIT_IC_RAW_INTR_STAT_RX_UNDER ((u32)0x00000001)
/** @} */
/**************************************************************************//**
* @defgroup IC_ENABLE
* @{
*****************************************************************************/
#define BIT_CTRL_IC_ENABLE ((u32)0x00000001)
/** @} */
/**************************************************************************//**
* @defgroup IC_STATUS
* @{
*****************************************************************************/
#define BIT_IC_STATUS_BUS_BUSY ((u32)0x00000001 << 7)
#define BIT_IC_STATUS_SLV_ACTIVITY ((u32)0x00000001 << 6)
#define BIT_IC_STATUS_MST_ACTIVITY ((u32)0x00000001 << 5)
#define BIT_IC_STATUS_RFF ((u32)0x00000001 << 4)
#define BIT_IC_STATUS_RFNE ((u32)0x00000001 << 3)
#define BIT_IC_STATUS_TFE ((u32)0x00000001 << 2)
#define BIT_IC_STATUS_TFNF ((u32)0x00000001 << 1)
#define BIT_IC_STATUS_ACTIVITY ((u32)0x00000001)
/** @} */
/**************************************************************************//**
* @defgroup IC_SDA_HOLD
* @{
*****************************************************************************/
#define BIT_CTRL_IC_SDA_HOLD ((u32)0x0000ffff)
/** @} */
/**************************************************************************//**
* @defgroup IC_TX_ABRT_SOURCE
* @{
*****************************************************************************/
#define BIT_IC_TX_ABRT_SOURCE_ABRT_SLVRD_INTX ((u32)0x00000001 << 15)
#define BIT_IC_TX_ABRT_SOURCE_ABRT_SLV_ARBLOST ((u32)0x00000001 << 14)
#define BIT_IC_TX_ABRT_SOURCE_ABRT_SLVFLUSH_TXFIFO ((u32)0x00000001 << 13)
#define BIT_IC_TX_ABRT_SOURCE_ARB_LOST ((u32)0x00000001 << 12)
#define BIT_IC_TX_ABRT_SOURCE_ABRT_MASTER_DIS ((u32)0x00000001 << 11)
#define BIT_IC_TX_ABRT_SOURCE_ABRT_10B_RD_NORSTRT ((u32)0x00000001 << 10)
#define BIT_IC_TX_ABRT_SOURCE_ABRT_SBYTE_NORSTRT ((u32)0x00000001 << 9)
#define BIT_IC_TX_ABRT_SOURCE_ABRT_HS_NORSTRT ((u32)0x00000001 << 8)
#define BIT_IC_TX_ABRT_SOURCE_ABRT_SBYTE_ACKDET ((u32)0x00000001 << 7)
#define BIT_IC_TX_ABRT_SOURCE_ABRT_HS_ACKDET ((u32)0x00000001 << 6)
#define BIT_IC_TX_ABRT_SOURCE_ABRT_GCALL_READ ((u32)0x00000001 << 5)
#define BIT_IC_TX_ABRT_SOURCE_ABRT_GCALL_NOACK ((u32)0x00000001 << 4)
#define BIT_IC_TX_ABRT_SOURCE_ABRT_TXDATA_NOACK ((u32)0x00000001 << 3)
#define BIT_IC_TX_ABRT_SOURCE_ABRT_10ADDR2_NOACK ((u32)0x00000001 << 2)
#define BIT_IC_TX_ABRT_SOURCE_ABRT_10ADDR1_NOACK ((u32)0x00000001 << 1)
#define BIT_IC_TX_ABRT_SOURCE_ABRT_7B_ADDR_NOACK ((u32)0x00000001)
/** @} */
/**************************************************************************//**
* @defgroup IC_SLV_DATA_NACK_ONLY
* @{
*****************************************************************************/
#define BIT_CTRL_IC_SLV_DATA_NACK_ONLY ((u32)0x00000001)
/** @} */
/**************************************************************************//**
* @defgroup IC_DMA_CR
* @{
*****************************************************************************/
#define BIT_IC_DMA_CR_TDMAE ((u32)0x00000001 << 1)
#define BIT_IC_DMA_CR_RDMAE ((u32)0x00000001)
/** @} */
/**************************************************************************//**
* @defgroup IC_SDA_SETUP
* @{
*****************************************************************************/
#define BIT_CTRL_IC_SDA_SETUP ((u32)0x000000ff)
/** @} */
/**************************************************************************//**
* @defgroup IC_ACK_GENERAL_CALL
* @{
*****************************************************************************/
#define BIT_CTRL_IC_ACK_GENERAL_CALL ((u32)0x00000001)
/** @} */
/**************************************************************************//**
* @defgroup IC_DMA_CMD
* @{
*****************************************************************************/
#define BIT_IC_DMA_CMD_RESTART ((u32)0x00000001 << 7)
#define BIT_IC_DMA_CMD_STOP ((u32)0x00000001 << 6)
#define BIT_IC_DMA_CMD_RW ((u32)0x00000001 << 5) /* 0 is write, 1 is read */
#define BIT_IC_DMA_CMD_ENABLE ((u32)0x00000001) /* HW auto clear after transfer done */
/** @} */
/**************************************************************************//**
* @defgroup IC_DMA_MOD
* @{
*****************************************************************************/
#define BIT_IC_DMA_MOD ((u32)0x00000003)
/** @} */
/**************************************************************************//**
* @defgroup IC_SLEEP
* @{
*****************************************************************************/
#define BIT_IC_SLEEP_CLOCK_GATED ((u32)0x00000001 << 1)
#define BIT_IC_SLEEP_CLOCK_CONTROL ((u32)0x00000001)
/** @} */
/**************************************************************************//**
* @defgroup IC_FILTER
* @{
*****************************************************************************/
#define BIT_IC_FILTER_DIG_FLTR_SEL ((u32)0x00000001 << 8)
#define BIT_CTRL_IC_FILTER_DIG_FLTR_DEG ((u32)0x0000000F)
/** @} */
/**************************************************************************//**
* @defgroup IC_SAR1
* @{
*****************************************************************************/
#define BIT_CTRL_IC_SAR1 ((u32)0x0000007F)
/** @} */
/** @} */
/**
* @}
*/
/**
* @}
*/
/* Other Definitions --------------------------------------------------------*/
//I2C Timing Parameters
#define I2C_SS_MIN_SCL_HTIME 4000 //the unit is ns.
#define I2C_SS_MIN_SCL_LTIME 4700 //the unit is ns.
#define I2C_FS_MIN_SCL_HTIME 600 //the unit is ns.
#define I2C_FS_MIN_SCL_LTIME 1300 //the unit is ns.
#define I2C_HS_MIN_SCL_HTIME_100 60 //the unit is ns, with bus loading = 100pf
#define I2C_HS_MIN_SCL_LTIME_100 120 //the unit is ns., with bus loading = 100pf
#define I2C_HS_MIN_SCL_HTIME_400 160 //the unit is ns, with bus loading = 400pf
#define I2C_HS_MIN_SCL_LTIME_400 320 //the unit is ns., with bus loading = 400pf
typedef struct
{
I2C_TypeDef* I2Cx;
u32 Tx_HandshakeInterface;
u32 Rx_HandshakeInterface;
IRQn_Type IrqNum;
} I2C_DevTable;
extern const I2C_DevTable I2C_DEV_TABLE[2];
extern u32 I2C_SLAVEWRITE_PATCH;
extern u32 IC_FS_SCL_HCNT_TRIM;
extern u32 IC_FS_SCL_LCNT_TRIM;
#endif
/******************* (C) COPYRIGHT 2016 Realtek Semiconductor *****END OF FILE****/

View file

@ -0,0 +1,356 @@
/**
******************************************************************************
* @file rtl8711b_i2s.h
* @author
* @version V1.0.0
* @date 2016-05-17
* @brief This file contains all the functions prototypes for the I2S firmware
* library.
******************************************************************************
* @attention
*
* This module is a confidential and proprietary property of RealTek and
* possession or use of this module requires written permission of RealTek.
*
* Copyright(c) 2016, Realtek Semiconductor Corporation. All rights reserved.
******************************************************************************
*/
#ifndef _RTL8710B_I2S_H_
#define _RTL8710B_I2S_H_
/** @addtogroup AmebaZ_Periph_Driver
* @{
*/
/** @defgroup I2S
* @brief I2S driver modules
* @{
*/
/** @addtogroup I2S
* @verbatim
*****************************************************************************************
* Introduction
*****************************************************************************************
* I2S:
* - Base Address: I2S_DEV
* - Source clk: 22.579MHz or 24.576MHz(default)
* - Sample rate: 8K, 16K, 24K, 32K, 48K, 96K, 7.35K, 14.7K, 22.05K, 29.4K, 44.1K, 88.2K
* - Sample bit: 16 bit, 24 bit
* - Page num & page size: Max page_num=4, Max page_size=16K byte
* - IRQ: I2S0_PCM0_IRQ
*
*****************************************************************************************
* PINMUX
*****************************************************************************************
* I2S:
* - S0: _PA_18(mck)/_PA_19(tx)/_PA_20(rx)/_PA_21(clk)/_PA_22(ws).
* - S1: _PB_4(mck)/_PB_5(tx)/_PB_6(ws)/_PA_31(clk)/_PA_24(rx).
*
*****************************************************************************************
* How to use I2S
*****************************************************************************************
* To use I2S peripheral, the following steps are mandatory:
*
* 1. Enable I2S power:
* LXBUS_FCTRL(ON).
*
* 2. Enable the I2S interface clock using
* RCC_PeriphClockCmd(APBPeriph_I2S0, APBPeriph_I2S0_CLOCK, ENABLE);
*
* 3. I2S pinmux:
* Pinmux_Config(Pin_Num, PINMUX_FUNCTION_I2S).
*
* 4. Fill the I2S_InitStruct with the desired parameters.
*
* 5. configure I2S with the corresponding configuration.
* I2S_Init(I2S_DEV, &I2S_Adapter.I2SInitStruct)
*
* 6. Activate the I2S peripheral:
* I2S_Cmd(I2S_DEV, ENABLE).
*
* 7. Configure interrupts:
* I2S_INTConfig()
*
* @note All other functions can be used separately to modify, if needed,
* a specific feature of the I2S
*****************************************************************************************
* @endverbatim
*/
/* Exported types ------------------------------------------------------------*/
/** @defgroup I2S_Exported_Types I2S Exported Types
* @{
*/
/**
* @brief I2S Init structure definition
*/
typedef struct {
u32 I2S_SlaveMode; /*!< Specifies the I2S operating mode
This parameter can be a value of @ref I2S_device_mode */
u32 I2S_WordLen; /*!< Specifies the I2S word length
This parameter can be a value of @ref I2S_word_length */
u32 I2S_Justify; /*!< Specifies the I2S digital interface format
This parameter can be a value of @ref I2S_format */
u32 I2S_EndianSwap; /*!< Specifies the I2S endian mode
This parameter can be a value of @ref I2S_endian_swap */
u32 I2S_ChNum; /*!< Specifies the I2S channel number
This parameter can be a value of @ref I2S_channel_number */
u32 I2S_PageNum; /*!< Specifies the I2S page number
This parameter must be set to a value in the 2~4 range */
u32 I2S_PageSize; /*!< Specifies the I2S page size
This parameter must be set to a value in the 1~4096 Word range */
u32 I2S_Rate; /*!< Specifies the I2S sample rate
This parameter can be a value of @ref I2S_sample_rate */
u32 I2S_TRxAct; /*!< Specifies the I2S transfer direction
This parameter can be a value of @ref I2S_direction */
u32 I2S_InterLoopback;/*!< Specifies the I2S internal/external loopback
This parameter must be set to a value 0(external) or 1(internal) */
} I2S_InitTypeDef;
/**
* @}
*/
/* Exported constants --------------------------------------------------------*/
/** @defgroup I2S_Exported_Constants I2S Exported Constants
* @{
*/
/** @defgroup I2S_device_mode I2S Device Mode
* @{
*/
#define I2S_MASTER_MODE ((u32)0x00000000)
#define I2S_SLAVE_MODE ((u32)0x00000001)
#define IS_I2S_MODE(MODE) (((MODE) == I2S_MASTER_MODE) || \
((MODE) == I2S_SLAVE_MODE))
/**
* @}
*/
/** @defgroup I2S_word_length I2S Word Length
* @{
*/
#define I2S_WL_16 ((u32)0x00000000)
#define I2S_WL_24 ((u32)0x00000001)
#define IS_I2S_WORD_LEN(LEN) (((LEN) == I2S_WL_16) || \
((LEN) == I2S_WL_24))
/**
* @}
*/
/** @defgroup I2S_format I2S Interface Format
* @{
*/
#define I2S_JY_I2S ((u32)0x00000000)
#define I2S_JY_LEFT ((u32)0x00000001)
#define I2S_JY_RIGHT ((u32)0x00000002)
#define IS_I2S_JUSTIFY(FORMAT) (((FORMAT) == I2S_JY_I2S) || \
((FORMAT) == I2S_JY_LEFT) || \
((FORMAT) == I2S_JY_RIGHT))
/**
* @}
*/
/** @defgroup I2S_endian_swap I2S Endian Swap
* @{
*/
#define I2S_ES_LITTLE ((u32)0x00000000)
#define I2S_ES_BIG ((u32)0x00000001)
#define IS_I2S_ENDIAN_SWAP(SWAP) (((SWAP) == I2S_ES_LITTLE) || \
((SWAP) == I2S_ES_BIG))
/**
* @}
*/
/** @defgroup I2S_direction I2S Bus Direction(Transmit/Receive)
* @{
*/
#define I2S_ONLY_RX ((u32)0x00000000)
#define I2S_ONLY_TX ((u32)0x00000001)
#define I2S_TXRX ((u32)0x00000002)
#define IS_I2S_DIR(DIR) (((DIR) == I2S_ONLY_RX) || \
((DIR) == I2S_ONLY_TX) || \
((DIR) == I2S_TXRX))
/**
* @}
*/
/** @defgroup I2S_channel_number I2S Channel Number
* @{
*/
#define I2S_CH_STEREO ((u32)0x00000000)
#define I2S_CH_RSVD ((u32)0x00000001)
#define I2S_CH_MONO ((u32)0x00000002)
#define IS_I2S_CHN_NUM(NUM) (((NUM) == I2S_CH_STEREO) || \
((NUM) == I2S_CH_MONO))
/**
* @}
*/
/** @defgroup I2S_sample_rate I2S Sample Rate
* @{
*/
#define I2S_SR_8KHZ ((u32)0x00000000)
#define I2S_SR_16KHZ ((u32)0x00000001)
#define I2S_SR_24KHZ ((u32)0x00000002)
#define I2S_SR_32KHZ ((u32)0x00000003)
#define I2S_SR_48KHZ ((u32)0x00000005)
#define I2S_SR_96KHZ ((u32)0x00000006)
#define I2S_SR_7p35KHZ ((u32)0x00000010)
#define I2S_SR_14p7KHZ ((u32)0x00000011)
#define I2S_SR_22p05KHZ ((u32)0x00000012)
#define I2S_SR_29p4KHZ ((u32)0x00000013)
#define I2S_SR_44p1KHZ ((u32)0x00000015)
#define I2S_SR_88p2KHZ ((u32)0x00000016)
#define IS_I2S_SAMPLE_RATE(RATE) (((RATE) == I2S_SR_8KHZ) || \
((RATE) == I2S_SR_16KHZ) || \
((RATE) == I2S_SR_24KHZ) || \
((RATE) == I2S_SR_32KHZ) || \
((RATE) == I2S_SR_48KHZ) || \
((RATE) == I2S_SR_96KHZ) || \
((RATE) == I2S_SR_7p35KHZ) || \
((RATE) == I2S_SR_14p7KHZ) || \
((RATE) == I2S_SR_22p05KHZ) || \
((RATE) == I2S_SR_29p4KHZ) || \
((RATE) == I2S_SR_44p1KHZ) || \
((RATE) == I2S_SR_88p2KHZ))
/**
* @}
*/
/**
* @}
*/
/** @defgroup I2S_Exported_Functions I2S Exported Functions
* @{
*/
_LONG_CALL_ void I2S_Init(I2S_TypeDef* I2Sx, I2S_InitTypeDef* I2S_InitStruct);
_LONG_CALL_ void I2S_Cmd(I2S_TypeDef* I2Sx, u8 NewState);
_LONG_CALL_ void I2S_INTConfig(I2S_TypeDef* I2Sx, u32 I2STxIntrMSK, u32 I2SRxIntrMSK);
_LONG_CALL_ void I2S_SetRate(I2S_TypeDef* I2Sx, u32 I2S_Rate);
_LONG_CALL_ void I2S_SetWordLen(I2S_TypeDef* I2Sx, u32 I2S_WordLen);
_LONG_CALL_ void I2S_SetChNum(I2S_TypeDef* I2Sx, u32 I2S_ChNum);
_LONG_CALL_ void I2S_SetPageNum(I2S_TypeDef* I2Sx, u32 I2S_PageNum);
_LONG_CALL_ void I2S_SetPageSize(I2S_TypeDef* I2Sx, u32 I2S_PageSize);
_LONG_CALL_ void I2S_SetDirection(I2S_TypeDef* I2Sx, u32 I2S_TRxAct);
_LONG_CALL_ void I2S_INTClear(I2S_TypeDef* I2Sx, u32 I2STxIntrClr, u32 I2SRxIntrClr);
_LONG_CALL_ void I2S_INTClearAll(I2S_TypeDef* I2Sx);
_LONG_CALL_ void I2S_ISRGet(I2S_TypeDef* I2Sx, u32* I2STxIsr, u32* I2SRxIsr);
_LONG_CALL_ void I2S_SetDMABuf(I2S_TypeDef* I2Sx, u8 *I2STxData, u8 *I2SRxData);
_LONG_CALL_ u32 I2S_GetTxPage(I2S_TypeDef* I2Sx);
_LONG_CALL_ void I2S_TxPageDMA_EN(I2S_TypeDef* I2Sx, u32 I2STxIdx);
_LONG_CALL_ void I2S_RxPageDMA_EN(I2S_TypeDef* I2Sx, u32 I2SRxIdx);
_LONG_CALL_ void I2S_TxDmaCmd(I2S_TypeDef* I2Sx, u32 NewState);
_LONG_CALL_ void I2S_RxDmaCmd(I2S_TypeDef* I2Sx, u32 NewState);
/**
* @}
*/
/* Registers Definitions --------------------------------------------------------*/
/**************************************************************************//**
* @defgroup I2S_Register_Definitions I2S Register Definitions
* @{
*****************************************************************************/
/**************************************************************************//**
* @defgroup I2S_CONTROL
* @{
*****************************************************************************/
#define BIT_CTRL_CTLX_I2S_EN ((u32)0x00000001 << 0)
#define BIT_CTRL_CTLX_I2S_TX_ACT_MASK ((u32)0x00000003 << 1)
#define BIT_CTRL_CTLX_I2S_CHN_NUM_MASK ((u32)0x00000003 << 3)
#define BIT_CTRL_CTLX_I2S_WORD_LEN_MASK ((u32)0x00000001 << 6)
#define BIT_CTRL_CTLX_I2S_INTERNAL ((u32)0x00000001 << 7)
#define BIT_CTRL_CTLX_I2S_ENDIAN_SWAP ((u32)0x00000001 << 12)
#define BIT_CTRL_CTLX_I2S_CLK_SRC ((u32)0x00000001 << 30)
#define BIT_CTRL_CTLX_I2S_SW_RSTN ((u32)0x00000001 << 31)
/** @} */
/**************************************************************************//**
* @defgroup I2S_SETTING
* @{
*****************************************************************************/
#define BIT_SETTING_I2S_PAGE_SIZE_MASK ((u32)0x00000FFF)
#define BIT_SETTING_I2S_PAGE_NUM_MASK ((u32)0x00000003 << 12)
#define BIT_SETTING_I2S_RATE_MASK ((u32)0x00000007 << 14)
/** @} */
/**************************************************************************//**
* @defgroup I2S_TX_INT_MASK or STATUS
* @{
*****************************************************************************/
#define I2S_TX_INT_PAGE0_OK ((u32)0x00000001 << 0)
#define I2S_TX_INT_PAGE1_OK ((u32)0x00000001 << 1)
#define I2S_TX_INT_PAGE2_OK ((u32)0x00000001 << 2)
#define I2S_TX_INT_PAGE3_OK ((u32)0x00000001 << 3)
#define I2S_TX_INT_PAGE0_UNAVA ((u32)0x00000001 << 4)
#define I2S_TX_INT_PAGE1_UNAVA ((u32)0x00000001 << 5)
#define I2S_TX_INT_PAGE2_UNAVA ((u32)0x00000001 << 6)
#define I2S_TX_INT_PAGE3_UNAVA ((u32)0x00000001 << 7)
#define I2S_TX_INT_EMPTY ((u32)0x00000001 << 8)
/** @} */
/**************************************************************************//**
* @defgroup I2S_RX_INT_MASK or STATUS
* @{
*****************************************************************************/
#define I2S_RX_INT_PAGE0_OK ((u32)0x00000001 << 0)
#define I2S_RX_INT_PAGE1_OK ((u32)0x00000001 << 1)
#define I2S_RX_INT_PAGE2_OK ((u32)0x00000001 << 2)
#define I2S_RX_INT_PAGE3_OK ((u32)0x00000001 << 3)
#define I2S_RX_INT_PAGE0_UNAVA ((u32)0x00000001 << 4)
#define I2S_RX_INT_PAGE1_UNAVA ((u32)0x00000001 << 5)
#define I2S_RX_INT_PAGE2_UNAVA ((u32)0x00000001 << 6)
#define I2S_RX_INT_PAGE3_UNAVA ((u32)0x00000001 << 7)
#define I2S_RX_INT_FULL ((u32)0x00000001 << 8)
/** @} */
/**************************************************************************//**
* @defgroup I2S_TX_OWN or RX_PAGE_OWN
* @{
*****************************************************************************/
#define BIT_IS_PAGE_OWN ((u32)0x80000000)
/** @} */
/** @} */
/**
* @}
*/
/**
* @}
*/
#endif /* _RTL8710B_I2S_H_ */
/******************* (C) COPYRIGHT 2016 Realtek Semiconductor *****END OF FILE****/

View file

@ -0,0 +1,134 @@
/**
******************************************************************************
* @file rtl8711b_otf.h
* @author
* @version V1.0.0
* @date 2016-05-17
* @brief This file contains all the functions prototypes for the flash run time decrypt firmware
* library.
******************************************************************************
* @attention
*
* This module is a confidential and proprietary property of RealTek and
* possession or use of this module requires written permission of RealTek.
*
* Copyright(c) 2015, Realtek Semiconductor Corporation. All rights reserved.
******************************************************************************
*/
#ifndef _RTL8711B_OTF_H_
#define _RTL8711B_OTF_H_
/** @addtogroup AmebaZ_Platform
* @{
*/
/** @defgroup PROTECTION
* @brief PROTECTION driver modules
* @{
*/
/** @addtogroup PROTECTION
* @verbatim
*****************************************************************************************
* RSIP(OTF) Introduction
*****************************************************************************************
* -used for flash firmware protection, and flash firmware will be encrypted use AES.
* -16B KEY shoud be written to EFUSE OTP KEY area use EFUSE_OTF_KEY.
* -Enable should be write to EFUSE 0x19[5].
*****************************************************************************************
* RDP Introduction
*****************************************************************************************
* -after enable RDP, top 4k RAM can not be read.
* -16B RDP key should be written to EFUSE RDP key area use EFUSE_RDP_KEY.
* -Enable bit should be write to EFUSE use EFUSE_RDP_EN.
*****************************************************************************************
* @endverbatim
*/
/* Exported constants --------------------------------------------------------*/
/** @defgroup PROTECTION_Exported_Constants OTF Exported Constants
* @{
*/
#define OTF_LENGTH_UNIT 4096
/**
* @}
*/
/* Exported functions --------------------------------------------------------*/
/** @defgroup PROTECTION_Exported_Functions OTF Exported Functions
* @{
*/
_LONG_CALL_ void OTF_init(u8* IV);
_LONG_CALL_ void OTF_Cmd(u32 NewStatus);
_LONG_CALL_ void OTF_Mask(u32 MaskIdx, u32 Addr, u32 Len, u32 NewStatus);
_LONG_CALL_ u32 KEY_Request(u32 KeyTypeBit);
_LONG_CALL_ u32 RDP_EN_Request(void);
/**
* @}
*/
/* Registers Definitions --------------------------------------------------------*/
/**************************************************************************//**
* @defgroup OTF_Register_Definitions OTF Register Definitions
* @{
*****************************************************************************/
/**************************************************************************//**
* @defgroup OTF_DEC
* @{
*****************************************************************************/
#define REG_SYS_OTF_DEC_CTRL 0x02D8
#define REG_SYS_OTF_DEC_ADDR_MASK0 0x02DC
#define REG_SYS_OTF_DEC_ADDR_MASK1 0x02E4
#define REG_SYS_OTF_DEC_ADDR_MASK2 0x02E8
#define REG_SYS_OTF_DEC_ADDR_MASK3 0x02EC
#define REG_SYS_OTF_DEC_IV_EXT 0x02F0
/** @} */
/**************************************************************************//**
* @defgroup REG_SYS_OTF_DEC_CTRL
* @{
*****************************************************************************/
#define OTF_FEN_OTFDEC ((u32)0x00000001) /*!<function enable of OTF decoder */
#define OTF_DEC_IV_BYTE_SWAP ((u32)0x00000002) /*!<Big/little endian conversion for input OTF IV */
#define OTF_DEC_KEY_BYTE_SWAP ((u32)0x00000004) /*!<Big/little endian conversion for input OTF KEY*/
#define OTF_DEC_CIPHER_BYTE_SWAP ((u32)0x00000008) /*!Big/little endian conversion for calculated cipher*/
/** @} */
/**************************************************************************//**
* @defgroup OTF_DEC_ADDR_MASK
* @{
*****************************************************************************/
#define OTF_DEC_MASK_EN ((u32)0x00000001) /*!<Decoder mask enable for address~address+length */
#define OTF_DEC_MASK_SA ((u32)0x01FFFFFE) /*!<Start address for decoder mask, unit is byte */
#define OTF_DEC_MASK_LEN ((u32)0xFE000000) /*!<Address range for decoder mask, unit is 4KB */
/** @} */
/**************************************************************************//**
* @defgroup RDP_ERROR_STATUS
* @{
*****************************************************************************/
#define RDP_SYSTEMBIN_WRONG ((u32)0x00000001) /*!<system.bin not load to flash */
#define RDP_RDPBIN_WRONG ((u32)0x00000002) /*!<rdp.bin not load to flash */
#define RDP_KEY_REQUEST_TIMEOUT ((u32)0x00000003) /*!<Key request timeout */
#define RDP_NOT_ENABLE ((u32)0x00000004) /*!<RDP not enable in efuse */
#define RDP_CHECKSUM_ERROR ((u32)0x00000005) /*!<Check sum error */
/** @} */
/** @} */
/**
* @}
*/
/**
* @}
*/
/* Other definations --------------------------------------------------------*/
#define KEY_REQ_POLL_TIMES 0xFF
#endif
/******************* (C) COPYRIGHT 2016 Realtek Semiconductor *****END OF FILE****/

View file

@ -0,0 +1,177 @@
#ifndef __INC_RTL8710B_PERI_ON_H
#define __INC_RTL8710B_PERI_ON_H
#define MASK_ALLON 0xFFFFFFFF
#define HAL_PERI_ON_READ32(addr) HAL_READ32(PERI_ON_BASE, addr)
#define HAL_PERI_ON_WRITE32(addr, value) HAL_WRITE32(PERI_ON_BASE, addr, value)
#define HAL_PERL_ON_FUNC_CTRL(addr,value,ctrl) \
HAL_PERI_ON_WRITE32(addr, ((HAL_PERI_ON_READ32(addr) & (~value))|((MASK_ALLON - ctrl + 1) & value)))
//2 0x200 REG_PEON_PWR_CTRL
#define BIT_SOC_UAHV_EN BIT(2)
#define BIT_SOC_UALV_EN BIT(1)
#define BIT_SOC_USBD_EN BIT(0)
//2 0x210 REG_SOC_FUNC_EN
#define BIT_SOC_BOOT_FROM_JTAG BIT(31)
#define BIT_SOC_UNLOCK_FROM_JTAG BIT(30)
#define BIT_SOC_WAKE_FROM_PS BIT(29)
#define BIT_SOC_PATCH_FUNC0 BIT(28)
#define BIT_SOC_PATCH_FUNC1 BIT(27)
#define BIT_SOC_PATCH_FUNC2 BIT(26)
#define BIT_SOC_XMODEM_PAGE_PG BIT(25)
#define BIT_SOC_XMODEM_FLASH_EMPTY BIT(24)
#define BIT_SOC_SECURITY_ENGINE_EN BIT(20)
#define BIT_SOC_GTIMER_EN BIT(16)
#define BIT_SOC_GDMA1_EN BIT(14)
#define BIT_SOC_GDMA0_EN BIT(13)
#define BIT_SOC_LOG_UART_EN BIT(12)
#define BIT_SOC_CPU_EN BIT(8)
#define BIT_SOC_MEM_CTRL_EN BIT(6)
#define BIT_SOC_FLASH_EN BIT(4)
#define BIT_SOC_LXBUS_EN BIT(2)
#define BIT_SOC_OCP_EN BIT(1)
#define BIT_SOC_FUN_EN BIT(0)
#define LXBUS_FCTRL(ctrl) HAL_PERL_ON_FUNC_CTRL(REG_SOC_FUNC_EN, BIT_SOC_LXBUS_EN, ctrl)
//2 0x0214 REG_SOC_HCI_COM_FUNC_EN
#define BIT_SOC_HCI_WL_MACON_EN BIT(16)
#define BIT_SOC_HCI_SM_SEL BIT(13)
#define BIT_SOC_HCI_OTG_RST_MUX BIT(5)
#define BIT_SOC_HCI_OTG_EN BIT(4)
#define BIT_SOC_HCI_SDIOD_ON_RST_MUX BIT(3)
#define BIT_SOC_HCI_SDIOD_OFF_EN BIT(1)
#define BIT_SOC_HCI_SDIOD_ON_EN BIT(0)
#define WL_MACON_FCTRL(ctrl) HAL_PERL_ON_FUNC_CTRL(REG_SOC_HCI_COM_FUNC_EN, BIT_SOC_HCI_WL_MACON_EN, ctrl)
#define SDIOD_OFF_FCTRL(ctrl) HAL_PERL_ON_FUNC_CTRL(REG_SOC_HCI_COM_FUNC_EN, BIT_SOC_HCI_SDIOD_OFF_EN, ctrl)
//2 0x0218 REG_SOC_PERI_FUNC0_EN
#define BIT_PERI_I2S0_EN BIT(24)
#define BIT_PERI_I2C1_EN BIT(17)
#define BIT_PERI_I2C0_EN BIT(16)
#define BIT_PERI_SPI1_EN BIT(9)
#define BIT_PERI_SPI0_EN BIT(8)
#define BIT_PERI_UART2_EN BIT(2)
#define BIT_PERI_UART1_EN BIT(1)
#define BIT_PERI_UART0_EN BIT(0)
//2 0x021C REG_SOC_PERI_FUNC1_EN
#define BIT_PERI_GPIO_EN BIT(8)
#define BIT_PERI_ADC0_EN BIT(0)
//2 0x0220 REG_SOC_PERI_BD_FUNC0_EN
#define BIT_PERI_UART2_BD_EN BIT(2)
#define BIT_PERI_UART1_BD_EN BIT(1)
#define BIT_PERI_UART0_BD_EN BIT(0)
//2 0x0230 REG_PESOC_CLK_CTRL
#define BIT_SOC_SLPCK_BTCMD_EN BIT(29)
#define BIT_SOC_ACTCK_BTCMD_EN BIT(28)
#define BIT_SOC_ACTCK_GPIO_EN BIT(24)
#define BIT_SOC_ACTCK_GDMA1_EN BIT(18)
#define BIT_SOC_ACTCK_GDMA0_EN BIT(16)
#define BIT_SOC_ACTCK_TIMER_EN BIT(14)
#define BIT_SOC_ACTCK_LOG_UART_EN BIT(12)
#define BIT_SOC_ACTCK_FLASH_EN BIT(8)
#define BIT_SOC_ACTCK_VENDOR_REG_EN BIT(6)
#define BIT_SOC_ACTCK_TRACE_EN BIT(4)
#define BIT_SOC_CKE_PLFM BIT(2)
#define BIT_SOC_CKE_OCP BIT(0)
//2 0x0234 REG_PESOC_PERI_CLK_CTRL0
#define BIT_SOC_ACTCK_SPI1_EN BIT(18)
#define BIT_SOC_ACTCK_SPI0_EN BIT(16)
#define BIT_SOC_ACTCK_UART1_EN BIT(2)
#define BIT_SOC_ACTCK_UART0_EN BIT(0)
//2 0x0238 REG_PESOC_PERI_CLK_CTRL1
#define BIT_SOC_ACTCK_ADC_EN BIT(24)
#define BIT_SOC_ACTCK_I2S_EN BIT(16)
#define BIT_SOC_ACTCK_I2C1_EN BIT(2)
#define BIT_SOC_ACTCK_I2C0_EN BIT(0)
//2 0x0240 REG_PESOC_HCI_CLK_CTRL0
#define BIT_SOC_ACTCK_OTG_EN BIT(4)
#define BIT_SOC_ACTCK_SDIO_HST_EN BIT(2) // SDIO_HST clock enable in CPU run mode
#define BIT_SOC_ACTCK_SDIO_DEV_EN BIT(0) // SDIO_DEV clock enable in CPU run mode
/* REG_PESOC_CLK_SEL 0x0250 */
#define BIT_SHIFT_PESOC_UART1_SCLK_SEL 26
#define BIT_MASK_PESOC_UART1_SCLK_SEL 0x03 /* [27:26] uart1 rx clock, 01: osc 8m; 00: xtal; 10: xtal nco */
#define BIT_SHIFT_PESOC_UART0_SCLK_SEL 19
#define BIT_MASK_PESOC_UART0_SCLK_SEL 0x03 /* [20:19] uart0 rx clock, 01: osc 8m; 00: xtal; 10: xtal nco */
#define BIT_FLASH_CK_PS_DIV_EN BIT(25) /* 1: enable to generate flash clock (with phase shift) divided by 500M pll clock, HW detect this signal¡¯s rising edge to start the phase shift clock division circuit. */
#define BIT_FLASH_CK_DIV_EN BIT(24) /* 1: enable to generate flash clock (no phase shift) divided by 500M pll clock, HW detect this signal¡¯s rising edge to start the no phase shift division circuit. */
#define BIT_FLASH_CAL_EN BIT(23) /* 1: delay flash sout for calibration; 0: bypass flash sout to spic */
#define BIT_SHIFT_FLASH_CK_PS_INT 12
#define BIT_MASK_FLASH_CK_PS_INT 0x03 /* [14:12] Flash clock phase shift in units of 500M pll clock cycels */
#define BIT_FLASH_PS_DIV_RDY BIT(7) /* ready flag of Flash clock with phase shift, Read only */
#define BIT_FLASH_DIV_RDY BIT(6) /* ready flag of Flash clock, Read only */
#define BIT_SHIFT_PESOC_TRACE_CK_SEL 4
#define BIT_MASK_PESOC_TRACE_CK_SEL 0x03 /* [5:4] "Trace clock select0: 12.5MH1: 25MHz2: 50MHz3: 100MHz" */
#define BIT_FLASH_DIV_HIGH_FRAC BIT(3) /* "Only valid when r_FLASH_DIV_FRAC= 1, it decides the duty cycle of flash clock when not divided by integer1: duty cycle > 50% ; 0: duty cycle < 50%" */
#define BIT_FLASH_DIV_FRAC BIT(2) /* "Flash clock division ratio, fractional part0: no fraction, only divided by integer set by bit[1:0], 1: 0.5" */
#define BIT_SHIFT_DIV_INT 0
#define BIT_MASK_FLASH_DIV_INT 0x03 /* [1:0] "Flash clock division ratio, integrate part0: divided by 21: divided by 32: divided by 43: divided by 5" */
//0x0244 REG_PESOC_COM_CLK_CTRL1
#define BIT_SOC_ACTCK_SECURITY_ENG_EN BIT(4)
#define BIT_SOC_ACTCK_LXBUS_EN BIT(0) //spec name is wrong (BIT_SOC_ACTCK_WL_EN)
//0x02E0 REG_PON_PINMUX_CTRL
#define BIT_HCI_SDIOD_PIN_EN BIT(0)
#define SDIOD_PIN_FCTRL(ctrl) HAL_PERL_ON_FUNC_CTRL(REG_PON_PINMUX_CTRL, BIT_HCI_SDIOD_PIN_EN, ctrl)
//0x0304 REG_PESOC_SOC_CTRL
#define BIT_PESOC_LX_SLV_SWAP_SEL BIT(10)
#define BIT_PESOC_LX_MST_SWAP_SEL BIT(9)
#define BIT_PESOC_LX_WL_SWAP_SEL BIT(8)
#define LX_WL_SWAP_CTRL(ctrl) HAL_PERL_ON_FUNC_CTRL(REG_PESOC_SOC_CTRL, BIT_PESOC_LX_WL_SWAP_SEL, ctrl)
#define LX_MST_SWAP_CTRL(ctrl) HAL_PERL_ON_FUNC_CTRL(REG_PESOC_SOC_CTRL, BIT_PESOC_LX_MST_SWAP_SEL, ctrl)
//0x2FC REG_FW_PPROTECT_KEY_CTRL
#define BIT_RDP_EN BIT(3) /* load from efuse */
#define BIT_RDP_EN_LOAD BIT(2)
#define BIT_RDP_KEY_REQ BIT(1)
#define BIT_OTF_KEY_REQ BIT(0)
//==========PERION Register Address Definition ==================//
#define REG_PEON_PWR_CTRL 0x0200
#define REG_PON_ISO_CTRL 0x0204
#define REG_SOC_FUNC_EN 0x0210
#define REG_SOC_HCI_COM_FUNC_EN 0x0214
#define REG_SOC_PERI_FUNC0_EN 0x0218
#define REG_SOC_PERI_FUNC1_EN 0x021C
#define REG_SOC_PERI_BD_FUNC0_EN 0x0220
#define REG_PESOC_CLK_CTRL 0x0230
#define REG_PESOC_PERI_CLK_CTRL0 0x0234
#define REG_PESOC_PERI_CLK_CTRL1 0x0238
#define REG_PESOC_CLK_CTRL3 0x023C
#define REG_PESOC_HCI_CLK_CTRL0 0x0240
#define REG_PESOC_COM_CLK_CTRL1 0x0244
#define REG_PESOC_HW_ENG_CLK_CTRL 0x0248
#define REG_PESOC_CLK_SEL 0x0250
#define REG_UART_NCO_CTRL 0x026C
//#define REG_OSC32K_CTRL 0x0270 /* AmebaZ move to 0xf0 */
#define REG_OSC32K_REG_CTRL0 0x0274
#define REG_OSC32K_REG_CTRL1 0x0278
#define REG_THERMAL_METER_CTRL 0x027C /* AmebaZ no change */
/* 0x0280~0x2D0: 41 16bits for pinmux pad control */
#define REG_GPIO_PINMUX_CTRL 0x0280
#define REG_PON_PINMUX_CTRL 0x02E0
/* request OFT Key autoload */
#define REG_FW_PPROTECT_KEY_CTRL 0x02FC
#define REG_PESOC_SOC_CTRL 0x0304
#endif // end of "#ifndef __INC_RTL8710B_PERI_ON_H"

View file

@ -0,0 +1,248 @@
/**
******************************************************************************
* @file rtl8711b_rcc.h
* @author
* @version V1.0.0
* @date 2016-05-17
* @brief This file contains all the functions prototypes for peripheral reset and clock control driver.
******************************************************************************
* @attention
*
* This module is a confidential and proprietary property of RealTek and
* possession or use of this module requires written permission of RealTek.
*
* Copyright(c) 2015, Realtek Semiconductor Corporation. All rights reserved.
******************************************************************************
*/
#ifndef _RTL8711B_RCC_H_
#define _RTL8711B_RCC_H_
/** @addtogroup AmebaZ_Platform
* @{
*/
/** @defgroup RCC
* @brief RCC driver modules
* @{
*/
/** @addtogroup RCC
* @verbatim
*****************************************************************************************
* Introduction
*****************************************************************************************
* - functions prototypes for peripheral reset and clock control driver.
*
*****************************************************************************************
* supported peripherals
*****************************************************************************************
* -APBPeriph_SECURITY_ENGINE
* -APBPeriph_GTIMER
* -APBPeriph_GDMA1
* -APBPeriph_GDMA0
* -APBPeriph_FLASH
* -APBPeriph_OTG
* -APBPeriph_UART0
* -APBPeriph_UART1
* -APBPeriph_LOGUART
* -APBPeriph_SPI0
* -APBPeriph_SPI1
* -APBPeriph_I2C0
* -APBPeriph_I2C1
* -APBPeriph_I2S0
* -APBPeriph_ADC
* -APBPeriph_GPIO
*
*****************************************************************************************
* how to use
*****************************************************************************************
* use UART0 as example:
* RCC_PeriphClockCmd(APBPeriph_UART0, APBPeriph_UART0_CLOCK, ENABLE);
*
*****************************************************************************************
* @endverbatim
*/
/* Exported constants --------------------------------------------------------*/
/** @defgroup RCC_CLK_Exported_Constants RCC Exported Constants
* @{
*/
/** @defgroup CLK_CTRL_REG_Exported_Constants
* @{
*/
#define PESOC_CLK_CTRL 0
#define PERI_CLK_CTRL0 1 //0x234
#define PERI_CLK_CTRL1 2 //0x238
#define PESOC_CLK_CTRL3 3 //0x23C
#define PESOC_HCI_CLK_CTRL0 4 //0x240
#define PESOC_COM_CLK_CTRL1 5 //0x244
/**
* @}
*/
/** @defgroup REG_PESOC_CLK_CTRL_Exported_Constants 0x230 REG_PESOC_CLK_CTRL Exported Constants
* @{
*/
#define APBPeriph_GPIO_CLOCK (BIT_SOC_ACTCK_GPIO_EN)
#define APBPeriph_GDMA1_CLOCK (BIT_SOC_ACTCK_GDMA1_EN)
#define APBPeriph_GDMA0_CLOCK (BIT_SOC_ACTCK_GDMA0_EN)
#define APBPeriph_GTIMER_CLOCK (BIT_SOC_ACTCK_TIMER_EN)
#define APBPeriph_LOGUART_CLOCK (BIT_SOC_ACTCK_LOG_UART_EN)
#define APBPeriph_FLASH_CLOCK (BIT_SOC_ACTCK_FLASH_EN)
#define APBPeriph_VENDOR_REG_CLOCK (BIT_SOC_ACTCK_VENDOR_REG_EN)
#define APBPeriph_TRACE_CLOCK (BIT_SOC_ACTCK_TRACE_EN)
/**
* @}
*/
/** @defgroup REG_PESOC_PERI_CLK_CTRL0_Exported_Constants 234 REG_PESOC_PERI_CLK_CTRL0 Exported Constants
* @{
*/
#define APBPeriph_UART0_CLOCK (BIT_SOC_ACTCK_UART0_EN | (PERI_CLK_CTRL0<<29))
#define APBPeriph_UART1_CLOCK (BIT_SOC_ACTCK_UART1_EN | (PERI_CLK_CTRL0<<29))
#define APBPeriph_SPI0_CLOCK (BIT_SOC_ACTCK_SPI0_EN | (PERI_CLK_CTRL0<<29))
#define APBPeriph_SPI1_CLOCK (BIT_SOC_ACTCK_SPI1_EN | (PERI_CLK_CTRL0<<29))
/**
* @}
*/
/** @defgroup REG_PESOC_PERI_CLK_CTRL1_Exported_Constants 238 REG_PESOC_PERI_CLK_CTRL1 Exported Constants
* @{
*/
#define APBPeriph_I2C0_CLOCK (BIT_SOC_ACTCK_I2C0_EN | (PERI_CLK_CTRL1<<29))
#define APBPeriph_I2C1_CLOCK (BIT_SOC_ACTCK_I2C1_EN | (PERI_CLK_CTRL1<<29))
#define APBPeriph_I2S0_CLOCK (BIT_SOC_ACTCK_I2S_EN | (PERI_CLK_CTRL1<<29))
#define APBPeriph_ADC_CLOCK (BIT_SOC_ACTCK_ADC_EN | (PERI_CLK_CTRL1<<29))
/**
* @}
*/
/** @defgroup PESOC_HCI_CLK_CTRL0_Exported_Constants 240 PESOC_HCI_CLK_CTRL0 Exported Constants
* @{
*/
#define APBPeriph_SDIOD_CLOCK (BIT_SOC_ACTCK_SDIO_DEV_EN | (PESOC_HCI_CLK_CTRL0 << 29))
#define APBPeriph_SDIOH_CLOCK (BIT_SOC_ACTCK_SDIO_HST_EN | (PESOC_HCI_CLK_CTRL0 << 29))
#define APBPeriph_OTG_CLOCK (BIT_SOC_ACTCK_OTG_EN | (PESOC_HCI_CLK_CTRL0 << 29))
/**
* @}
*/
/** @defgroup PESOC_COM_CLK_CTRL1_Exported_Constants 244 PESOC_COM_CLK_CTRL1 Exported Constants
* @{
*/
#define APBPeriph_WL_CLOCK (BIT_SOC_ACTCK_LXBUS_EN | (PESOC_COM_CLK_CTRL1 << 29))
#define APBPeriph_LXBUS_CLOCK (BIT_SOC_ACTCK_LXBUS_EN | (PESOC_COM_CLK_CTRL1 << 29))
#define APBPeriph_SEC_ENG_CLOCK (BIT_SOC_ACTCK_SECURITY_ENG_EN | (PESOC_COM_CLK_CTRL1 << 29))
/**
* @}
*/
/**
* @}
*/
/** @defgroup RCC_CLK_Exported_Constants RCC Exported Constants
* @{
*/
/** @defgroup FUNC_CTRL_REG_Exported_Constants
* @{
*/
#define SOC_FUNC_EN 0 //210
#define SOC_HCI_COM_FUNC_EN 1 //214
#define SOC_PERI_FUNC0_EN 2 //218
#define SOC_PERI_FUNC1_EN 3 //21c
#define APBPeriph_NULL 0 //if you dont want to set any function, you can use this
#define APBPeriph_CLOCK_NULL 0 //if you dont want to set any clock, you can use this
/**
* @}
*/
/** @defgroup REG_SOC_FUNC_EN_Exported_Constants 210 REG_SOC_FUNC_EN Exported Constants
* @{
*/
#define APBPeriph_SECURITY_ENGINE BIT_SOC_SECURITY_ENGINE_EN
#define APBPeriph_GTIMER BIT_SOC_GTIMER_EN
#define APBPeriph_GDMA1 BIT_SOC_GDMA1_EN
#define APBPeriph_GDMA0 BIT_SOC_GDMA0_EN
#define APBPeriph_FLASH BIT_SOC_FLASH_EN
#define APBPeriph_LXBUS BIT_SOC_LXBUS_EN
/**
* @}
*/
/** @defgroup REG_SOC_HCI_COM_FUNC_EN_Exported_Constants 214 REG_SOC_HCI_COM_FUNC_EN Exported Constants
* @{
*/
#define APBPeriph_WLMAC (BIT_SOC_HCI_WL_MACON_EN | SOC_HCI_COM_FUNC_EN << 30)
#define APBPeriph_SM (BIT_SOC_HCI_SM_SEL | SOC_HCI_COM_FUNC_EN << 30)
#define APBPeriph_OTGRST (BIT_SOC_HCI_OTG_RST_MUX | SOC_HCI_COM_FUNC_EN << 30)
#define APBPeriph_OTG (BIT_SOC_HCI_OTG_EN | SOC_HCI_COM_FUNC_EN << 30)
#define APBPeriph_SDIOD_ON_RST (BIT_SOC_HCI_SDIOD_ON_RST_MUX | SOC_HCI_COM_FUNC_EN << 30)
#define APBPeriph_SDIOD_OFF (BIT_SOC_HCI_SDIOD_OFF_EN | SOC_HCI_COM_FUNC_EN << 30)
#define APBPeriph_SDIOD_ON (BIT_SOC_HCI_SDIOD_ON_EN | SOC_HCI_COM_FUNC_EN << 30)
/**
* @}
*/
/** @defgroup REG_SOC_PERI_FUNC0_EN_Exported_Constants 218 REG_SOC_PERI_FUNC0_EN Exported Constants
* @{
*/
#define APBPeriph_UART0 (BIT_PERI_UART0_EN | SOC_PERI_FUNC0_EN << 30)
#define APBPeriph_UART1 (BIT_PERI_UART1_EN | SOC_PERI_FUNC0_EN << 30)
#define APBPeriph_LOGUART (BIT_PERI_UART2_EN | SOC_PERI_FUNC0_EN << 30)
#define APBPeriph_SPI0 (BIT_PERI_SPI0_EN | SOC_PERI_FUNC0_EN << 30)
#define APBPeriph_SPI1 (BIT_PERI_SPI1_EN | SOC_PERI_FUNC0_EN << 30)
#define APBPeriph_I2C0 (BIT_PERI_I2C0_EN | SOC_PERI_FUNC0_EN << 30)
#define APBPeriph_I2C1 (BIT_PERI_I2C1_EN | SOC_PERI_FUNC0_EN << 30)
#define APBPeriph_I2S0 (BIT_PERI_I2S0_EN | SOC_PERI_FUNC0_EN << 30)
/**
* @}
*/
/** @defgroup REG_SOC_PERI_FUNC1_EN_Exported_Constants 21c REG_SOC_PERI_FUNC1_EN Exported Constants
* @{
*/
#define APBPeriph_ADC (BIT_PERI_ADC0_EN | SOC_PERI_FUNC1_EN << 30)
#define APBPeriph_GPIO (BIT_PERI_GPIO_EN | SOC_PERI_FUNC1_EN << 30)
/**
* @}
*/
/**
* @}
*/
/* Exported functions --------------------------------------------------------*/
/** @defgroup RCC_Exported_Functions RCC Exported Functions
* @{
*/
_LONG_CALL_ void RCC_PeriphClockCmd(u32 APBPeriph, u32 APBPeriph_Clock, u8 NewState);
_LONG_CALL_ void FUNC_HCI_COM(u32 Function_Bit, u8 NewState);
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/* Registers Definitions --------------------------------------------------------*/
/* Other definations --------------------------------------------------------*/
#endif /* _RTL8711B_RCC_H_ */
/******************* (C) COPYRIGHT 2016 Realtek Semiconductor *****END OF FILE****/

View file

@ -0,0 +1,479 @@
/**
******************************************************************************
* @file rtl8711b_rtc.h
* @author
* @version V1.0.0
* @date 2016-05-17
* @brief This file contains all the functions prototypes for the RTC firmware
* library.
******************************************************************************
* @attention
*
* This module is a confidential and proprietary property of RealTek and
* possession or use of this module requires written permission of RealTek.
*
* Copyright(c) 2015, Realtek Semiconductor Corporation. All rights reserved.
******************************************************************************
*/
#ifndef _RTL8711B_RTC_H_
#define _RTL8711B_RTC_H_
/** @addtogroup AmebaZ_Periph_Driver
* @{
*/
/** @defgroup RTC
* @brief RTC driver modules
* @{
*/
/** @addtogroup RTC
* @verbatim
*****************************************************************************************
* Introduction
*****************************************************************************************
* The real-time clock (RTC) is an independent BCD timer/counter.
* One 32-bit register contains the seconds, minutes, hours (12 or 24-hour format)
* expressed in binary coded decimal format (BCD).
* One 32-bit register contains the days expressed in binary format.
* Daylight saving time compensation can also be performed.
* One programmable alarm contains seconds, minutes, hours and days with interrupt function,
* and can be triggered by any combination of the time fields.
* A digital calibration feature is available to compensate for some deviation.
* After backup domain reset, all RTC registers are protected against possible parasitic
* write accesses.
* As long as the supply voltage remains in the operating range, the RTC never stops,
* regardless of the device status (Run mode, low power mode or under reset).
*
*****************************************************************************************
* How to use RTC
*****************************************************************************************
* To use the RTC, the following steps are mandatory:
*
* 1. Initialize the RTC Clock Source.
* RTC_ClockSource()
*
* 2. Fill the variable RTC_InitStruct with default parameters, or set the desired parameters manually:
* RTC_StructInit(&RTC_InitStruct)
*
* 3. configure the RTC peripheral with the corresponding configurations contained in RTC_InitStruct:
* Call RTC_Init(&RTC_InitStruct)
*
* 4. Fill the variable RTC_TimeStruct with default parameters() (Time = 00d:00h:00min:00sec)
* RTC_TimeStructInit(&RTC_TimeStruct)
* setting the desired calendar time parameters manually.
*
* 5. Set calendar time:
* RTC_SetTime(RTC_Format_BIN, &RTC_TimeStruct).
*
* 6. If RTC_OUT output is needed, the pinmux configuration is as follows:
* Pinmux_Config(PinName, PINMUX_FUNCTION_RTCOUT)
*
* RTC_OUT output pinmux:
* S0: PA_30
* S1: PA_16
*
*****************************************************************************************
* How to use Alarm
*****************************************************************************************
* To use the Alarm, the following steps are mandatory:
*
* 1. Configure the RTC as described in the first part of this driver.
*
* 2. Fill the variable RTC_AlarmStruct of type RTC_AlarmTypeDef with default parameters
* RTC_AlarmStructInit(&RTC_AlarmStruct)
* or setting the desired Alarm time parameters manually.
*
* 3. configure Alarm:
* RTC_SetAlarm(RTC_Format_BIN, &RTC_AlarmStruct)
*
* 4. Enable alarm and alarm interrupt.
* RTC_AlarmCmd(ENABLE)
*
* 5. Enable IRQ as follows:
* InterruptRegister(RTC_IntHandler, RTC_IRQ, NULL, 4);
* InterruptEn(RTC_IRQ, 4);
*
* @endverbatim
*/
/* Exported types ------------------------------------------------------------*/
/** @defgroup RTC_Exported_Types RTC Exported Types
* @{
*/
/**
* @brief RTC Init structure definition
*/
typedef struct {
u32 RTC_HourFormat; /*!< Specifies the RTC Hour Format.
This parameter can be a value of @ref RTC_Hour_Formats */
u32 RTC_AsynchPrediv; /*!< Specifies the RTC Asynchronous Predivider value.
This parameter must be a value of @ref RTC_Asynchronous_Predivider */
u32 RTC_SynchPrediv; /*!< Specifies the RTC Synchronous Predivider value.
This parameter must be a value of @ref RTC_Synchronous_Predivider */
} RTC_InitTypeDef;
/**
* @brief RTC Time structure definition
*/
typedef struct
{
u16 RTC_Days; /*!< Day in binary format 9bits 0~0x1FF */
u8 RTC_Hours; /*!< Specifies the RTC Time Hour.
This parameter must be set to a value in the 1-12 range
if the RTC_HourFormat_12 is selected or 0-23 range if
the RTC_HourFormat_24 is selected. */
u8 RTC_Minutes; /*!< Specifies the RTC Time Minutes.
This parameter must be set to a value in the 0-59 range. */
u8 RTC_Seconds; /*!< Specifies the RTC Time Seconds.
This parameter must be set to a value in the 0-59 range. */
u8 RTC_H12_PMAM; /*!< Specifies the RTC AM/PM Time.
This parameter can be a value of @ref RTC_AM_PM_Definitions */
}RTC_TimeTypeDef;
/**
* @brief RTC Alarm structure definition
*/
typedef struct
{
RTC_TimeTypeDef RTC_AlarmTime; /*!< Specifies the RTC Alarm Time members. */
u32 RTC_AlarmMask; /*!< Specifies the RTC Alarm1 Masks(H:M:S).
This parameter can be a value of @ref RTC_AlarmMask1_Definitions */
u32 RTC_Alarm2Mask; /*!< Specifies the RTC Alarm2 Masks Day).
This parameter can be a value of @ref RTC_AlarmMask2_Definitions */
}RTC_AlarmTypeDef;
/**
* @}
*/
/* Exported constants --------------------------------------------------------*/
/** @defgroup RTC_Exported_Constants RTC Exported Constants
* @{
*/
/** @defgroup RTC_Input_parameter_format_definitions
* @{
*/
#define RTC_Format_BIN ((u32)0x000000000)
#define RTC_Format_BCD ((u32)0x000000001)
#define IS_RTC_FORMAT(FORMAT) (((FORMAT) == RTC_Format_BIN) || ((FORMAT) == RTC_Format_BCD))
/**
* @}
*/
/** @defgroup RTC_Hour_Formats
* @{
*/
#define RTC_HourFormat_24 ((u32)0x00000000)
#define RTC_HourFormat_12 ((u32)0x00000080)
#define IS_RTC_HOUR_FORMAT(FORMAT) (((FORMAT) == RTC_HourFormat_12) || \
((FORMAT) == RTC_HourFormat_24))
/**
* @}
*/
/** @defgroup RTC_Asynchronous_Predivider
* @{
*/
#define IS_RTC_ASYNCH_PREDIV(PREDIV) ((PREDIV) <= 0x1FF)
/**
* @}
*/
/** @defgroup RTC_Synchronous_Predivider
* @{
*/
#define IS_RTC_SYNCH_PREDIV(PREDIV) ((PREDIV) <= 0x1FF)
/**
* @}
*/
/** @defgroup RTC_Time_Definitions
* @{
*/
#define IS_RTC_HOUR12(HOUR) (((HOUR) > 0) && ((HOUR) <= 12))
#define IS_RTC_HOUR24(HOUR) ((HOUR) <= 23)
#define IS_RTC_MINUTES(MINUTES) ((MINUTES) <= 59)
#define IS_RTC_SECONDS(SECONDS) ((SECONDS) <= 59)
/**
* @}
*/
/** @defgroup RTC_AM_PM_Definitions
* @{
*/
#define RTC_H12_AM ((u8)0x00) //AM or 24-hour format
#define RTC_H12_PM ((u8)0x01) //PM
#define IS_RTC_H12_AMPM(PM) (((PM) == RTC_H12_AM) || ((PM) == RTC_H12_PM))
/**
* @}
*/
/** @defgroup RTC_AlarmMask1_Definitions
* @{
*/
#define RTC_AlarmMask_None ((u32)0x00000000)
#define RTC_AlarmMask_Hours ((u32)0x00800000)
#define RTC_AlarmMask_Minutes ((u32)0x00008000)
#define RTC_AlarmMask_Seconds ((u32)0x00000080)
#define RTC_AlarmMask_All ((u32)0x00808080)
#define IS_ALARM_MASK(MASK) (((MASK) & 0x7F7F7F) == 0)
/**
* @}
*/
/** @defgroup RTC_AlarmMask2_Definitions
* @{
*/
#define RTC_Alarm2Mask_None ((u32)0x00000000)
#define RTC_Alarm2Mask_Days ((u32)0x00000200)
#define IS_ALARM2_MASK(MASK) (((MASK) & ~RTC_Alarm2Mask_Days) == 0)
/**
* @}
*/
/** @defgroup RTC_Alarms_Definitions
* @{
*/
#define RTC_Alarm ((u32)0x00000100)
#define IS_RTC_ALARM(ALARM) ((ALARM) == RTC_Alarm)
#define IS_RTC_CMD_ALARM(ALARM) (((ALARM) & RTC_Alarm) != (u32)0)
/**
* @}
*/
/** @defgroup RTC_Alarms_Interrupt_Definitions
* @{
*/
#define RTC_Alarm_IntEn ((u32)0x00001000)
/**
* @}
*/
/** @defgroup RTC_DayLightSaving_Definitions
* @{
*/
#define RTC_DayLightSaving_SUB1H ((u32)0x00000002)
#define RTC_DayLightSaving_ADD1H ((u32)0x00000001)
#define IS_RTC_DAYLIGHT_SAVING(SAVE) (((SAVE) == RTC_DayLightSaving_SUB1H) || \
((SAVE) == RTC_DayLightSaving_ADD1H))
#define RTC_StoreOperation_Reset ((u32)0x00000000)
#define RTC_StoreOperation_Set ((u32)0x00000004)
#define IS_RTC_STORE_OPERATION(OPERATION) (((OPERATION) == RTC_StoreOperation_Reset) || \
((OPERATION) == RTC_StoreOperation_Set))
/**
* @}
*/
/** @defgroup RTC_Output_selection_Definitions
* @{
*/
#define RTC_Output_Disable ((u32)0x00000000)
#define RTC_Output_Alarm ((u32)0x00000020) ////wakeup
#define RTC_Output_clkspre ((u32)0x00000040) ////1Hz
#define RTC_Output_clkapre ((u32)0x00000060) ////256Hz
#define IS_RTC_OUTPUT(OUTPUT) (((OUTPUT) == RTC_Output_Disable) || \
((OUTPUT) == RTC_Output_Alarm) || \
((OUTPUT) == RTC_Output_clkspre) || \
((OUTPUT) == RTC_Output_clkapre))
/**
* @}
*/
/** @defgroup RTC_Smooth_Calibration_Definitions
* @{
*/
#define RTC_CalibPeriod_1MIN ((u32)0x00000000)
#define RTC_CalibPeriod_2MIN ((u32)0x00010000)
#define RTC_CalibPeriod_3MIN ((u32)0x00020000)
#define RTC_CalibPeriod_4MIN ((u32)0x00030000)
#define RTC_CalibPeriod_5MIN ((u32)0x00040000)
#define RTC_CalibPeriod_6MIN ((u32)0x00050000)
#define RTC_CalibPeriod_7MIN ((u32)0x00060000)
#define RTC_CalibPeriod_8MIN ((u32)0x00070000)
#define IS_RTC_CALIB_PERIOD(DCP) (((DCP) == RTC_CalibPeriod_1MIN) || \
((DCP) == RTC_CalibPeriod_2MIN) || \
((DCP) == RTC_CalibPeriod_3MIN) || \
((DCP) == RTC_CalibPeriod_4MIN) || \
((DCP) == RTC_CalibPeriod_5MIN) || \
((DCP) == RTC_CalibPeriod_6MIN) || \
((DCP) == RTC_CalibPeriod_7MIN) || \
((DCP) == RTC_CalibPeriod_8MIN))
#define RTC_Calib_Disable ((u32)0x00000000)
#define RTC_Calib_Enable ((u32)0x00008000)
#define IS_RTC_CALIB_ENABLE(DCE) (((DCE) == RTC_Calib_Disable) || \
((DCE) == RTC_Calib_Enable))
#define RTC_CalibSign_Positive ((u32)0x00000000)
#define RTC_CalibSign_Negative ((u32)0x00004000)
#define IS_RTC_CALIB_SIGN(SIGN) (((SIGN) == RTC_CalibSign_Positive) || \
((SIGN) == RTC_CalibSign_Negative))
#define IS_RTC_CALIB_VALUE(VALUE) ((VALUE) <= 0x7F)
/**
* @}
*/
/**
* @}
*/
/** @defgroup RTC_Exported_Functions RTC Exported Functions
* @{
*/
_LONG_CALL_ void RTC_BypassShadowCmd(u32 NewState);
_LONG_CALL_ void RTC_StructInit(RTC_InitTypeDef* RTC_InitStruct);
_LONG_CALL_ u32 RTC_Init(RTC_InitTypeDef* RTC_InitStruct);
_LONG_CALL_ void RTC_TimeStructInit(RTC_TimeTypeDef* RTC_TimeStruct);
_LONG_CALL_ u32 RTC_SetTime(u32 RTC_Format, RTC_TimeTypeDef* RTC_TimeStruct);
_LONG_CALL_ void RTC_GetTime(u32 RTC_Format, RTC_TimeTypeDef* RTC_TimeStruct);
_LONG_CALL_ u32 RTC_SetAlarm(u32 RTC_Format, RTC_AlarmTypeDef* RTC_AlarmStruct);
_LONG_CALL_ void RTC_AlarmStructInit(RTC_AlarmTypeDef* RTC_AlarmStruct);
_LONG_CALL_ void RTC_GetAlarm(u32 RTC_Format, RTC_AlarmTypeDef* RTC_AlarmStruct);
_LONG_CALL_ void RTC_AlarmCmd(u32 NewState);
_LONG_CALL_ void RTC_AlarmClear(void);
_LONG_CALL_ void RTC_DayLightSavingConfig(u32 RTC_DayLightSaving, u32 RTC_StoreOperation);
_LONG_CALL_ u32 RTC_GetStoreOperation(void);
_LONG_CALL_ void RTC_OutputConfig(u32 RTC_Output);
_LONG_CALL_ u32 RTC_SmoothCalibConfig(u32 CalibSign, u32 Value, u32 CalibPeriod, u32 Calib_Enable);
/**
* @}
*/
/* Registers Definitions --------------------------------------------------------*/
/**************************************************************************//**
* @defgroup RTC_Register_Definitions RTC Register Definitions
* @{
*****************************************************************************/
/**************************************************************************//**
* @defgroup RTC_TR
* @{
*****************************************************************************/
#define RTC_TR_DAY ((u32)0xFF800000)
#define RTC_TR_PM ((u32)0x00400000)
#define RTC_TR_HT ((u32)0x00300000)
#define RTC_TR_HU ((u32)0x000F0000)
#define RTC_TR_MNT ((u32)0x00007000)
#define RTC_TR_MNU ((u32)0x00000F00)
#define RTC_TR_ST ((u32)0x00000070)
#define RTC_TR_SU ((u32)0x0000000F)
/** @} */
/**************************************************************************//**
* @defgroup RTC_CR
* @{
*****************************************************************************/
#define RTC_CR_ALRAIE ((u32)0x00001000)
#define RTC_CR_ALRAE ((u32)0x00000100)
#define RTC_CR_FMT ((u32)0x00000080)
#define RTC_CR_OSEL ((u32)0x00000060)
#define RTC_CR_BYPSHAD ((u32)0x00000008)
#define RTC_CR_BCK ((u32)0x00000004)
#define RTC_CR_SUB1H ((u32)0x00000002)
#define RTC_CR_ADD1H ((u32)0x00000001)
/** @} */
/**************************************************************************//**
* @defgroup RTC_ISR
* @{
*****************************************************************************/
#define RTC_ISR_RECALPF ((u32)0x00010000)
#define RTC_ISR_ALRAF ((u32)0x00000100)
#define RTC_ISR_INIT ((u32)0x00000080)
#define RTC_ISR_INITF ((u32)0x00000040)
#define RTC_ISR_RSF ((u32)0x00000020)
#define RTC_ISR_INITS ((u32)0x00000010)
#define RTC_ISR_ALMWF ((u32)0x00000001)
/** @} */
/**************************************************************************//**
* @defgroup RTC_PRER
* @{
*****************************************************************************/
#define RTC_PRER_PREDIV_A ((u32)0x01FF0000)
#define RTC_PRER_PREDIV_S ((u32)0x000001FF)
/** @} */
/**************************************************************************//**
* @defgroup RTC_CALIBR
* @{
*****************************************************************************/
#define RTC_CALIBR_CALP ((u32)0x00070000)
#define RTC_CALIBR_DCE ((u32)0x00008000)
#define RTC_CALIBR_DCS ((u32)0x00004000)
#define RTC_CALIBR_DC ((u32)0x0000007F)
/** @} */
/**************************************************************************//**
* @defgroup RTC_ALRMAR
* @{
*****************************************************************************/
#define RTC_ALRMAR_MSK2 ((u32)0x00800000)
#define RTC_ALRMAR_PM ((u32)0x00400000)
#define RTC_ALRMAR_HT ((u32)0x00300000)
#define RTC_ALRMAR_HU ((u32)0x000F0000)
#define RTC_ALRMAR_MSK1 ((u32)0x00008000)
#define RTC_ALRMAR_MNT ((u32)0x00007000)
#define RTC_ALRMAR_MNU ((u32)0x00000F00)
#define RTC_ALRMAR_MSK0 ((u32)0x00000080)
#define RTC_ALRMAR_ST ((u32)0x00000070)
#define RTC_ALRMAR_SU ((u32)0x0000000F)
/** @} */
/**************************************************************************//**
* @defgroup RTC_ALRMBR
* @{
*****************************************************************************/
#define RTC_ALRMBR_MSK3 ((u32)0x00000200)
#define RTC_ALRMBR_DT ((u32)0x000001FF)
/** @} */
/**************************************************************************//**
* @defgroup RTC_WPR
* @{
*****************************************************************************/
#define RTC_WPR_KEY ((u32)0x000000FF)
/** @} */
/** @} */
/**
* @}
*/
/**
* @}
*/
/* Masks Definition */
#define RTC_TR_RESERVED_MASK ((u32)0xFFFF7F7F)
#define INITMODE_TIMEOUT ((u32) 0x00010000)
#define SYNCHRO_TIMEOUT ((u32) 0x00020000)
#define RECALPF_TIMEOUT ((u32) 0x00020000)
#define ALARMDIS_TIMEOUT ((u32) 0x00020000)
#define RTC_DIV_XTAL_MASK ((u32) 0x07FF0000)
#endif //_RTL8711B_RTC_H_
/******************* (C) COPYRIGHT 2016 Realtek Semiconductor *****END OF FILE****/

View file

@ -0,0 +1,649 @@
/**
******************************************************************************
* @file rtl8711b_ssi.h
* @author
* @version V1.0.0
* @date 2016-05-17
* @brief This file contains all the functions prototypes for the SPI firmware
* library.
******************************************************************************
* @attention
*
* This module is a confidential and proprietary property of RealTek and
* possession or use of this module requires written permission of RealTek.
*
* Copyright(c) 2016, Realtek Semiconductor Corporation. All rights reserved.
******************************************************************************
*/
#ifndef _RTL8710B_SPI_H_
#define _RTL8710B_SPI_H_
/** @addtogroup AmebaZ_Periph_Driver
* @{
*/
/** @defgroup SPI
* @brief SPI driver modules
* @{
*/
/** @addtogroup SPI
* @verbatim
*****************************************************************************************
* Introduction
*****************************************************************************************
* SPI0:
* - Support Motorola SPI interface
* - Role: Slave
* - Base Address: SPI0_DEV
* - Bus Clk: 62.5MHz
* - BaudRate: less than or equal to 31.25M
* - Transfer mode:TRx
* - Data Frame Size: 4-16 bits supported
* - IRQ Number: SPI0_IRQ
* - GDMA TX handshake interface: GDMA_HANDSHAKE_INTERFACE_SPI0_TX
* - GDMA RX handshake interface: GDMA_HANDSHAKE_INTERFACE_SPI0_RX
*
* SPI1:
* - Support Motorola SPI interface
* - Role: Master
* - Base Address: SPI1_DEV
* - Bus Clk: 62.5MHz
* - BaudRate: less than or equal to 31.25M
* - Transfer mode:Tx,Rx,TRx,EEPROM Read
* - Data Frame Size: 4-16 bits supported
* - IRQ Number: SPI1_IRQ
* - GDMA TX handshake interface: GDMA_HANDSHAKE_INTERFACE_SPI1_TX
* - GDMA RX handshake interface: GDMA_HANDSHAKE_INTERFACE_SPI1_RX
*
*****************************************************************************************
* PINMUX
*****************************************************************************************
* SPI0:
* - S0: PA_1(Sclk)/PA_2(CS)/PA_3(MISO)/PA_4(MOSI).
* - S1: PA_18(Sclk)/PA_19(CS)/PA_22(MISO)/PA_23(MOSI).
* - S2: PB_0(Sclk)/PB_1(CS)/PB_2(MISO)/PB_3(MOSI).
*
* SPI1:
* - S0: PA_1(Sclk)/PA_2(CS)/PA_3(MISO)/PA_4(MOSI).
* - S1: PA_18(Sclk)/PA_19(CS)/PA_22(MISO)/PA_23(MOSI).
* - S2: PB_0(Sclk)/PB_1(CS)/PB_2(MISO)/PB_3(MOSI).
*
*****************************************************************************************
* How to use Normal SPI
*****************************************************************************************
* To use the SPI in DMA mode, the following steps are mandatory:
*
* 1. Enable peripheral clock using the following functions:
* -RCC_PeriphClockCmd(APBPeriph_SPI0, APBPeriph_SPI0_CLOCK, ENABLE) for SPI0;
* -RCC_PeriphClockCmd(APBPeriph_SPI1, APBPeriph_SPI1_CLOCK, ENABLE) for SPI1;
*
* 2. Configure the SPIx pinmux:
* -Pinmux_Config(Pin_Num, PINMUX_FUNCTION_SPIS) for SPI0;
* -Pinmux_Config(Pin_Num, PINMUX_FUNCTION_SPIM) for SPI1;
*
* 3. Program the Polarity,Phase,Transfer Mode,Baud Rate Prescaler,DataFrameSize,
* Interrupt TRx Threshold level,DMA TRx Threshold level and other parameters using
* SSI_StructInit() and change some parameters if needed
*
* 4. Init Hardware use step3 parameters:
* SSI_Init(SPI_TypeDef *spi_dev, SSI_InitTypeDef *SSI_InitStruct)
*
* 5. Enable the SPI:
* SSI_Cmd()
*
* 6. When using poll:
* -Using SSI_Writeable() function to make sure that the transmit FIFO is not full,
* then using SSI_WriteData() function to send data
*
* -Using SSI_Readable() function to make sure that the receive FIFO is not empty,
* then using SSI_ReadData() function to receive data
*
* 7. Enable the NVIC and the corresponding interrupt using following function if you need
* to use interrupt mode.
* -SSI_INTConfig(): SPI IRQ Mask set
* -InterruptRegister(): register the SPI irq handler
* -InterruptEn(): Enable the NVIC interrupt and set irq priority
*
*
* @note in SPI_Exported_Functions group, these functions below are about Interrupts
* and flags management:
* -SSI_GetIsr()
* -SSI_GetRawIsr()
* -SSI_INTConfig()
* -SSI_SetRxFifoLevel()
* -SSI_SetTxFifoLevel()
* -SSI_SetIsrClean()
*
*
*****************************************************************************************
* How to use SPI in DMA mode
*****************************************************************************************
* To use the SPI in DMA mode, the following steps are mandatory:
*
* 1. Enable peripheral clock using the following functions:
* -RCC_PeriphClockCmd(APBPeriph_SPI0, APBPeriph_SPI0_CLOCK, ENABLE) for SPI0;
* -RCC_PeriphClockCmd(APBPeriph_SPI1, APBPeriph_SPI1_CLOCK, ENABLE) for SPI1;
*
* 2. Configure the SPIx pinmux:
* -Pinmux_Config(Pin_Num, PINMUX_FUNCTION_SPIS) for SPI0;
* -Pinmux_Config(Pin_Num, PINMUX_FUNCTION_SPIM) for SPI1;
*
* 3. Program the Polarity,Phase,Transfer Mode,Baud Rate Prescaler,DataFrameSize,
* Interrupt TRx Threshold level,DMA TRx Threshold level and other parameters using
* SSI_StructInit() and change some parameters if needed
*
* 4. Init Hardware use step3 parameters:
* SSI_Init(SPI_TypeDef *spi_dev, SSI_InitTypeDef *SSI_InitStruct)
*
* 5. Enable the SPI:
* SSI_Cmd()
*
* 6. GDMA related configurations(DMA burst size/source address/destination address/block size etc).
*
* 7. Active the SPI DMA TX/RX using SSI_SetDmaEnable() function.
*
* @note in SPI_Exported_Functions group, these functions below are about DMA:
* -SSI_SetDmaEnable()
* -SSI_SetDmaLevel()
*
*****************************************************************************************
* @endverbatim
*/
/* Exported Types --------------------------------------------------------*/
/** @defgroup SPI_Exported_Types SPI Exported Types
* @{
*/
/**
* @brief SPI Init structure definition
*/
typedef struct
{
u32 SPI_DmaRxDataLevel; /*!< Specifies the DMA receive data level.
The dma_rx_req is generated when the number of valid data entries in the
receive FIFO is equal to or above this field value+1,and RDMAE=1.
@note For Amebaz, the value range of this parameter should be 0 to 63,because
the depth of Rx FIFO is 64. */
u32 SPI_DmaTxDataLevel; /*!< Specifies the DMA transmit data level.
The dma_tx_req is generated when the number of valid data entries in the
transmit FIFO is equal to or below this field value,and TDMAE=1.
@note For Amebaz, the value range of this parameter should be 0 to 63,because
the depth of Rx FIFO is 64. */
u32 SPI_RxThresholdLevel; /*!< Specifies the receive FIFO threshold level.
This Parameter controls the level of entries(or above) at which the receive FIFO controller
triggers an interrupt.When the number of receive FIFO entries is greater than or equal to this
value +1,the receive FIFO full interrupt is triggered.
@note For Amebaz, the value range of this parameter should be 0 to 63,because the depth
of Rx FIFO is 64. */
u32 SPI_TxThresholdLevel; /*!< Specifies the transmit FIFO threshold level.
This Parameter controls the level of entries (or below) at which the transmit FIFO controller
triggers an interrupt.When the number of transmit FIFO entries is less than or equal to this
value,the transmit FIFO empty interrupt is triggered.
@note For Amebaz, the value range of this parameter should be 0 to 63,because of the depth
of Rx FIFO is 64. */
u32 SPI_SlaveSelectEnable; /*!< Set the slave select enable flag.
This Parameter controls which slave to be selected by master,each bit in SER register
corresponds to a slave select line(ss_x_n) from spi master.
@note The default vlaue of this parameter is 0,and one slave is selected.if more slaves to be selected,
you may use SW way to do this.And this parameter is used only when the device is master. */
u32 SPI_ClockDivider; /*!< Specifies the SPI Baud Rate.
The value of sclk_out equals to ssi_clk devides the value of this parameter
@note The LSB for this field is always set to 0 and is unaffected by a write operation,which ensures
an even value is held. */
u32 SPI_DataFrameNumber; /*!< Specifies the number of data frames master wants to receive .
When TMOD=10 or TMOD=11,Ctrl1 register uses this value to set the number of data frames to
be continuous received.
@note The value of this parameter should be set to the number of data frames that to be received
minus one.And this parameter is used only when the device is master. */
u32 SPI_DataFrameFormat; /*!< Selects which serial protocol transfers the data .
This parameter can be a value of @ref SPI_Frame_Format_definitions. */
u32 SPI_DataFrameSize; /*!< Selects the data frame length .
This parameter can be a value of @ref SPI_Data_Frame_Size_definitions.
@note Need to right-justify transmit data before writting into the transmit FIFO
The transmit logic ignores the upper unused bits when transmitting the data. */
u32 SPI_InterruptMask; /*!< Specifies which interrupt to be enable.
Each bit in this parameter corresponds to a specific interrupt.*/
u32 SPI_Role; /*!< Specifies the role of SPI device.
This parameter can be a value of @ref SPI_ROLE_definitions. . */
u32 SPI_SclkPhase; /*!< Specifies the serial clock phase.
When SPI_SclkPhase = 0, data are captured on the first edge of the serial clock. When SPI_SclkPhase = 1,
the serial clock starts toggling one cycle after the slave select line is activated, and data
are captured on the second edge of the serial clock.
This parameter can be a value of @ref SPI_SCPH_definitions.
@note Valid when the frame format(FRF) is set to Motorola SPI. */
u32 SPI_SclkPolarity; /*!< Specifies the serial clock polarity.
When SPI_SclkPolarity = 0, the serial clock remains low when idle. When SPI_SclkPolarity = 1,
the serial clock remains high when idle.
This parameter can be a value of @ref SPI_SCPOL_definitions.
@note Valid when the frame format(FRF) is set to Motorola SPI.*/
u32 SPI_TransferMode; /*!< Selects the mode of transfer for serial communication.
This parameter can be a value of @ref SPI_TMOD_definitions.
@note This transfer mode is only valid when the DW_apb_ssi is configured as a master device.*/
u32 SPI_MicrowireControlFrameSize; /*!< Selects the length of the control word for the Microwire frame format.
This parameter can be a value of @ref SPI_MW_Control_Frame_Size_definitions. */
u32 SPI_MicrowireDirection; /*!< Specifies of the data word when the Microwire serial protocol is used.
This parameter can be a value of @ref SPI_MW_Direction_definitions. */
u32 SPI_MicrowireHandshaking; /*!< Specifies Microwire Handshaking.
This parameter can be a value of @ref SPI_MW_Handshake_Enable_definitions. */
u32 SPI_MicrowireTransferMode; /*!< Specifies Microwire Transfer Mode.
This parameter can be a value of @ref SPI_MW_TMOD_definitions. */
}SSI_InitTypeDef;
/**
* @}
*/
/* Exported constants --------------------------------------------------------*/
/** @defgroup SPI_Exported_Constants SPI Exported Constants
* @{
*/
/** @defgroup SPI_TMOD_definitions
* @{
*/
#define TMOD_TR (0)
#define TMOD_TO (1)
#define TMOD_RO (2)
#define TMOD_EEPROM_R (3)
/**
* @}
*/
/** @defgroup SPI_SCPOL_definitions
* @{
*/
#define SCPOL_INACTIVE_IS_LOW (0)
#define SCPOL_INACTIVE_IS_HIGH (1)
/**
* @}
*/
/** @defgroup SPI_SCPH_definitions
* @{
*/
#define SCPH_TOGGLES_IN_MIDDLE (0)
#define SCPH_TOGGLES_AT_START (1)
/**
* @}
*/
/** @defgroup SPI_Data_Frame_Size_definitions
* @{
*/
#define DFS_4_BITS (3)
#define DFS_5_BITS (4)
#define DFS_6_BITS (5)
#define DFS_7_BITS (6)
#define DFS_8_BITS (7)
#define DFS_9_BITS (8)
#define DFS_10_BITS (9)
#define DFS_11_BITS (10)
#define DFS_12_BITS (11)
#define DFS_13_BITS (12)
#define DFS_14_BITS (13)
#define DFS_15_BITS (14)
#define DFS_16_BITS (15)
/**
* @}
*/
/** @defgroup SPI_MW_Control_Frame_Size_definitions
* @{
*/
#define CFS_1_BIT (0)
#define CFS_2_BITS (1)
#define CFS_3_BITS (2)
#define CFS_4_BITS (3)
#define CFS_5_BITS (4)
#define CFS_6_BITS (5)
#define CFS_7_BITS (6)
#define CFS_8_BITS (7)
#define CFS_9_BITS (8)
#define CFS_10_BITS (9)
#define CFS_11_BITS (10)
#define CFS_12_BITS (11)
#define CFS_13_BITS (12)
#define CFS_14_BITS (13)
#define CFS_15_BITS (14)
#define CFS_16_BITS (15)
/**
* @}
*/
/** @defgroup SPI_ROLE_definitions
* @{
*/
#define SSI_SLAVE (0)
#define SSI_MASTER (1)
/**
* @}
*/
/** @defgroup SPI_Frame_Format_definitions
* @{
*/
#define FRF_MOTOROLA_SPI (0)
#define FRF_TI_SSP (1)
#define FRF_NS_MICROWIRE (2)
#define FRF_RSVD (3)
/**
* @}
*/
/** @defgroup SPI_DMA_Control_definitions
* @{
*/
#define SSI_NODMA (0)
#define SSI_RXDMA_ENABLE (1)
#define SSI_TXDMA_ENABLE (2)
#define SSI_TRDMA_ENABLE (3)
/**
* @}
*/
/** @defgroup SPI_MW_Handshake_Enable_definitions
* @{
*/
#define MW_HANDSHAKE_DISABLE (0)
#define MW_HANDSHAKE_ENABLE (1)
/**
* @}
*/
/** @defgroup SPI_MW_Direction_definitions
* @{
*/
#define MW_DIRECTION_SLAVE_TO_MASTER (0)
#define MW_DIRECTION_MASTER_TO_SLAVE (1)
/**
* @}
*/
/** @defgroup SPI_MW_TMOD_definitions
* @{
*/
#define MW_TMOD_NONSEQUENTIAL (0)
#define MW_TMOD_SEQUENTIAL (1)
/**
* @}
*/
/** @defgroup SPI_FIFO_depth_definitions
* @{
*/
#define SSI_TX_FIFO_DEPTH (64)
#define SSI_RX_FIFO_DEPTH (64)
/**
* @}
*/
/**
* @}
*/
/* Exported functions --------------------------------------------------------*/
/** @defgroup SPI_Exported_Functions SPI Exported Functions
* @{
*/
/** @defgroup SPI_Exported_Normal_Functions SPI Exported Normal Functions
* @{
*/
_LONG_CALL_ void SSI_Cmd(SPI_TypeDef *spi_dev, u32 NewStaus);
_LONG_CALL_ void SSI_SetSclkPolarity(SPI_TypeDef *spi_dev, u32 SclkPolarity);
_LONG_CALL_ void SSI_SetSclkPhase(SPI_TypeDef *spi_dev, u32 SclkPhase);
_LONG_CALL_ void SSI_WriteData(SPI_TypeDef *spi_dev, u32 value);
_LONG_CALL_ VOID SSI_INTConfig(SPI_TypeDef* spi_dev, u32 SSI_IT, u32 newState);
_LONG_CALL_ void SSI_SetRxFifoLevel(SPI_TypeDef *spi_dev, u32 RxThresholdLevel);
_LONG_CALL_ void SSI_SetTxFifoLevel(SPI_TypeDef *spi_dev, u32 TxThresholdLevel);
_LONG_CALL_ void SSI_SetSlaveEnable(SPI_TypeDef *spi_dev, u32 SlaveIndex);
_LONG_CALL_ u32 SSI_Busy(SPI_TypeDef *spi_dev);
_LONG_CALL_ u32 SSI_Writeable(SPI_TypeDef *spi_dev);
_LONG_CALL_ u32 SSI_Readable(SPI_TypeDef *spi_dev);
_LONG_CALL_ u32 SSI_GetRxCount(SPI_TypeDef *spi_dev);
_LONG_CALL_ u32 SSI_GetTxCount(SPI_TypeDef *spi_dev);
_LONG_CALL_ u32 SSI_GetStatus(SPI_TypeDef *spi_dev);
_LONG_CALL_ u32 SSI_GetIsr(SPI_TypeDef *spi_dev);
_LONG_CALL_ u32 SSI_ReadData(SPI_TypeDef *spi_dev);
_LONG_CALL_ u32 SSI_ReceiveData(SPI_TypeDef *spi_dev, void* RxData, u32 Length);
_LONG_CALL_ u32 SSI_SendData(SPI_TypeDef *spi_dev, void* TxData, u32 Length, u32 Role);
_LONG_CALL_ u32 SSI_GetRawIsr(SPI_TypeDef *spi_dev);
_LONG_CALL_ u32 SSI_GetSlaveEnable(SPI_TypeDef *spi_dev);
_LONG_CALL_ u32 SSI_GetDataFrameSize(SPI_TypeDef *spi_dev);
_LONG_CALL_ void SSI_Init(SPI_TypeDef *spi_dev, SSI_InitTypeDef *SSI_InitStruct);
_LONG_CALL_ void SSI_StructInit(SSI_InitTypeDef* SSI_InitStruct);
_LONG_CALL_ void SSI_SetDataFrameSize(SPI_TypeDef *spi_dev, u32 DataFrameSize);
_LONG_CALL_ void SSI_SetBaud(SPI_TypeDef *SPIx, u32 BaudRate, u32 IpClk);
_LONG_CALL_ void SSI_SetIsrClean(SPI_TypeDef *spi_dev, u32 InterruptStatus);
_LONG_CALL_ void SSI_SetReadLen(SPI_TypeDef *spi_dev, u32 DataFrameNumber);
_LONG_CALL_ void SSI_PinmuxInit(u8 Index, u32 PinmuxSelect);
_LONG_CALL_ void SSI_PinmuxDeInit(u8 Index, u32 PinmuxSelect);
/**
* @}
*/
/** @defgroup SPI_Exported_DMA_Functions SPI Exported DMA Functions
* @{
*/
_LONG_CALL_ BOOL SSI_TXGDMA_Init(u32 Index, PGDMA_InitTypeDef GDMA_InitStruct, void *CallbackData,
IRQ_FUN CallbackFunc, u8 *pTxData, u32 Length);
_LONG_CALL_ BOOL SSI_RXGDMA_Init(u8 Index, GDMA_InitTypeDef *GDMA_InitStruct, void *CallbackData,
IRQ_FUN CallbackFunc, u8 *pRxData, u32 Length);
_LONG_CALL_ void SSI_SetDmaEnable(SPI_TypeDef *spi_dev, u32 newState, u32 Mask);
_LONG_CALL_ void SSI_SetDmaLevel(SPI_TypeDef *spi_dev, u32 TxLeve, u32 RxLevel);
/**
* @}
*/
/**
* @}
*/
/* Registers Definitions --------------------------------------------------------*/
/**************************************************************************//**
* @defgroup SPI_Register_Definitions SPI Register Definitions
* @{
*****************************************************************************/
/**************************************************************************//**
* @defgroup CTRLR0
* @{
*****************************************************************************/
#define BIT_CTRLR0_DFS ((u32)0x0000000F)
#define BIT_CTRLR0_FRF ((u32)0x00000003 << 4)
#define BIT_CTRLR0_SCPH ((u32)0x00000001 << 6)
#define BIT_CTRLR0_SCPOL ((u32)0x00000001 << 7)
#define BIT_CTRLR0_TMOD ((u32)0x00000003 << 8)
#define BIT_CTRLR0_SLV_OE ((u32)0x00000001 << 10)
#define BIT_CTRLR0_SRL ((u32)0x00000001 << 11)
#define BIT_CTRLR0_CFS ((u32)0x0000000F << 12)
/** @} */
/**************************************************************************//**
* @defgroup CTRLR1
* @{
*****************************************************************************/
#define BIT_CTRLR1_NDF ((u32)0x0000FFFF)
/** @} */
/**************************************************************************//**
* @defgroup SSIENR
* @{
*****************************************************************************/
#define BIT_SSIENR_SSI_EN ((u32)0x00000001)
/** @} */
/**************************************************************************//**
* @defgroup MWCR
* @{
*****************************************************************************/
#define BIT_MWCR_MWMOD ((u32)0x00000001)
#define BIT_MWCR_MDD ((u32)0x00000001 << 1)
#define BIT_MWCR_MHS ((u32)0x00000001 << 2)
/** @} */
/**************************************************************************//**
* @defgroup SER
* @{
*****************************************************************************/
#define BIT_SER_SER ((u32)0x0000FFFF)
/** @} */
/**************************************************************************//**
* @defgroup BAUDR
* @{
*****************************************************************************/
#define BIT_BAUDR_SCKDV ((u32)0x0000FFFF)
/** @} */
/**************************************************************************//**
* @defgroup TXFLTR
* @{
*****************************************************************************/
#define BIT_TXFTLR_TFT ((u32)0x0000003F)//(TX_ABW-1):0
/** @} */
/**************************************************************************//**
* @defgroup RXFLTR
* @{
*****************************************************************************/
#define BIT_RXFTLR_RFT ((u32)0x0000003F) // (RX_ABW-1):0
/** @} */
/**************************************************************************//**
* @defgroup TXFLR
* @{
*****************************************************************************/
#define BIT_MASK_TXFLR_TXTFL ((u32)0x0000007F) // (TX_ABW):0
/** @} */
/**************************************************************************//**
* @defgroup RXFLR
* @{
*****************************************************************************/
#define BIT_MASK_RXFLR_RXTFL ((u32)0x0000007F) // (RX_ABW):0
/** @} */
/**************************************************************************//**
* @defgroup SR
* @{
*****************************************************************************/
#define BIT_SR_BUSY ((u32)0x00000001)
#define BIT_SR_TFNF ((u32)0x00000001 << 1)
#define BIT_SR_TFE ((u32)0x00000001 << 2)
#define BIT_SR_RFNE ((u32)0x00000001 << 3)
#define BIT_SR_RFF ((u32)0x00000001 << 4)
#define BIT_SR_TXE ((u32)0x00000001 << 5)
#define BIT_SR_DCOL ((u32)0x00000001 << 6)
/** @} */
/**************************************************************************//**
* @defgroup IMR
* @{
*****************************************************************************/
#define BIT_IMR_TXEIM ((u32)0x00000001)
#define BIT_IMR_TXOIM ((u32)0x00000001 << 1)
#define BIT_IMR_RXUIM ((u32)0x00000001 << 2)
#define BIT_IMR_RXOIM ((u32)0x00000001 << 3)
#define BIT_IMR_RXFIM ((u32)0x00000001 << 4)
#define BIT_IMR_MSTIM ((u32)0x00000001 << 5)
/** @} */
/**************************************************************************//**
* @defgroup ISR
* @{
*****************************************************************************/
#define BIT_ISR_TXEIS ((u32)0x00000001)
#define BIT_ISR_TXOIS ((u32)0x00000001 << 1)
#define BIT_ISR_RXUIS ((u32)0x00000001 << 2)
#define BIT_ISR_RXOIS ((u32)0x00000001 << 3)
#define BIT_ISR_RXFIS ((u32)0x00000001 << 4)
#define BIT_ISR_MSTIS ((u32)0x00000001 << 5)
/** @} */
/**************************************************************************//**
* @defgroup RISR
* @{
*****************************************************************************/
#define BIT_RISR_TXEIR ((u32)0x00000001)
#define BIT_RISR_TXOIR ((u32)0x00000001 << 1)
#define BIT_RISR_RXUIR ((u32)0x00000001 << 2)
#define BIT_RISR_RXOIR ((u32)0x00000001 << 3)
#define BIT_RISR_RXFIR ((u32)0x00000001 << 4)
#define BIT_RISR_MSTIR ((u32)0x00000001 << 5)
/** @} */
/**************************************************************************//**
* @defgroup DMACR
* @{
*****************************************************************************/
#define BIT_SHIFT_DMACR_RDMAE ((u32)0x00000001)
#define BIT_SHIFT_DMACR_TDMAE ((u32)0x00000001 << 1)
/** @} */
/**************************************************************************//**
* @defgroup DMATDLR
* @{
*****************************************************************************/
#define BIT_DMATDLR_DMATDL ((u32)0x0000003F) // (TX_ABW-1):0
/** @} */
/**************************************************************************//**
* @defgroup DMARDLR
* @{
*****************************************************************************/
#define BIT_DMARDLR_DMARDL ((u32)0x0000003F )// (RX_ABW-1):0
/** @} */
/**************************************************************************//**
* @defgroup DR
* @{
*****************************************************************************/
#define BIT_DR_DR ((u32)0x0000FFFF)
/** @} */
/** @} */
/**
* @}
*/
/**
* @}
*/
/* Other Definitions --------------------------------------------------------*/
typedef struct
{
SPI_TypeDef* SPIx;
u32 Tx_HandshakeInterface;
u32 Rx_HandshakeInterface;
IRQn_Type IrqNum;
} SPI_DevTable;
extern const SPI_DevTable SPI_DEV_TABLE[2];
#endif //_RTL8710B_SPI_H_
/******************* (C) COPYRIGHT 2016 Realtek Semiconductor *****END OF FILE****/

View file

@ -0,0 +1,302 @@
/**
******************************************************************************
* @file rtl8711b_syscfg.h
* @author
* @version V1.0.0
* @date 2016-05-17
* @brief This file contains all the functions prototypes for SYSCFG firmware
* library.
******************************************************************************
* @attention
*
* This module is a confidential and proprietary property of RealTek and
* possession or use of this module requires written permission of RealTek.
*
* Copyright(c) 2015, Realtek Semiconductor Corporation. All rights reserved.
******************************************************************************
*/
#ifndef _RTL8710B_SYSCFG_H_
#define _RTL8710B_SYSCFG_H_
/** @addtogroup AmebaZ_Platform
* @{
*/
/** @defgroup SYSCFG
* @brief SYSCFG driver modules
* @{
*/
/** @addtogroup SYSCFG
* @verbatim
*****************************************************************************************
* Introduction
*****************************************************************************************
* Used for system, user can not used it if not needed.
*
*****************************************************************************************
* REG_SYS_SYSTEM_CFG0 Introduction
*****************************************************************************************
*
* BIT[31] Trapped PKG_ENG_SEL value 0: normal package; 1: engineering mode
* BIT[30] CHIP_EN PIN input value
* BIT[27:24] BD info
* BIT[16] 1: Test chip; 0:MP
* BIT[11:8] Vendor ID
* BIT[7:4] Chip version
* BIT[3:0] Vendor ID defined in RF
*
*****************************************************************************************
* REG_SYS_SYSTEM_CFG1 Introduction
*****************************************************************************************
*
* BIT[31:28] is BIT_SYSCFG_TRP_ICFG, value is load from following trap pin:
* ICFG[0]/ICFG[1]/ICFG[2]/ICFG[3] when trap pin TSET_MODE_SEL = 1
* BIT[27] is BIT_SYSCFG_TRP_BOOT_SEL
* 0: boot normal, 1: uart flash download
* value load from trap pin UART_DOWNLOAD_IMAGE
* BIT[25] is BIT_SYSCFG_TRP_SPSLDO_SEL, Trapped Selection for SPS
* 0: SWR mode; 1: LDO mode
* load from trap pin SPS_LDO_SEL
* BIT[16] BIT_V15_VLD 1.5V Power Ready, 1: Power Ready
* BIT[9] BIT_SYS_SYSPLL_CLK_RDY SYS PLL Clock Stable, 1: Clock Stable
* BIT[8] BIT_SYS_XCLK_VLD Xtal Clock Stable, 1: Clock Stable
* BIT[0] BIT_SYSCFG_ALDN_STS 1: SYS CFG autoload done; 0; SYSCFG autoload not ready
*
*****************************************************************************************
* REG_SYS_SYSTEM_CFG2 Introduction
*****************************************************************************************
*
* BIT[7:0] ROM Information
*
*****************************************************************************************
* REG_SYS_EFUSE_SYSCFGx Introduction
*****************************************************************************************
*
* REG_SYS_EFUSE_SYSCFG0: load from EFUSE 0x00~0x03
* REG_SYS_EFUSE_SYSCFG1: load from EFUSE 0x04~0x07
* REG_SYS_EFUSE_SYSCFG2: load from EFUSE 0x08~0x0B
* REG_SYS_EFUSE_SYSCFG3: load from EFUSE 0x0C~0x0F
* REG_SYS_EFUSE_SYSCFG4: load from EFUSE 0x10~0x13
* REG_SYS_EFUSE_SYSCFG5: load from EFUSE 0x14~0x17
* REG_SYS_EFUSE_SYSCFG6: load from EFUSE 0x18~0x1B
* REG_SYS_EFUSE_SYSCFG7: load from EFUSE 0x1C~0x1F
*
*****************************************************************************************
* trap pins
*****************************************************************************************
*
* GPIOA_0:
* TEST_MODE_SEL
* default PD
*
* GPIOA_3:
* SPS_LDO_SEL
* default PU, internal PU
* 0: SWR 1: LDO
* load to 0x1F4[25]
*
* GPIOA_30:
* UART_DOWNLOAD_IMAGE
* default PU
* load to 0x1F4[27]
*
*****************************************************************************************
* @endverbatim
*/
/* Exported constants --------------------------------------------------------*/
/** @defgroup SYSCFG_Exported_Constants SYSCFG Exported Constants
* @{
*/
/** @defgroup SYSCFG_Bounding_Option_definitions
* @{
*/
#define SYSCFG_BD_QFN32 ((u32)0x000000000)
#define SYSCFG_BD_QFN48_MCM_8MBFlash ((u32)0x000000001)
#define SYSCFG_BD_QFN48 ((u32)0x000000002)
#define SYSCFG_BD_QFN48_NEW ((u32)0x000000000)
#define SYSCFG_BD_QFN68 ((u32)0x000000007)
#define SYSCFG_BD_QFN68_NEW ((u32)0x000000005)
#define SYSCFG_BD_TFBGA_MCM_8761A ((u32)0x000000004)
/**
* @}
*/
/**
* @}
*/
/* Exported functions --------------------------------------------------------*/
/** @defgroup SYSCFG_Exported_Functions SYSCFG Exported Functions
* @{
*/
_LONG_CALL_ u32 SYSCFG0_Get(void);
_LONG_CALL_ u32 SYSCFG0_CUTVersion(void);
_LONG_CALL_ u32 SYSCFG0_BDOption(void);
_LONG_CALL_ u32 SYSCFG1_Get(void);
_LONG_CALL_ u32 SYSCFG1_AutoLoadDone(void);
_LONG_CALL_ u32 SYSCFG1_TRP_LDOMode(void);
_LONG_CALL_ u32 SYSCFG1_TRP_UARTImage(void);
_LONG_CALL_ u32 SYSCFG1_TRP_ICFG(void);
_LONG_CALL_ u32 SYSCFG2_Get(void);
_LONG_CALL_ u32 SYSCFG2_ROMINFO_Get(void);
_LONG_CALL_ void SYSCFG2_ROMINFO_Set(void);
/**
* @}
*/
/* Registers Definitions --------------------------------------------------------*/
/**************************************************************************//**
* @defgroup SYSCFG_Register_Definitions SYSCFG Register Definitions
* @{
*****************************************************************************/
/**************************************************************************//**
* @defgroup REG_SYS_EFUSE_SYSCFG0
* @{
*****************************************************************************/
#define BIT_MASK_SYS_EEROM_SWR_PAR_05_00 (0x0000003F << 24)
#define BIT_MASK_SYS_EEROM_LDO_PAR_07_04 (0x0000000F << 20)
#define BIT_SYS_CHIPPDN_EN (0x00000001 << 17) /* 0:reset pin just give interrupt; 1:reset pin will powerdown chip directy */
#define BIT_SYS_EEROM_B12V_EN (0x00000001 << 16)
#define BIT_MASK_SYS_EEROM_VID1 (0x000000FF << 8)
#define BIT_MASK_SYS_EEROM_VID0 (0x000000FF)
/** @} */
/**************************************************************************//**
* @defgroup REG_SYS_EFUSE_SYSCFG1
* @{
*****************************************************************************/
#define BIT_MASK_SYS_PDSPL_STL (0x00000003 << 24)
#define BIT_MASK_SYS_PDSOC_STL (0x00000003 << 22)
#define BIT_MASK_SYS_PDPON_STL (0x00000003 << 20)
#define BIT_MASK_SYS_SWREG_XRT (0x00000003 << 18)
#define BIT_MASK_SYS_SWSLC_STL (0x00000003 << 16)
#define BIT_MASK_SYS_EEROM_SWR_PAR_46_45 (0x00000003 << 14)
#define BIT_MASK_SYS_EEROM_SWR_PAR_40_39 (0x00000003 << 12)
#define BIT_MASK_SYS_EEROM_SWR_PAR_33_26 (0x000000ff << 4)
#define BIT_MASK_SYS_EEROM_SWSLD_VOL (0x00000007)
/** @} */
/**************************************************************************//**
* @defgroup REG_SYS_EFUSE_SYSCFG2
* @{
*****************************************************************************/
#define BIT_MASK_SYS_EERROM_ANAPAR_SPLL_24_15 (0x000003ff << 21)
#define BIT_MASK_SYS_EEROM_ANAPAR_SPLL_05_02 (0x0000000f << 16)
#define BIT_MASK_SYS_EEROM_XTAL_STEL_SEL (0x00000003 << 12)
#define BIT_MASK_SYS_EEROM_XTAL_FREQ_SEL (0x0000000f << 8)
/** @} */
/**************************************************************************//**
* @defgroup REG_SYS_EFUSE_SYSCFG3
* @{
*****************************************************************************/
#define BIT_MASK_SYS_DBG_PINGP_EN (0x0000000f << 28)
#define BIT_MASK_SYS_DBG_SEL (0x00000fff << 16)
#define BIT_MASK_SYS_DBGBY3_LOC_SEL (0x00000003 << 14)
#define BIT_MASK_SYS_DBGBY2_LOC_SEL (0x00000003 << 12)
#define BIT_MASK_SYS_DBGBY1_LOC_SEL (0x00000003 << 10)
#define BIT_MASK_SYS_DBGBY0_LOC_SEL (0x00000003 << 8)
#define BIT_SYS_EEROM_ANAPAR_SPLL_49 (0x00000001 << 3)
#define BIT_MASK_SYS_EEROM_ANAPAR_SPLL_27_25 (0x00000007)
/** @} */
/**************************************************************************//**
* @defgroup REG_SYS_EFUSE_SYSCFG4
* @{
*****************************************************************************/
#define BIT_MASK_SYS_GPIOA_E2 (0x00000007 << 1)
#define BIT_SYS_GPIOA_H3L1 (0x00000001)
/** @} */
/**************************************************************************//**
* @defgroup REG_SYS_EFUSE_SYSCFG6
* @{
*****************************************************************************/
#define BIT_SYS_ICFG2_TEST (0x00000001 << 31)
#define BIT_MASK_SYS_BOOT_TYPE_SEL (0x00000003 << 28)
#define BIT_MASK_SYS_CPU_CLK_SEL (0x00000003 << 26)
#define BIT_SYS_FLASH_DEEP_SLEEP_EN (0x00000001 << 25)
#define BIT_SYS_SPIC_PARA_EN (0x00000001 << 24)
#define BIT_USB_AUTOINSTALL_EN (0x00000001 << 6)
#define BIT_USB_AUTOLOAD_UPHY_EN (0x00000001 << 7)
/* 0x19 */
#define BIT_SYS_DIS_BOOT_LOG_EN (0x00000001 << 15)
#define BIT_SYS_UART2_DEFAULT_GPIO (0x00000001 << 14) /*!< 0: PA29 & PA30, 1: PA16 & PA17 */
#define BIT_SYS_FLASH_ENCRYPT_EN (0x00000001 << 13)
#define BIT_SYS_SDIO_FEN (0x00000001 << 1) /*!< SDIO Function enable */
#define BIT_SYS_SDIO_GP_SEL (0x00000001 << 0) /*!< SDIO Pinmux selection 0: GPIOA_18 ~ GPIOA_23 1: GPIOA_6 ~ GPIOA_11 */
/** @} */
/**************************************************************************//**
* @defgroup REG_SYS_EFUSE_SYSCFG7
* @{
*****************************************************************************/
#define BIT_SYS_MEM_RMV_SIGN (0x00000001 << 31)
#define BIT_SYS_MEM_RMV_1PRF1 (0x00000001 << 29)
#define BIT_SYS_MEM_RMV_1PRF0 (0x00000001 << 28)
#define BIT_SYS_MEM_RMV_1PSR (0x00000001 << 27)
#define BIT_SYS_MEM_RMV_1PHSR (0x00000001 << 26)
#define BIT_SYS_MEM_RMV_ROM (0x00000001 << 25)
#define BIT_MASK_SYS_MEM_RME_CPU (0x00000007 << 22)
#define BIT_MASK_SYS_MEM_RME_WLAN (0x00000007 << 19)
#define BIT_SYS_MEM_RME_USB (0x00000001 << 18)
#define BIT_SYS_MEM_RME_SDIO (0x00000001 << 17)
/** @} */
/**************************************************************************//**
* @defgroup REG_SYS_SYSTEM_CFG0
* @{
*****************************************************************************/
#define BIT_SYSCFG_RF_RL_ID (0x0000000F) /*!< Vendor ID defined in RF */
#define BIT_MASK_SYSCFG_CUT_VER (0x0000000F << 4)
#define BIT_MASK_SYSCFG_VENDOR_ID (0x0000000F << 8)
#define BIT_MASK_SYSCFG_CHIP_TYPE (0x00000001 << 16)
#define BIT_MASK_SYSCFG_BD_OPT (0x0000000F << 24)
#define BIT_SYSCFG_BD_PKG_SEL (0x00000001 << 31)
/** @} */
/**************************************************************************//**
* @defgroup REG_SYS_SYSTEM_CFG1
* @{
*****************************************************************************/
#define BIT_MASK_SYSCFG_TRP_ICFG (0x0000000f << 28)
#define BIT_SysCFG_TRP_SPSLDO_SEL (0x00000001 << 25)
#define BIT_SysCFG_TRP_UART_IMAGE (0x00000001 << 27)
#define BIT_V15_VLD (0x00000001 << 16)
#define BIT_SYS_SYSPLL_CLK_RDY (0x00000001 << 9)
#define BIT_SYS_XCLK_VLD (0x00000001 << 8)
#define BIT_SYSCFG_ALDN_STS (0x00000001 << 0)
/** @} */
/**************************************************************************//**
* @defgroup REG_SYS_SYSTEM_CFG2
* @{
*****************************************************************************/
#define BIT_MASK_SYSCFG_ROM_INFO (0x000000FF)
/** @} */
/** @} */
/**
* @}
*/
/**
* @}
*/
/* Other definations --------------------------------------------------------*/
/******************* Macro definition for TRP_ICFG ********************/
#define SYSCFG_TRP_ICFG_STOP_IN_ROMBOOT 2
#define SYSCFG_TRP_ICFG_FLASH_LOCATION 3 /* Ameba1 used, AmebaZ not use */
#endif //_RTL8710B_SYSCFG_H_
/******************* (C) COPYRIGHT 2016 Realtek Semiconductor *****END OF FILE****/

View file

@ -0,0 +1,618 @@
/**
******************************************************************************
* @file rtl8711b_tim.h
* @author
* @version V1.0.0
* @date 2016-05-17
* @brief This file contains all the functions prototypes for the Timer firmware
* library.
******************************************************************************
* @attention
*
* This module is a confidential and proprietary property of RealTek and
* possession or use of this module requires written permission of RealTek.
*
* Copyright(c) 2015, Realtek Semiconductor Corporation. All rights reserved.
******************************************************************************
*/
#ifndef _RTL8711B_TIMER_H_
#define _RTL8711B_TIMER_H_
/** @addtogroup AmebaZ_Periph_Driver
* @{
*/
/** @defgroup Timer
* @brief Timer driver modules
* @{
*/
/** @addtogroup Timer
* @verbatim
*****************************************************************************************
* Introduction
*****************************************************************************************
* TIM0/TIM1/TIM2/TIM3: used as generic timers for time-base generation
* - Base Address: TIM0/TIM1/TIM2/TIM3
* - Clock Source: 32kHz
* - Resolution: 32bit
* - Count Mode: Upcounting
* - Interrupt Generation
* - Support Upcounting mode
* TIM4:
* - Base Address: TIM4
* - Channels: 1
* - Clock Source: XTAL, normally is 40MHz
* - Resolution: 16bit
* - Prescaler: 8bit
* - Count Mode: Upcounting
* - Input Pin: 1 input capture
* - Interrupt/DMA Generation
* - Support Upcounting mode/Statistic Pulse Width mode/Statistic Pulse Number mode
* TIM5:
* - Base Address: TIM5
* - Channels: 6
* - Clock Source: XTAL, normally is 40MHz
* - Resolution: 16bit
* - Prescaler: 8bit
* - Count Mode: Upcounting
* - Interrupt/DMA Generation
* - Input Pin: 1 input capture
* - Ouput Pin: 6 PWM out
* - Support Upcounting mode/Input capture mode/PWM mode/One Pulse mode
*
*****************************************************************************************
* Sys Timer
*****************************************************************************************
* - TIM0 is used as systimer, so TIM0 can not be used for other purpose, see DELAY charpter for more information
*
*****************************************************************************************
* PIN LOCATION
*****************************************************************************************
* TIM4:
* - Input Pin (TRIG): PA_18
*
* TIM5:
* - Input Pin (TRIG): PA_19
* - Output Pin:
* channel 0 channel 1 channel 2 channel 3 channel 4 channel 5
* S0: PA_23 PA_15 PA_0 PA_30 PA_13 PA_22
* S1: PA_14 PA_16 PA_17 PA_12 PA_5 NULL
* S2: NULL NULL NULL PA_21 PA_29 NULL
*
*****************************************************************************************
* Upcounting mode
*****************************************************************************************
* TIM0~5 support
* The counter counts from 0 to the auto-reload value (content of the TIMx_ARR register),
* then restarts from 0 and generates a counter overflow interrupt.
*
*****************************************************************************************
* Statistic Pulse Width mode
*****************************************************************************************
* Only TIM4 support
* TIM4 can statistic the width of active level of TRGI. When the TRGI is transferred from
* inactive level to active level, the counter is enabled automatically and counter starts
* from 0. When the TRGI is transferred from active level to inactive level , the counter
* is disabled automatically, the current counter value will be copied to CCR0 field of
* TIMx_CCR0, the CCxIF will be set and an interrupt or a DMA request can be sent if they
* are enabled.
*
*****************************************************************************************
* Statistic Pulse Number mode
*****************************************************************************************
* Only TIM4 support
* TIM4 can statistic the number of active edge of TRGI in the given period. When the
* counter overflow, the number will be copied to CCR0 field of TIMx_CCR0, the CCxIF will
* be set and an interrupt or a DMA request can be sent if they are enabled
*
*****************************************************************************************
* Input capture mode
*****************************************************************************************
* Only TIM5 supports
* In input capture mode, the CCRx field of TIMx_CCRx are used to latch the value of the
* counter after a transition detected by the TRGI signal. When a capture occurs, the
* corresponding CCXIF flag (TIMx_SR register) is set and an interrupt or a DMA request
* can be sent if they are enabled.
*
*****************************************************************************************
* PWM mode
*****************************************************************************************
* Only TIM5 supports
* Pulse Width Modulation mode allows you to generate a signal with a frequency determined
* by the value of the TIMx_ARR register and a duty cycle determined by the value of the
* CCRx field of TIMx_CCRx register.
* Period = (ARR + 1)*Tcnt, Duty cycle = (CCRx+1)*Tcnt/Period, where Tcnt = Txtal *(PSC+1).
*
*****************************************************************************************
* One Pulse mode
*****************************************************************************************
* Only TIM5 supports
* This mode allows the counter to be started in response to a stimulus and to generate
* a pulse with a programmable length after a programmable delay. Starting the counter can
* be controlled through the active edge of TRGI. Generating the waveform can be done in PWM
* mode. You select One-pulse mode by setting the OPM bit in the TIMx_CR register. This makes
* the counter stop automatically at the next update event.
*
* NOTICE: you shoud pull up/down the pwm pin (PAD_PullCtrl) when you use one pulse mode based on polarity
*
*****************************************************************************************
* How to use Base Timer
*****************************************************************************************
* To use the Timer in Timing(Time base) mode, the following steps are mandatory:
*
* 1. Enable TIM clock :
* RCC_PeriphClockCmd(APBPeriph_GTIMER, APBPeriph_GTIMER_CLOCK, ENABLE)
*
* 2. Fill the TIM_InitStruct with default parameters using:
* RTIM_TimeBaseStructInit(&TIM_InitStruct)
* or setting the desired parameters manually.
*
* 3. Configure the Time Base unit with the corresponding configurations, register TimerIRQHandler
* and enable the NVIC if you need to generate the update interrupt.
* RTIM_TimeBaseInit(TIMx, &TIM_InitStruct, IrqNum, UserCB, UserCBData)
*
* 4. Enable the corresponding interrupt using :
* RTIM_INTConfig(TIMx, TIM_IT_Update, ENABLE)
*
* 5. Enable the TIM counter.
* RTIM_Cmd(TIMx, ENABLE)
*
* Note1: All other functions can be used separately to modify, if needed,
* a specific feature of the Timer.
*
*****************************************************************************************
* How to use Timer in Capture Compare Mode
*****************************************************************************************
* To use the Timer in CC mode, the following steps are mandatory:
*
* 1. Enable TIM clock :
* RCC_PeriphClockCmd(APBPeriph_GTIMER, APBPeriph_GTIMER_CLOCK, ENABLE)
*
* 2. Configure the TIM pinmux:
* Pinmux_Config(PinName, PinFunc)
*
* 3. Configure the Time base unit as described in the first part of this driver if needed,
* else the Timer will run with the default configuration:
* - Autoreload value = 0xFFFF
* - Prescaler value = 0x0000
*
* 4. Fill the TIM_CCInitStruct with the desired parameters including:
* - The TIM Output Compare mode: TIM_CCMode
* - TIM Output Compare Pulse value: TIM_OCMPulse
* - TIM Output Compare Polarity : TIM_CCPolarity
* - TIM Output Compare value update protection: TIM_OCProtection
*
* 5. Configure the desired channel with the corresponding configuration
* RTIM_CCxInit(TIMx, &TIM_CCInitStruct, TIM_Channel)
*
* 6. Enable corresponding TIM channel.
* RTIM_CCxCmd(TIMx, TIM_Channel, TIM_CCx_Enable)
*
* 7. Enable the TIM counter.
* RTIM_Cmd(TIMx, ENABLE)
*
* Note1: All other functions can be used separately to modify, if needed,
* a specific feature of the Timer.
*
* Note2: In case of PWM mode, the TIMx peripheral Preload register on CCRx(TIM_OCProtection)
* should be enabled.
*
* Note3: If the corresponding interrupt or DMA request are needed, the user should:
* 1. Enable the NVIC (or the DMA) to use the TIM interrupts (or DMA requests).
* 2. Enable the corresponding interrupt (or DMA request) using the function
* RTIM_ITConfig(TIMx, TIM_IT_CCx, ENABLE) (or RTIM_DMACmd(TIMx, TIM_DMA_CCx, ENABLE))
* 3. GDMA related configurations(source address/destination address/block size etc.)
* if needed, by calling:
* GDMA_ChnlAlloc()
* GDMA_Init()
* GDMA_Cmd()
*
* @endverbatim
*/
/* Exported types ------------------------------------------------------------*/
/** @defgroup TIM_Exported_Types TIM Exported Types
* @{
*/
/**
* @brief TIM Basic Init structure definition
*/
typedef struct {
u32 TIM_Prescaler; /*!< Specifies the prescaler value used to divide the TIM clock.
This parameter can be a number between 0x00 and 0xFF, basic timer dont care */
u32 TIM_Period; /*!< Specifies the period value to be loaded into the active
Auto-Reload Register at the next update event.
This parameter is 16bits for TIM4-5, and 32bits for TIM0-TIM3
you can get it from SourceClock & TIM_Prescaler */
u32 TIM_UpdateEvent; /*!< Specifies whether or not to enable update event(UEV).
This parameter can be ENABLE or DISABLE. ENABLE means UEV Enable, DISABLE means UEV Disable*/
u32 TIM_UpdateSource; /*!< Specifies the update request source. This parameter can be
TIM_UpdateSource_Overflow or TIM_UpdateSource_Global.
TIM_UpdateSource_Overflow means counter overflow generates an update event(UEV).
TIM_UpdateSource_Global means both counter overflow and setting the UG bit can generate UEV.*/
u32 TIM_ARRProtection; /*!< DISABLE or ENABLE, when ENABLE: period will update when cnt = 0(counter overflow, an UEV happens),
or period will update immediatly */
u8 TIM_Idx; /*!< 0~5 */
} RTIM_TimeBaseInitTypeDef;
/**
* @brief TIM Output Compare Init structure definition
*/
typedef struct
{
u32 TIM_CCMode; /*!< Specifies the TIM5 mode. This parameter can be a value of TIM_CCMode_PWM or TIM_CCMode_Inputcapture */
u32 TIM_CCPolarity; /*!< Specifies the polarity. This parameter can be TIM_CCPolarity_High/TIM_CCPolarity_Low.
If CCx channel is configured as output:
TIM_CCPolarity_High means OCx active high.
TIM_CCPolarity_Low means OCx active low.
If CCx channel is configured as input:
TIM_CCPolarity_High means positive edge of TRGI is active for capture.
TIM_CCPolarity_Low means negative edge of TRGI is active for capture. */
u32 TIM_OCProtection; /*!< Output Compare value update protection. TIM_OCPreload_Enable/TIM_OCPreload_Disable.
TIM_OCPreload_Enable means duty cycle will update when UEV happens if write to CCRx field in TIMx_CCRX.
TIM_OCPreload_Disable means duty cycle will update immediately if write to CCRx field in TIMx_CCRX.*/
u32 TIM_OCPulse; /*!< Specifies the output pulse value to be loaded into the CCRx Register, which decides the duty cycle.
This parameter can be a number between 0x0000 and 0xFFFF */
u32 TIM_ICPulseMode; /*!< Specifies the TIM4 mode, TIM_CCMode_PulseWidth or TIM_CCMode_PulseNumber */
} TIM_CCInitTypeDef;
/**
* @}
*/
/* Exported constants --------------------------------------------------------*/
/** @defgroup TIM_Exported_constants TIM Exported constants
* @{
*/
/** @defgroup TIM_Type_definitions
* @{
*/
#define IS_TIM_ALL_TIM(PERIPH) (((PERIPH) == TIM0) || \
((PERIPH) == TIM1) || \
((PERIPH) == TIM2) || \
((PERIPH) == TIM3) || \
((PERIPH) == TIM4) || \
((PERIPH) == TIM5))
#define IS_TIM_ONE_PULSE_TIM(PERIPH) ((PERIPH) == TIM5)
#define IS_TIM_CCM_TIM(PERIPH) (((PERIPH) == TIM4) || \
((PERIPH) == TIM5))
#define IS_TIM_PWM_TIM(PERIPH) ((PERIPH) == TIM5)
#define IS_TIM_INPULSE_TIM(PERIPH) ((PERIPH) == TIM4)
#define IS_TIM_DMA_TIM(PERIPH) (((PERIPH) == TIM4) || \
((PERIPH) == TIM5))
#define IS_TIM_40M_TIM(PERIPH) (((PERIPH) == TIM4) || \
((PERIPH) == TIM5))
/**
* @}
*/
/** @defgroup TIM_Channel_definitions
* @{
*/
#define TIM_Channel_0 ((u16)0x0000)
#define TIM_Channel_1 ((u16)0x0001)
#define TIM_Channel_2 ((u16)0x0002)
#define TIM_Channel_3 ((u16)0x0003)
#define TIM_Channel_4 ((u16)0x0004)
#define TIM_Channel_5 ((u16)0x0005)
#define IS_TIM_CHANNEL(CHANNEL) (((CHANNEL) == TIM_Channel_0) || \
((CHANNEL) == TIM_Channel_1) || \
((CHANNEL) == TIM_Channel_2) || \
((CHANNEL) == TIM_Channel_3) || \
((CHANNEL) == TIM_Channel_4) || \
((CHANNEL) == TIM_Channel_5))
/**
* @}
*/
/** @defgroup TIMx_Prescaler_definitons
* @{
*/
#define IS_TIM_PSC(VAL) (VAL <= 0xFF)
/**
* @}
*/
/** @defgroup TIMx_Control_Bit_definitions
* @{
*/
#define TIM_OPMode_ETP_positive ((u32)0x00000000)
#define TIM_OPMode_ETP_negative ((u32)0x000000100)
#define IS_TIM_OPM_ETP_MODE(MODE) (((MODE) == TIM_OPMode_ETP_positive) || \
((MODE) == TIM_OPMode_ETP_negative))
#define TIM_OPMode_Single ((u32)0x00000008)
#define TIM_OPMode_Repetitive ((u32)0x00000000) /* repeative is PWM mode */
#define IS_TIM_OPM_MODE(MODE) (((MODE) == TIM_OPMode_Single) || \
((MODE) == TIM_OPMode_Repetitive))
#define TIM_UpdateSource_Global ((u32)0x00000000) /*!< Source of update is the counter overflow or the setting of UG bit. */
#define TIM_UpdateSource_Overflow ((u32)0x00000004) /*!< Source of update is counter overflow. */
#define IS_TIM_UPDATE_SOURCE(SOURCE) (((SOURCE) == TIM_UpdateSource_Global) || \
((SOURCE) == TIM_UpdateSource_Overflow))
/**
* @}
*/
/** @defgroup TIMx_DMA_and_Interrupt_Enable_definitions
* @{
*/
#define TIM_IT_Update ((u32)0x00000001)
#define TIM_IT_CC0 ((u32)0x00000002)
#define TIM_IT_CC1 ((u32)0x00000004)
#define TIM_IT_CC2 ((u32)0x00000008)
#define TIM_IT_CC3 ((u32)0x00000010)
#define TIM_IT_CC4 ((u32)0x00000020)
#define TIM_IT_CC5 ((u32)0x00000040)
#define IS_TIM_IT(IT) ((((IT) & (u32)0xFF80) == 0x0000) && (((IT) & (u32)0x7F) != 0x0000))
#define IS_TIM_GET_IT(IT) (((IT) == TIM_IT_Update) || \
((IT) == TIM_IT_CC0) || \
((IT) == TIM_IT_CC1) || \
((IT) == TIM_IT_CC2) || \
((IT) == TIM_IT_CC3) || \
((IT) == TIM_IT_CC4) || \
((IT) == TIM_IT_CC5))
#define TIM_DMA_Update ((u32)0x00000100)
#define TIM_DMA_CC0 ((u32)0x00000200)
#define TIM_DMA_CC1 ((u32)0x00000400)
#define TIM_DMA_CC2 ((u32)0x00000800)
#define TIM_DMA_CC3 ((u32)0x00001000)
#define TIM_DMA_CC4 ((u32)0x00002000)
#define TIM_DMA_CC5 ((u32)0x00004000)
#define IS_TIM_DMA_SOURCE(SOURCE) ((((SOURCE) & (u32)0x80FF) == 0x0000) && ((SOURCE) != 0x0000))
/**
* @}
*/
/** @defgroup TIMx_Event_Generation_definitons
* @{
*/
#define TIM_PSCReloadMode_Update ((u32)0x00000000)
#define TIM_PSCReloadMode_Immediate ((u32)0x00000001)
#define IS_TIM_PRESCALER_RELOAD(RELOAD) (((RELOAD) == TIM_PSCReloadMode_Update) || \
((RELOAD) == TIM_PSCReloadMode_Immediate))
#define TIM_EventSource_Update ((u32)0x00000001)
#define TIM_EventSource_CC0 ((u32)0x00000002)
#define TIM_EventSource_CC1 ((u32)0x00000004)
#define TIM_EventSource_CC2 ((u32)0x00000008)
#define TIM_EventSource_CC3 ((u32)0x00000010)
#define TIM_EventSource_CC4 ((u32)0x00000020)
#define TIM_EventSource_CC5 ((u32)0x00000040)
#define IS_TIM_EVENT_SOURCE(SOURCE) ((((SOURCE) & 0xFF80) == 0x0000) && \
(((SOURCE) & 0x7F) != 0x0000))
/**
* @}
*/
/** @defgroup TIMx_Capture_Compare_definitions
* @{
*/
#define TIM_CCx_Enable ((u32)0x01000000)
#define TIM_CCx_Disable ((u32)0x00000000)
#define IS_TIM_CCX(CCX) (((CCX) == TIM_CCx_Enable) || ((CCX) == TIM_CCx_Disable))
#define TIM_OCPreload_Enable ((u32)0x02000000)
#define TIM_OCPreload_Disable ((u32)0x00000000)
#define IS_TIM_OCPRELOAD_STATE(STATE) (((STATE) == TIM_OCPreload_Enable) || \
((STATE) == TIM_OCPreload_Disable))
#define TIM_CCPolarity_High ((u32)0x00000000) /*!< if input is set : Positive edge of TRGI is active for capture */
#define TIM_CCPolarity_Low ((u32)0x04000000) /*!< if input is set : negative edge of TRGI is active for capture */
#define IS_TIM_CC_POLARITY(POLARITY) (((POLARITY) == TIM_CCPolarity_High) || \
((POLARITY) == TIM_CCPolarity_Low))
/* TIM5 PWM or Inputcapture mode */
#define TIM_CCMode_PWM ((u32)0x00000000)
#define TIM_CCMode_Inputcapture ((u32)0x08000000)
#define IS_TIM_CC_MODE(MODE) (((MODE) == TIM_CCMode_PWM) || \
((MODE) == TIM_CCMode_Inputcapture))
/* TIM4 pulse mode */
#define TIM_CCMode_PulseWidth ((u32)0x00000000)
#define TIM_CCMode_PulseNumber ((u32)0x10000000)
#define IS_TIM_CC_PULSEMODE(MODE) (((MODE) == TIM_CCMode_PulseWidth) || \
((MODE) == TIM_CCMode_PulseNumber))
#define TIM_CCMode_CCR ((u32)0x0000FFFF)
#define IS_TIM_CC_PULSEWIDTH(Compare) ((Compare) <= TIM_CCMode_CCR)
/**
* @}
*/
/**
* @}
*/
/** @defgroup TIM_Exported_Functions TIM Exported Functions
* @{
*/
/** @defgroup TimeBase_Management_Functions TimeBase Management Functions
* @{
*/
_LONG_CALL_ void RTIM_TimeBaseStructInit(RTIM_TimeBaseInitTypeDef* TIM_InitStruct);
_LONG_CALL_ void RTIM_TimeBaseInit(RTIM_TypeDef* TIMx, RTIM_TimeBaseInitTypeDef* TIM_InitStruct, IRQn_Type IrqNum, IRQ_FUN UserCB, u32 UserCBData);
_LONG_CALL_ void RTIM_Cmd(RTIM_TypeDef* TIMx, u32 NewState);
_LONG_CALL_ void RTIM_DeInit(RTIM_TypeDef* TIMx);
_LONG_CALL_ u32 RTIM_GetCount(RTIM_TypeDef* TIMx);
_LONG_CALL_ void RTIM_UpdateDisableConfig(RTIM_TypeDef* TIMx, u32 NewState);
_LONG_CALL_ void RTIM_ARRPreloadConfig(RTIM_TypeDef* TIMx, u32 NewState);
_LONG_CALL_ void RTIM_UpdateRequestConfig(RTIM_TypeDef* TIMx, u32 TIM_UpdateSource);
_LONG_CALL_ void RTIM_PrescalerConfig(RTIM_TypeDef* TIMx, u32 Prescaler, u32 TIM_PSCReloadMode);
_LONG_CALL_ void RTIM_GenerateEvent(RTIM_TypeDef* TIMx, u32 TIM_EventSource);
_LONG_CALL_ void RTIM_ChangePeriod(RTIM_TypeDef* TIMx, u32 Autoreload);
_LONG_CALL_ void RTIM_Reset(RTIM_TypeDef* TIMx);
/**
* @}
*/
/** @defgroup Capture_Compare_Management_Functions Capture Compare Management Functions
* @{
*/
_LONG_CALL_ void RTIM_CCStructInit(TIM_CCInitTypeDef* TIM_CCInitStruct);
_LONG_CALL_ void RTIM_CCxInit(RTIM_TypeDef* TIMx, TIM_CCInitTypeDef* TIM_CCInitStruct, u16 TIM_Channel);
_LONG_CALL_ void RTIM_CCRxMode(RTIM_TypeDef* TIMx, u16 TIM_Channel, u32 TIM_CCMode);
_LONG_CALL_ void RTIM_CCRxSet(RTIM_TypeDef* TIMx, u32 Compare, u16 TIM_Channel);
_LONG_CALL_ u32 RTIM_CCRxGet(RTIM_TypeDef* TIMx, u16 TIM_Channel);
_LONG_CALL_ void RTIM_OCxPreloadConfig(RTIM_TypeDef* TIMx, u32 TIM_OCProtection, u16 TIM_Channel);
_LONG_CALL_ void RTIM_CCxPolarityConfig(RTIM_TypeDef* TIMx, u32 TIM_OCPolarity, u16 TIM_Channel);
_LONG_CALL_ void RTIM_CCxCmd(RTIM_TypeDef* TIMx, u16 TIM_Channel, u32 TIM_CCx);
_LONG_CALL_ void RTIM_SetOnePulseOutputMode(RTIM_TypeDef* TIMx, u32 TIM_OPMode, u32 TrigerPolarity);
/**
* @}
*/
/** @defgroup Interrupt_and_DMA_Management_Functions Interrupt and DMA Management Functions
* @{
*/
_LONG_CALL_ void RTIM_DMACmd(RTIM_TypeDef* TIMx, u16 TIM_DMASource, u32 NewState);
_LONG_CALL_ void RTIM_INTConfig(RTIM_TypeDef* TIMx, u32 TIM_IT, u32 NewState);
_LONG_CALL_ void RTIM_INTClear(RTIM_TypeDef* TIMx);
_LONG_CALL_ void RTIM_INTClearPendingBit(RTIM_TypeDef* TIMx, u16 TIM_IT);
_LONG_CALL_ u32 RTIM_GetFlagStatus(RTIM_TypeDef* TIMx, u32 TIM_FLAG);
_LONG_CALL_ u32 RTIM_GetINTStatus(RTIM_TypeDef* TIMx, u32 TIM_IT);
_LONG_CALL_ u32 RTIM_TXGDMA_Init(u32 TIM_Channel, GDMA_InitTypeDef *GdmaInitStruct, void *CallbackData, IRQ_FUN CallbackFunc, u8* pDataBuf, u32 DataLen);
_LONG_CALL_ u32 RTIM_RXGDMA_Init(u32 TIM_Idx, u32 TIM_Channel, GDMA_InitTypeDef *GdmaInitStruct, void *CallbackData, IRQ_FUN CallbackFunc, u8 *pDataBuf, int DataLen);
/**
* @}
*/
/**
* @}
*/
/* Registers Definitions --------------------------------------------------------*/
/**************************************************************************//**
* @defgroup TIM_Register_Definitions TIM Register Definitions
* @{
*****************************************************************************/
/**************************************************************************//**
* @defgroup TIM_EN
* @{
*****************************************************************************/
#define TIM_CR_CNT_START ((u32)0x00000001) /*!<Counter start */
#define TIM_CR_CNT_STOP ((u32)0x00000002) /*!<Counter stop */
#define TIM_CR_CNT_RUN ((u32)0x00000100) /*!<Counter run status. polling bit */
#define TIM_CR_CNT_STS ((u32)0x00010000) /*!<Counter working status, polling bit */
/** @} */
/**************************************************************************//**
* @defgroup TIM_CR
* @{
*****************************************************************************/
#define TIM_CR_UDIS ((u32)0x00000002) /*!<Update disable */
#define TIM_CR_URS ((u32)0x00000004) /*!<Update request source */
#define TIM_CR_OPM ((u32)0x00000008) /*!<One pulse mode */
#define TIM_CR_ARPE ((u32)0x00000010) /*!<Auto-reload preload enable */
#define TIM_CR_ETP ((u32)0x00000100) /*!<External trigger polarity for one pulse mode (TRGI). */
/** @} */
/**************************************************************************//**
* @defgroup TIM_DIER
* @{
*****************************************************************************/
/* Interrupt EN */
#define TIM_DIER_UIE ((u32)0x00000001) /*!<Update interrupt enable */
#define TIM_DIER_CC0IE ((u32)0x00000002) /*!<Capture/Compare 0 interrupt enable */
#define TIM_DIER_CC1IE ((u32)0x00000004) /*!<Capture/Compare 1 interrupt enable */
#define TIM_DIER_CC2IE ((u32)0x00000008) /*!<Capture/Compare 2 interrupt enable */
#define TIM_DIER_CC3IE ((u32)0x00000010) /*!<Capture/Compare 3 interrupt enable */
#define TIM_DIER_CC4IE ((u32)0x00000020) /*!<Capture/Compare 4 interrupt enable */
#define TIM_DIER_CC5IE ((u32)0x00000040) /*!<Capture/Compare 5 interrupt enable */
/* DMA EN */
#define TIM_DIER_UDE ((u32)0x00000100) /*!<Update DMA request enable */
#define TIM_DIER_CC0DE ((u32)0x00000200) /*!<Capture/Compare 0 DMA request enable */
#define TIM_DIER_CC1DE ((u32)0x00000400) /*!<Capture/Compare 1 DMA request enable */
#define TIM_DIER_CC2DE ((u32)0x00000800) /*!<Capture/Compare 2 DMA request enable */
#define TIM_DIER_CC3DE ((u32)0x00001000) /*!<Capture/Compare 3 DMA request enable */
#define TIM_DIER_CC4DE ((u32)0x00002000) /*!<Capture/Compare 4 DMA request enable */
#define TIM_DIER_CC5DE ((u32)0x00004000) /*!<Capture/Compare 5 DMA request enable */
/** @} */
/**************************************************************************//**
* @defgroup TIM_SR
* @{
*****************************************************************************/
#define TIM_SR_UIF ((u32)0x00000001) /*!<Update interrupt Flag */
#define TIM_SR_CC0IF ((u32)0x00000002) /*!<Capture/Compare 0 interrupt Flag */
#define TIM_SR_CC1IF ((u32)0x00000004) /*!<Capture/Compare 1 interrupt Flag */
#define TIM_SR_CC2IF ((u32)0x00000008) /*!<Capture/Compare 2 interrupt Flag */
#define TIM_SR_CC3IF ((u32)0x00000010) /*!<Capture/Compare 3 interrupt Flag */
#define TIM_SR_CC4IF ((u32)0x00000020) /*!<Capture/Compare 4 interrupt Flag */
#define TIM_SR_CC5IF ((u32)0x00000040) /*!<Capture/Compare 5 interrupt Flag */
#define TIM_SR_UG_DONE ((u32)0x00010000) /*!<UG operation status for TIMx_EGR UG bit, polling bit */
/** @} */
/**************************************************************************//**
* @defgroup TIM_EGR
* @{
*****************************************************************************/
#define TIM_EGR_UG ((u32)0x00000001) /*!<Update Generation */
#define TIM_EGR_CC0G ((u32)0x00000002) /*!<Capture/Compare 0 Generation */
#define TIM_EGR_CC1G ((u32)0x00000004) /*!<Capture/Compare 1 Generation */
#define TIM_EGR_CC2G ((u32)0x00000008) /*!<Capture/Compare 2 Generation */
#define TIM_EGR_CC3G ((u32)0x00000010) /*!<Capture/Compare 3 Generation */
#define TIM_EGR_CC4G ((u32)0x00000020) /*!<Capture/Compare 4 Generation */
#define TIM_EGR_CC5G ((u32)0x00000040) /*!<Capture/Compare 5 Generation */
/** @} */
/**************************************************************************//**
* @defgroup TIM_CCMR
* @{
*****************************************************************************/
#define TIM_CCER_CCxE ((u32)0x01 << 24) /*!<Capture/Compare x input/output enable */
#define TIM_OCER_CCxPE ((u32)0x02 << 24) /*!<Output Compare x Preload enable */
#define TIM_CCER_CCxP ((u32)0x04 << 24) /*!<Capture/Compare x input/output Polarity */
#define TIM_CCER_CCxM ((u32)0x08 << 24) /*!<CCx working mode input or output mode */
#define TIM_ICER_CCxPULSE_MODE ((u32)0x10 << 24) /*!<CCx input pulse mode: width or num, just CC1 valid */
/** @} */
/** @} */
/**
* @}
*/
/**
* @}
*/
extern int TIMx_irq[6];
extern RTIM_TypeDef* TIMx[6];
extern u32 TIM_IT_CCx[6];
extern u32 TIM_DMA_CCx[6];
#define TIMER_TICK_US 31
#define TIMER_TICK_US_X4 (4*1000000/32000) //32k clock, 31.25us every timer_tick
#endif //_RTL8711B_TIMER_H_
/******************* (C) COPYRIGHT 2016 Realtek Semiconductor *****END OF FILE****/

View file

@ -0,0 +1,842 @@
/**
******************************************************************************
* @file rtl8711b_uart.h
* @author
* @version V1.0.0
* @date 2016-05-17
* @brief This file contains all the functions prototypes for the UART firmware
* library.
******************************************************************************
* @attention
*
* This module is a confidential and proprietary property of RealTek and
* possession or use of this module requires written permission of RealTek.
*
* Copyright(c) 2016, Realtek Semiconductor Corporation. All rights reserved.
******************************************************************************
*/
#ifndef _RTL8710B_UART_H_
#define _RTL8710B_UART_H_
/** @addtogroup AmebaZ_Periph_Driver
* @{
*/
/** @defgroup UART
* @{
*/
/** @addtogroup UART
* @verbatim
*****************************************************************************************
* Introduction
*****************************************************************************************
* UART0:
* - Base Address: UART0_DEV
* - IPclk: XTAL, normally is 40MHz
* - BaudRate: 110~6000000
* - Low Power Rx: Support
* - SocPs: SleepMode (clock gating & power gating)
* - Boot From UART without Flash
* - IRQ: UART0_IRQ
* - GDMA TX handshake interface: GDMA_HANDSHAKE_INTERFACE_UART0_TX
* - GDMA RX handshake interface: GDMA_HANDSHAKE_INTERFACE_UART0_RX
*
* UART1: The same as UART0 except following
* - Base Address: UART1_DEV
* - IRQ: UART1_IRQ
* - GDMA TX handshake interface: GDMA_HANDSHAKE_INTERFACE_UART1_TX
* - GDMA RX handshake interface: GDMA_HANDSHAKE_INTERFACE_UART1_RX
*
* UART2: Used as loguart
* - Base Address: UART2_DEV
* - IPclk: XTAL, normally is 40MHz
* - BaudRate: 110~6000000, default set 115200 for log
* - Low Power Rx: Not support
* - SocPs: power off when enter power save mode
* - Flash Program use LOGUART
* - IRQ: UART_LOG_IRQ
* - GDMA: not support
*
*****************************************************************************************
* PINMUX
*****************************************************************************************
* UART0:
* - S0: PA_1(rx)/PA_2(cts)/PA_3(rts)/PA_4(tx).
* - S1: PA_18(rx)/PA_19(cts)/PA_22(rts)/PA_23(tx).
*
* UART1:
* - S0: PA_25(rx)/PA_26(tx).
*
* UART2: LOGUART, default set to S1, dont change it if not necessary,
* - S0: PA_16(rx)/PA_17(tx).
* - S1: PA_29(rx)/PA_30(tx).
*
*****************************************************************************************
* Low Power Rx
*****************************************************************************************
* UART0 & UART1 support
* UART can receive data when soc enter power save mode
* baudrate: 110~500000
*
* NOTICE: not support Tx/Rx DMA mode under Low Power Rx.
*
*****************************************************************************************
* How to use Normal Uart
*****************************************************************************************
* To use the normal uart mode, the following steps are mandatory:
*
* 1. Enable peripheral clock and power:
* RCC_PeriphClockCmd(APBPeriph_UARTx, APBPeriph_UARTx_CLOCK, ENABLE);
*
* 2. configure the UART pinmux
* Pinmux_Config(Pin_Num, PINMUX_FUNCTION_UART)
*
* 3. Set default parameters, change some parameter if needed
* UART_StructInit(UART_InitTypeDef* UART_InitStruct)
*
* 4. init hardware use step3 parameters.
* UART_Init(UART_TypeDef* UARTx, UART_InitTypeDef *UART_InitStruct)
*
* 5. Set Baud Rate.
* UART_SetBaud(UART_TypeDef* UARTx, u32 BaudRate)
*
* 6. Enable IRQ using following function if needed
* UART_INTConfig(): UART IRQ Mask set
* InterruptRegister(): register the uart irq handler
* InterruptEn(): Enable the NVIC interrupt
*
* 7. Enable uart rx path:
* UART_RxCmd().
*
* @note in UART_Normal_functions group, these functions below are about Interrupts
* and flags management.
* UART_INTConfig()
* UART_IntStatus()
* UART_LineStatusGet()
*
*****************************************************************************************
* How to use uart in DMA mode
*****************************************************************************************
* To use the uart in DMA mode, the following steps are mandatory:
*
* 1. Enable peripheral clock and power:
* RCC_PeriphClockCmd(APBPeriph_UARTx, APBPeriph_UARTx_CLOCK, ENABLE);
*
* 2. configure the UART pinmux
* Pinmux_Config(Pin_Num, PINMUX_FUNCTION_UART)
*
* 3. Set default parameters, and change DMA mode open UART_InitStruct
* UART_StructInit(UART_InitTypeDef* UART_InitStruct)
*
* 4. init hardware use step3 parameters.
* UART_Init(UART_TypeDef* UARTx, UART_InitTypeDef *UART_InitStruct)
*
* 5. Set Baud Rate.
* UART_SetBaud(UART_TypeDef* UARTx, u32 BaudRate)
*
* 6. GDMA related configurations(source address/destination address/block size etc.).
* UART_TXGDMA_Init()
* UART_RXGDMA_Init()
*
* 7. Configure the uart DMA burst size:
* UART_TXDMAConfig()
* UART_RXDMAConfig().
*
* 8. Active the UART TX/RX DMA Request:
* UART_TXDMACmd()
* UART_RXDMACmd().
*
* 9. Enable uart rx path:
* UART_RxCmd().
*
* 10. Enable the DMA:
* DMA_Cmd().
*
*****************************************************************************************
* How to use uart in Low Power mode
*****************************************************************************************
* To use the uart in Low Power mode, the following steps are mandatory:
*
* 1. Enable peripheral clock and power:
* RCC_PeriphClockCmd(APBPeriph_UARTx, APBPeriph_UARTx_CLOCK, ENABLE);
*
* 2. configure the UART pinmux
* Pinmux_Config(Pin_Num, PINMUX_FUNCTION_UART)
*
* 3. Set default parameters, change some parameter if needed
* UART_StructInit(UART_InitTypeDef* UART_InitStruct)
*
* 4. init hardware use step3 parameters.
* UART_Init(UART_TypeDef* UARTx, UART_InitTypeDef *UART_InitStruct)
*
* 5. Set Baud Rate.
* UART_SetBaud(UART_TypeDef* UARTx, u32 BaudRate)
*
* 6. Enable IRQ using following function if needed
* UART_INTConfig(): UART IRQ Mask set
* InterruptRegister(): register the uart irq handler
* InterruptEn(): Enable the NVIC interrupt
*
* 6. Init Low power RX:
* UART_LPRxStructInit(LPUART_InitTypeDef* LPUART_InitStruct)
* UART_LPRxInit(UART_TypeDef* UARTx, LPUART_InitTypeDef *LPUART_InitStruct)
*
* 7. Set the low power RX Baud Rate
* UART_LPRxBaudSet(UART_TypeDef* UARTx, u32 BaudRate, u32 RxIPClockHz)
*
* 8. Enable monitor function if needed.
* UART_LPRxMonitorCmd()
*
* 9. select Low Power rx path:
* UART_LPRxpathSet()
*
* 10. select rx path clock source(XTAL/OSC):
* UART_LPRxIPClockSet().
*
* 11. Enable low power rx path:
* UART_LPRxCmd().
*
* @note when uart work in low power rx mode, clock source can switch between
* XTAL and OSC. As for how and when to excute switching action,
* refer to related uart specifications for more details.
*
* @note Besides, if more details about the uart low power rx path contens is needed,
* please refer to uart specifications.
*
*****************************************************************************************
* How to use uart in IrDA mode
*****************************************************************************************
* To use the uart in IrDA mode, the following steps are mandatory:
*
* 1. Enable peripheral clock and power:
* RCC_PeriphClockCmd(APBPeriph_UARTx, APBPeriph_UARTx_CLOCK, ENABLE);
*
* 2. configure the pinmux:
* Pinmux_Config(Pin_Num, PINMUX_FUNCTION_UART)
*
* 3. Disable rx path:
* UART_RxCmd().
*
* 4. Program the IrDA tx pulse width and location and IrDA rx pulse filter:
* UART_IrDAStructInit(IrDA_InitTypeDef * IrDA_InitStruct)
*
* 5. Init Hardware:
* UART_IrDAInit(UART_TypeDef* UARTx, IrDA_InitTypeDef * IrDA_InitStruct).
*
* 6. Enable the IrDA function:
* UART_IrDACmd().
*
* 7. According to the IrDA SIR protocol data format requrement, program Word Length,
* Stop Bit, Parity and DMA Mode(ENABLE/DISABLE):
* UART_StructInit(UART_InitTypeDef* UART_InitStruct)
* UART_Init(UART_TypeDef* UARTx, UART_InitTypeDef *UART_InitStruct)
*
* 8. Program the Baud Rate:
* UART_SetBaud().
*
* 9. Enable IRQ if needed:
* UART_INTConfig(): UART IRQ Mask set
* InterruptRegister(): register the uart irq handler
* InterruptEn(): Enable the NVIC interrupt
*
* 10. Enable uart rx path:
* UART_RxCmd().
*
* @note Amebaz IrDA just support IrDA SIR protocol, setting baud rate is no more than
* 115200 bps.
*
* @note because IrDA transfers data using infrared carrier and for the property of the
* IrDA transceiver, IrDA just work in half duplex mode. For details, refer to the IrDA
* protocol specification.
*****************************************************************************************
* @endverbatim
*/
/* Exported Types --------------------------------------------------------*/
/** @defgroup UART_Exported_Types UART Exported Types
* @{
*/
/**
* @brief UART Init structure definition
*/
typedef struct
{
u32 DmaModeCtrl; /*!< Specifies the uart DMA mode state.
This parameter can be ENABLE or DISABLE. */
u32 WordLen; /*!< Specifies the UART word length.
This parameter can be a value of @ref UART_Word_length_define. */
u32 StopBit; /*!< Specifies the UART stop bit number.
This parameter can be a value of @ref UART_Stop_Bit_define. */
u32 Parity; /*!< Specifies the UART parity.
This parameter can be a value of @ref UART_Parity_Enable_define. */
u32 ParityType; /*!< Specifies the UART parity type.
This parameter can be a value of @ref UART_Parity_Type_define. */
u32 StickParity; /*!< Specifies the UART stick parity.
This parameter can be a value of @ref UART_Stick_Parity_Type_define. */
u32 FlowControl; /*!< Specifies the UART auto flow control.
This parameter can be ENABLE or DISABLE. */
u32 RxFifoTrigLevel; /*!< Specifies the UART rx fifo trigger level.
This parameter can be a value of @ref UART_RX_FIFO_TRIGGER_LEVEL_define. */
u32 RxErReportCtrl; /*!< Specifies the UART rx error report control.
This parameter can be a value of @ref UART_Rx_Err_Report_define. */
} UART_InitTypeDef;
/**
* @brief UART Low Power Init structure definition
*
*/
typedef struct
{
u32 LPUART_OscPerbitUpdCtrl; /*!< Specifies the OSC perbit update control when use xtal 8M.
This parameter can be ENABLE or DISABLE.
ENABLE: osc perbit updates with xtal perbit when use xtal 8M.
DISABLE: osc perbit does't update with xtal perbit when use xtal 8M.
@note This parameter is only used in low power rx path with xtal 8M.
@note osc perbit will update when use osc 8M, even if LPUART_OscPerbitUpdCtrl is disable */
u32 LPUART_BitNumThres; /*!< Specifies the bit number threshold of one monitor period.
This parameter is used to get the average clock cycles of one bit
and can be a number between 0x00 and 0x7f.
@note This parameter is only used in low power rx path. */
} LPUART_InitTypeDef;
/**
* @brief UART IRDA Init structure definition
*
*/
typedef struct
{
u32 UART_IrDARxInv; /*!< Specifies the uart irda rx invert control.
This parameter can be ENABLE or DISABLE.
ENABLE: invert the irda input signal.
DISABLE: does't invert the irda input signal.
@note This parameter is only used in IrDA mode. */
u32 UART_IrDATxInv; /*!< Specifies the uart irda tx invert control.
This parameter can be ENABLE or DISABLE.
ENABLE: invert the irda output signal.
DISABLE: does't invert the irda output signal.
@note This parameter is only used in IrDA mode. */
u32 UART_UpperShift; /*!< Specifies the uart irda tx pulse right edge shift direction.
This parameter can be a value of @ref UART_IRDA_PULSE_SHIFT_define. */
u32 UART_UpperShiftVal; /*!< Specifies the uart irda tx pulse right edge shift value in the given direction.
This parameter can be a number between 0x0000 and 0x7fff. */
u32 UART_LowShift; /*!< Specifies the uart irda tx pulse left edge shift direction.
This parameter can be a value of @ref UART_IRDA_PULSE_SHIFT_define. */
u32 UART_LowShiftVal; /*!< Specifies the uart irda tx pulse left edge shift value in the given direction.
This parameter can be a number between 0x0000 and 0x7fff. */
u32 UART_RxFilterThres; /*!< Specifies the uart irda rx filter threshold.
This parameter can be a number between 0x0000 and 0x7fff
@note This parameter is only used in IrDA mode. */
u32 UART_RxFilterCmd; /*!< Specifies the uart irda rx filter control.
This parameter can be ENABLE or DISABLE.
ENABLE: uart IrDA rx filter is used.
DISABLE: uart IrDA rx filter is not used.
@note This parameter is only used in IrDA mode. */
}IrDA_InitTypeDef;
/**
* @}
*/
/* Exported constants --------------------------------------------------------*/
/** @defgroup UART_Exported_Constants UART Exported Constants
* @{
*/
/** @defgroup UART_IRDA_PULSE_SHIFT_define
* @{
*/
#define UART_IRDA_PULSE_LEFT_SHIFT ((u32)0x00000000)
#define UART_IRDA_PULSE_RIGHT_SHIFT ((u32)0x00000001)
#define IS_IRDA_PUL_SHIFT(SHIFT) (((SHIFT) == UART_IRDA_PULSE_LEFT_SHIFT) || \
((SHIFT) == UART_IRDA_PULSE_RIGHT_SHIFT))
/**
* @}
*/
/** @defgroup UART_RX_FIFO_TRIGGER_LEVEL_define
* @{
*/
#define UART_RX_FIFOTRIG_LEVEL_1BYTES ((u32)0x00000000)
#define UART_RX_FIFOTRIG_LEVEL_4BYTES ((u32)0x00000040)
#define UART_RX_FIFOTRIG_LEVEL_8BYTES ((u32)0x00000080)
#define UART_RX_FIFOTRIG_LEVEL_14BYTES ((u32)0x000000c0)
#define IS_UART_RXFIFO_LEVEL(LEVEL) (((LEVEL) == UART_RX_FIFOTRIG_LEVEL_1BYTES) || \
((LEVEL) == UART_RX_FIFOTRIG_LEVEL_4BYTES) || \
((LEVEL) == UART_RX_FIFOTRIG_LEVEL_8BYTES) || \
((LEVEL) == UART_RX_FIFOTRIG_LEVEL_14BYTES))
/**
* @}
*/
/** @defgroup UART_Word_length_define
* @{
*/
#define RUART_WLS_7BITS ((u32)0x00000000)
#define RUART_WLS_8BITS ((u32)0x00000001)
#define IS_UART_WLS(VAL) (((VAL) == RUART_WLS_7BITS) || \
((VAL) == RUART_WLS_8BITS))
/**
* @}
*/
/** @defgroup UART_Stop_Bit_define
* @{
*/
#define RUART_STOP_BIT_1 ((u32)0x00000000)
#define RUART_STOP_BIT_2 ((u32)0x00000001)
#define IS_UART_STOP_BIT(VAL) (((VAL) == RUART_STOP_BIT_1) || \
((VAL) == RUART_STOP_BIT_2))
/**
* @}
*/
/** @defgroup UART_Parity_Enable_define
* @{
*/
#define RUART_PARITY_DISABLE ((u32)0x00000000)
#define RUART_PARITY_ENABLE ((u32)0x00000001)
#define IS_UART_PARITY_ENABLE(VAL) (((VAL) == RUART_PARITY_DISABLE) || \
((VAL) == RUART_PARITY_ENABLE))
/**
* @}
*/
/** @defgroup UART_Parity_Type_define
* @{
*/
#define RUART_ODD_PARITY ((u32)0x00000000)
#define RUART_EVEN_PARITY ((u32)0x00000001)
#define IS_UART_PARITY_TYPE(VAL) (((VAL) == RUART_ODD_PARITY) || \
((VAL) == RUART_EVEN_PARITY))
/**
* @}
*/
/** @defgroup UART_Stick_Parity_Type_define
* @{
*/
#define RUART_STICK_PARITY_DISABLE ((u32)0x00000000)
#define RUART_STICK_PARITY_ENABLE ((u32)0x00000001)
#define IS_UART_STICK_PARITY_ENABLE(VAL) (((VAL) == RUART_STICK_PARITY_DISABLE) || \
((VAL) == RUART_STICK_PARITY_ENABLE))
/**
* @}
*/
/** @defgroup UART_Interrupt_ID_define
* @{
*/
#define RUART_MODEM_STATUS ((u32)0x00000000)
#define RUART_TX_FIFO_EMPTY ((u32)0x00000001)
#define RUART_RECEIVER_DATA_AVAILABLE ((u32)0x00000002)
#define RUART_RECEIVE_LINE_STATUS ((u32)0x00000003)
#define RUART_LP_RX_MONITOR_DONE ((u32)0x00000004)
#define RUART_TIME_OUT_INDICATION ((u32)0x00000006)
/**
* @}
*/
/** @defgroup UART_RX_Clock_Source_define
* note: register REG_PESOC_CLK_SEL 0x0250
* UART0: bit19 & bit20
* UART1: bit26 & bit27
* @{
*/
#define UART_RX_CLK_XTAL_40M ((u32)0x00000000)
#define UART_RX_CLK_OSC_8M ((u32)0x00000001)
#define UART_RX_CLK_XTAL_8M ((u32)0x00000002)
#define IS_UART_RX_CLK(CLK) (((CLK) == UART_RX_CLK_XTAL_40M) || \
((CLK) == UART_RX_CLK_XTAL_8M) || \
((CLK) == UART_RX_CLK_OSC_8M))
/**
* @}
*/
/** @defgroup UART_Rx_Err_Report_define
* @{
*/
#define UART_RX_EEROR_REPORT_DISABLE ((u32)0x00000000)
#define UART_RX_EEROR_REPORT_ENABLE ((u32)0x00000001)
#define IS_UART_RX_ERROR_REPORT(REPORT) (((REPORT) == UART_RX_EEROR_REPORT_DISABLE) || \
((REPORT) == UART_RX_EEROR_REPORT_ENABLE) )
/**
* @}
*/
/** @defgroup UART_Low_Power_Peripheral_define
* @{
*/
#define IS_LPUART_PERIPH(PERIPH) (((PERIPH) == UART0_DEV) || ((PERIPH) == UART1_DEV))
/**
* @}
*/
/** @defgroup UART_SoftWare_Status_define
* @{
*/
#define STATETX_DMA 1
#define STATETX_INT 2
#define STATETX_POLL 3
#define STATERX_DMA 1
#define STATERX_INT 2
#define STATERX_POLL 3
/**
* @}
*/
/**
* @}
*/
/* Exported functions --------------------------------------------------------*/
/** @defgroup UART_Exported_Functions UART Exported Functions
* @{
*/
/** @defgroup UART_Normal_functions
* @{
*/
_LONG_CALL_ void UART_DeInit(UART_TypeDef* UARTx);
_LONG_CALL_ void UART_StructInit(UART_InitTypeDef* UART_InitStruct);
_LONG_CALL_ void UART_Init(UART_TypeDef* UARTx, UART_InitTypeDef *UART_InitStruct);
_LONG_CALL_ u32 UART_BaudParaGet(u32 baudrate, u32 *ovsr, u32 *ovsr_adj);
_LONG_CALL_ void UART_BaudParaGetFull(u32 IPclk, u32 baudrate, u32 *ovsr, u32 *ovsr_adj);
_LONG_CALL_ void UART_SetBaudExt(UART_TypeDef* UARTx, u32 Ovsr, u32 Ovsr_adj);
_LONG_CALL_ void UART_SetBaud(UART_TypeDef* UARTx, u32 BaudRate);
_LONG_CALL_ void UART_SetRxLevel(UART_TypeDef* UARTx, u32 FifoLv);
_LONG_CALL_ void UART_RxCmd(UART_TypeDef* UARTx, u32 NewState);
_LONG_CALL_ u32 UART_Writable(UART_TypeDef* UARTx);
_LONG_CALL_ u32 UART_Readable(UART_TypeDef* UARTx);
_LONG_CALL_ void UART_CharPut(UART_TypeDef* UARTx, u8 TxData);
_LONG_CALL_ void UART_CharGet(UART_TypeDef* UARTx, u8 *pRxByte);
_LONG_CALL_ void UART_ReceiveData(UART_TypeDef* UARTx, u8* OutBuf, u32 Count);
_LONG_CALL_ void UART_SendData(UART_TypeDef* UARTx, u8* InBuf, u32 Count);
_LONG_CALL_ u32 UART_ReceiveDataTO(UART_TypeDef* UARTx, u8* OutBuf, u32 Count, u32 Times);
_LONG_CALL_ u32 UART_SendDataTO(UART_TypeDef* UARTx,u8* InBuf,u32 Count, u32 Times);
_LONG_CALL_ void UART_RxByteCntClear(UART_TypeDef* UARTx);
_LONG_CALL_ u32 UART_RxByteCntGet(UART_TypeDef* UARTx);
_LONG_CALL_ void UART_BreakCtl(UART_TypeDef* UARTx, u32 NewState);
_LONG_CALL_ u32 UART_ClearRxFifo(UART_TypeDef* UARTx);
_LONG_CALL_ void UART_ClearTxFifo(UART_TypeDef* UARTx);
_LONG_CALL_ void UART_INTConfig(UART_TypeDef* UARTx, u32 UART_IT, u32 newState);
_LONG_CALL_ u32 UART_IntStatus(UART_TypeDef* UARTx);
_LONG_CALL_ u32 UART_ModemStatusGet(UART_TypeDef* UARTx);
_LONG_CALL_ u32 UART_LineStatusGet(UART_TypeDef* UARTx);
_LONG_CALL_ void UART_WaitBusy(UART_TypeDef* UARTx, u32 PollTimes);
_LONG_CALL_ void UART_PinMuxInit(u8 UartIndex, u8 PinmuxSelect);
_LONG_CALL_ void UART_PinMuxDeinit(u8 UartIndex, u8 PinmuxSelect);
/**
* @}
*/
/** @defgroup UART_DMA_functions
* @{
*/
_LONG_CALL_ void UART_TXDMAConfig(UART_TypeDef* UARTx, u32 TxDmaBurstSize);
_LONG_CALL_ void UART_RXDMAConfig(UART_TypeDef* UARTx, u32 RxDmaBurstSize);
_LONG_CALL_ void UART_TXDMACmd(UART_TypeDef* UARTx, u32 NewState);
_LONG_CALL_ void UART_RXDMACmd(UART_TypeDef* UARTx, u32 NewState);
_LONG_CALL_ BOOL UART_TXGDMA_Init(u8 UartIndex, GDMA_InitTypeDef *GDMA_InitStruct, void *CallbackData, IRQ_FUN CallbackFunc, u8 *pTxBuf, int TxCount);
_LONG_CALL_ BOOL UART_RXGDMA_Init(u8 UartIndex, GDMA_InitTypeDef *GDMA_InitStruct, void *CallbackData, IRQ_FUN CallbackFunc, u8 *pRxBuf, int RxCount);
/**
* @}
*/
/** @defgroup UART_Low_Power_functions
* @{
*/
_LONG_CALL_ void UART_LPRxStructInit(LPUART_InitTypeDef* UART_InitStruct);
_LONG_CALL_ void UART_LPRxInit(UART_TypeDef* UARTx, LPUART_InitTypeDef *UART_InitStruct);
_LONG_CALL_ void UART_LPRxBaudSet(UART_TypeDef* UARTx, u32 BaudRate, u32 RxIPClockHz);
_LONG_CALL_ void UART_LPRxMonitorCmd(UART_TypeDef* UARTx, u32 NewState);
_LONG_CALL_ void UART_LPRxpathSet(UART_TypeDef* UARTx, u32 LPRxpath);
_LONG_CALL_ void UART_LPRxIPClockSet(UART_TypeDef* UARTx, u32 RxIPClock);
_LONG_CALL_ void UART_LPRxCmd(UART_TypeDef* UARTx, u32 NewState);
_LONG_CALL_ u32 UART_LPRxMonBaudCtrlRegGet(UART_TypeDef* UARTx);
_LONG_CALL_ u32 UART_LPRxMonitorSatusGet(UART_TypeDef* UARTx);
/**
* @}
*/
/** @defgroup UART_IRDA_functions
* @{
*/
_LONG_CALL_ void UART_IrDAStructInit(IrDA_InitTypeDef * IrDA_InitStruct);
_LONG_CALL_ void UART_IrDAInit(UART_TypeDef* UARTx, IrDA_InitTypeDef * IrDA_InitStruct);
_LONG_CALL_ void UART_IrDACmd(UART_TypeDef* UARTx, u32 NewState);
/**
* @}
*/
/**
* @}
*/
/* Registers Definitions --------------------------------------------------------*/
/**************************************************************************//**
* @defgroup UART_Register_Definitions UART Register Definitions
* @{
*****************************************************************************/
/**************************************************************************//**
* @defgroup DLH_INTCR
* @{
*****************************************************************************/
#define RUART_IER_ERBI ((u32)0x00000001) /*BIT[0], Enable received data available interrupt (rx trigger)*/
#define RUART_IER_ETBEI ((u32)0x00000001<<1) /*BIT[1], Enable transmitter FIFO empty interrupt (tx fifo empty)*/
#define RUART_IER_ELSI ((u32)0x00000001<<2) /*BIT[2], Enable receiver line status interrupt (receiver line status)*/
#define RUART_IER_EDSSI ((u32)0x00000001<<3) /*BIT[3], Enable modem status interrupt (modem status transition)*/
#define RUART_IER_EDMI ((u32)0x00000001<<4) /*BIT[4], Enable low power rx monitor done interrupt (monitor done)*/
#define RUART_IER_ETOI ((u32)0x00000001<<5) /*BIT[5], Enable rx time out interrupt*/
/** @} */
/**************************************************************************//**
* @defgroup INTID
* @{
*****************************************************************************/
#define RUART_IIR_INT_PEND ((u32)0x00000001) /*uart interrupt global status*/
#define RUART_IIR_INT_ID ((u32)0x00000007<<1) /*Uart Interrupt ID mask, register INTID[3:1]*/
/** @} */
/**************************************************************************//**
* @defgroup FCR
* @{
*****************************************************************************/
#define RUART_FIFO_CTL_RX_ERR_RPT ((u32)0x00000001) /*BIT[0], 0x01, RX error report control bit*/
#define RUART_FIFO_CTL_REG_CLEAR_RXFIFO ((u32)0x00000001<<1) /*BIT[1], 0x02, Write 1 clear*/
#define RUART_FIFO_CTL_REG_CLEAR_TXFIFO ((u32)0x00000001<<2) /*BIT[2], 0x04, Write 1 clear*/
#define RUART_FIFO_CTL_REG_DMA_ENABLE ((u32)0x00000001<<3) /*BIT[3], 0x08, Uart DMA control bit*/
#define RUART_FIFO_CTL_REG_RX_TRG_LEV ((u32)0x00000003<<6) /*BIT[7:6], 0xc0, Uart rx trigger level field*/
/** @} */
/**************************************************************************//**
* @defgroup MCR
* @{
*****************************************************************************/
#define RUART_MCL_FLOW_ENABLE ((u32)((0x00000001 << 5) | (0x00000001 << 1))) /*BIT[1],BIT[5],Uart auto flow control enable bit*/
/** @} */
/**************************************************************************//**
* @defgroup LCR
* @{
*****************************************************************************/
#define BIT_UART_LCR_BREAK_CTRL ((u32)0x00000001<<6) /*BIT[6], Uart break control function enable bit*/
#define RUART_LINE_CTL_REG_DLAB_ENABLE ((u32)0x00000001<<7) /*BIT[7], 0x80*/
/** @} */
/**************************************************************************//**
* @defgroup LSR
* @{
*****************************************************************************/
#define RUART_LINE_STATUS_REG_DR ((u32)0x00000001) /*BIT[0], Data ready indicator*/
#define RUART_LINE_STATUS_ERR_OVERRUN ((u32)0x00000001<<1) /*BIT[1], Over run*/
#define RUART_LINE_STATUS_ERR_PARITY ((u32)0x00000001<<2) /*BIT[2], Parity error*/
#define RUART_LINE_STATUS_ERR_FRAMING ((u32)0x00000001<<3) /*BIT[3], Framing error*/
#define RUART_LINE_STATUS_ERR_BREAK ((u32)0x00000001<<4) /*BIT[4], Break interrupt error*/
#define RUART_LINE_STATUS_REG_THRE ((u32)0x00000001<<5) /*BIT[5], 0x20, Transmit holding register empty interrupt enable*/
#define RUART_LINE_STATUS_REG_TEMT ((u32)0x00000001<<6) /*BIT[6], 0x40, Transmitter empty indicator(bit)*/
#define RUART_LINE_STATUS_ERR_RXFIFO ((u32)0x00000001<<7) /*BIT[7], RX FIFO error*/
#define RUART_LINE_STATUS_ERR (RUART_LINE_STATUS_ERR_OVERRUN |RUART_LINE_STATUS_ERR_PARITY| \
RUART_LINE_STATUS_ERR_FRAMING|RUART_LINE_STATUS_ERR_BREAK| \
RUART_LINE_STATUS_ERR_RXFIFO) /*Line status error*/
/** @} */
/**************************************************************************//**
* @defgroup SPR
* @{
*****************************************************************************/
#define RUART_SP_REG_RXBREAK_INT_STATUS ((u32)0x00000001<<7) /*BIT[7], 0x80, Write 1 clear*/
#define RUART_SP_REG_DBG_SEL ((u32)0x0000000F<<8) /*BIT[11:8], Debug port selection*/
#define RUART_SP_REG_XFACTOR_ADJ ((u32)0x000007FF<<16) /*BIT[26:16], ovsr_adj parameter field*/
/** @} */
/**************************************************************************//**
* @defgroup STSR
* @{
*****************************************************************************/
#define RUART_STS_REG_RESET_RCV ((u32)0x00000001<<3) /*BIT[3], 0x08, Reset uart receiver*/
#define RUART_STS_REG_XFACTOR ((u32)0x000FFFFF<<4) /*BIT[23:4]ovsr parameter field*/
/** @} */
/**************************************************************************//**
* @defgroup MISCR
* @{
*****************************************************************************/
#define RUART_IRDA_ENABLE ((u32)0x00000001) /*BIT[0], Enable IrDA*/
#define RUART_IRDA_TX_INVERT ((u32)0x00000001 << 13) /*BIT[13], Enable IrDA tx invert*/
#define RUART_IRDA_RX_INVERT ((u32)0x00000001 << 14) /*BIT[14], Enable IrDA rx invert*/
#define RUART_TXDMA_BURSTSIZE_MASK ((u32)0x0000001F << 3) /*BIT[7:3], Uart tx DMA burst size mask.
This field value must be no more than 16.
Because tx fifo depth is 16 in UART IP hardware*/
#define RUART_RXDMA_BURSTSIZE_MASK ((u32)0x0000001F << 8) /*BIT[12:8], Uart rx DMA burst size mask.
This field value must be no more than 16.
Because rx fifo depth is 16 in uart IP hardware*/
#define RUART_TXDMA_ENABLE ((u32)0x00000001 << 1) /*BIT[1], Uart tx DMA enable bit*/
#define RUART_RXDMA_ENABLE ((u32)0x00000001 << 2) /*BIT[2], Uart rx DMA enable bit*/
/** @} */
/**************************************************************************//**
* @defgroup TXPLSR
* @{
*****************************************************************************/
#define RUART_IRDA_TX_PUL_LOW_BUND_VAL ((u32)0x00007FFF) /*BIT[14:0], IrDA tx pulse low bound edge shift value*/
#define RUART_IRDA_TX_PUL_LOW_BUND_SHIFT ((u32)0x00000001 << 15) /*BIT[15], IrDA tx pulse low bound edge shift direction*/
#define RUART_IRDA_TX_PUL_UP_BUND_VAL ((u32)0x00007FFF << 16) /*BIT[30:16], IrDA tx pulse upper bound edge shift value*/
#define RUART_IRDA_TX_PUL_UP_BUND_SHIFT ((u32)0x00000001 << 31) /*BIT[31], IrDA tx pulse upper bound edge shift direction*/
/** @} */
/**************************************************************************//**
* @defgroup RXPLSR
* @{
*****************************************************************************/
#define RUART_IRDA_RX_FILTER_ENABLE ((u32)0x00000001) /*BIT[0], IrDA rx filter enable*/
#define RUART_IRDA_RX_FILTER_THRES ((u32)0x00007FFF << 1) /*BIT[15:1], IrDA rx filter threshold field*/
/** @} */
/**************************************************************************//**
* @defgroup REG_RX_PATH_CTRL
* @{
*****************************************************************************/
#define RUART_REG_LP_RX_PATH_SELECT ((u32)0x00000001) /*BIT[0], 0x01, Select uart low power rx path*/
#define RUART_REG_LP_RX_PATH_RESET ((u32)0x00000001 << 2) /*BIT[2], 0x40, Reset uart low power rx path receiver*/
/** @} */
/**************************************************************************//**
* @defgroup REG_MON_BAUD_CTRL
* @{
*****************************************************************************/
#define RUART_LP_RX_MON_ENABLE ((u32)0x00000001) /*BIT[0], 0x01, Enable low power rx monitor function*/
#define RUART_LP_RX_BIT_NUM_THRES ((u32)0x000000FF << 1) /*BIT[8:1], Bit Number threshold of one monitor period*/
#define RUART_LP_RX_OSC_CYCNUM_PERBIT ((u32)0x000FFFFF << 9) /*BIT[28:9], Cycle number perbit for osc clock */
#define RUART_LP_RX_OSC_UPD_IN_XTAL ((u32)0x00000001 << 29) /*BIT[29], Control bit for osc monitor parameter update */
/** @} */
/**************************************************************************//**
* @defgroup REG_MON_BAUD_STS
* @{
*****************************************************************************/
#define RUART_LP_RX_XTAL_CYCNUM_PERBIT ((u32)0x000FFFFF) /*BIT[19:0], Cycle number perbit for xtal clock */
#define RUART_LP_RX_MON_RDY ((u32)0x00000001 << 20) /*BIT[20], Monitor ready status*/
#define RUART_LP_RX_MON_TOTAL_BITS ((u32)0x0000000F << 21) /*BIT[28:21], Actualy monitor bit number */
/** @} */
/**************************************************************************//**
* @defgroup REG_RX_BYTE_CNT
* @{
*****************************************************************************/
/******************** Bits definition for register *******************/
#define RUART_RX_READ_BYTE_CNTER ((u32)0x0000FFFF) /*BIT[15:0], Byte number of data read from rx fifo */
#define RUART_RX_BYTE_CNTER_CLEAR ((u32)0x00000001 << 16) /*BIT[16], Write 1 clear rx byte counter*/
/** @} */
/** @} */
/**
* @}
*/
/**
* @}
*/
/* Other Definitions --------------------------------------------------------*/
typedef struct
{
u32 LOW_POWER_RX_ENABLE; /*Enable low power RX*/
} UARTCFG_TypeDef;
typedef struct
{
UART_TypeDef* UARTx;
u32 Tx_HandshakeInterface;
u32 Rx_HandshakeInterface;
IRQn_Type IrqNum;
} UART_DevTable;
extern UARTCFG_TypeDef uart_config[];
extern const UART_DevTable UART_DEV_TABLE[3];
extern u32 UART_StateTx[3];
extern u32 UART_StateRx[3];
extern const u32 BAUDRATE_TABLE_40M[][3];
#define MAX_UART_INDEX (2)
static inline void
UART_SetTxFlag(u32 UartIdx, u32 Flag)
{
UART_StateTx[UartIdx] = Flag;
}
static inline void
UART_SetRxFlag(u32 UartIdx, u32 Flag)
{
UART_StateRx[UartIdx] = Flag;
}
static inline u32
UART_GetTxFlag(u32 UartIdx)
{
return (UART_StateTx[UartIdx]);
}
static inline u32
UART_GetRxFlag(u32 UartIdx)
{
return (UART_StateRx[UartIdx]);
}
#endif
/******************* (C) COPYRIGHT 2016 Realtek Semiconductor *****END OF FILE****/

View file

@ -0,0 +1,176 @@
/**
******************************************************************************
* @file rtl8711b_vector.h
* @author
* @version V1.0.0
* @date 2016-05-17
* @brief This file contains all the functions prototypes for the IRQ firmware
* library.
******************************************************************************
* @attention
*
* This module is a confidential and proprietary property of RealTek and
* possession or use of this module requires written permission of RealTek.
*
* Copyright(c) 2016, Realtek Semiconductor Corporation. All rights reserved.
******************************************************************************
*/
#ifndef _RTL8710B_VECTOR_TABLE_H_
#define _RTL8710B_VECTOR_TABLE_H_
/** @addtogroup AmebaZ_Platform
* @{
*/
/** @defgroup IRQ
* @brief IRQ modules
* @{
*/
/** @addtogroup IRQ
* @verbatim
*****************************************************************************************
* Introduction
*****************************************************************************************
* IRQ table, please refer to IRQ Exported Constants->IRQn_enum->IRQn
*
*****************************************************************************************
* how to use
*****************************************************************************************
* 1. register/unregister IRQ use: InterruptRegister/InterruptUnRegister
* 2. enable/disable IRQ use: InterruptEn/InterruptDis
*
*****************************************************************************************
* @endverbatim
*/
/* Exported types ------------------------------------------------------------*/
/** @defgroup IRQ_Exported_Types IRQ Exported Types
* @{
*/
typedef s32 IRQn_Type;
typedef void (*HAL_VECTOR_FUN) (void);
typedef u32 (*IRQ_FUN)(void *Data);
/**
* @}
*/
/* Exported constants --------------------------------------------------------*/
/** @defgroup IRQ_Exported_Constants IRQ Exported Constants
* @{
*/
/** @defgroup IRQn_enum
* @{
*/
enum IRQn {
/****** Cortex-M4 Processor Exceptions Numbers ********/
NonMaskableInt_IRQn = -14, /*!< 2 Non Maskable Interrupt */
HardFault_IRQn = -13, /*!< 3 Hard Fault, all classes of Fault */
MemoryManagement_IRQn = -12, /*!< 4 Cortex-M3 Memory Management Interrupt */
BusFault_IRQn = -11, /*!< 5 Cortex-M3 Bus Fault Interrupt */
UsageFault_IRQn = -10, /*!< 6 Cortex-M3 Usage Fault Interrupt */
SVCall_IRQn = -5, /*!< 11 Cortex-M3 SV Call Interrupt */
DebugMonitor_IRQn = -4, /*!< 12 Cortex-M3 Debug Monitor Interrupt */
PendSV_IRQn = -2, /*!< 14 Cortex-M3 Pend SV Interrupt */
SysTick_IRQn = -1, /*!< 15 Cortex-M3 System Tick Interrupt */
/****** RTL8710B Specific Interrupt Numbers ************/
SYSTEM_ON_IRQ = 0, /*!< 16 SYS Interrupt for wakeup from power save */
WDG_IRQ = 1, /*!< 17 Watch dog global insterrupt */
TIMER0_IRQ = 2, /*!< 18 Timer0 global interrupt */
TIMER1_IRQ = 3, /*!< 19 Timer1 global interrupt */
TIMER2_IRQ = 4, /*!< 20 Timer2 global interrupt */
TIMER3_IRQ = 5, /*!< 21 Timer3 global interrupt */
SPI0_IRQ = 6, /*!< 22 SPI0 global interrupt for communication spi */
GPIO_IRQ = 7, /*!< 23 GPIO portA global interrupt */
UART0_IRQ = 8, /*!< 24 UART0 global interrupt */
SPI_FLASH_IRQ = 9, /*!< 25 SPI Flash global interrupt */
UART1_IRQ = 10, /*!< 26 UART1 global interrupt */
TIMER4_IRQ = 11, /*!< 27 Timer4 global interrupt */
SDIO_DEVICE_IRQ = 12, /*!< 28 SDIO device global interrupt */
I2S0_PCM0_IRQ = 13, /*!< 29 I2S0 global interrupt */
TIMER5_IRQ = 14, /*!< 30 Timer5 global interrupt */
WL_DMA_IRQ = 15, /*!< 31 Wlan Host global interrupt */
WL_PROTOCOL_IRQ = 16, /*!< 32 Wlan Firmware Wlan global interrupt */
CRYPTO_IRQ = 17, /*!< 33 IPsec global interrupt */
SPI1_IRQ = 18, /*!< 34 SPI1 global interrupt for communication spi */
PERIPHERAL_IRQ = 19, /*!< 35 not used */
GDMA0_CHANNEL0_IRQ = 20, /*!< 36 GDMA0 channel 0 global interrupt */
GDMA0_CHANNEL1_IRQ = 21, /*!< 37 GDMA0 channel 1 global interrupt */
GDMA0_CHANNEL2_IRQ = 22, /*!< 38 GDMA0 channel 2 global interrupt */
GDMA0_CHANNEL3_IRQ = 23, /*!< 39 GDMA0 channel 3 global interrupt */
GDMA0_CHANNEL4_IRQ = 24, /*!< 40 GDMA0 channel 4 global interrupt */
GDMA0_CHANNEL5_IRQ = 25, /*!< 41 GDMA0 channel 5 global interrupt */
I2C0_IRQ = 26, /*!< 42 I2C0 global interrupt */
I2C1_IRQ = 27, /*!< 43 I2C1 global interrupt */
UART_LOG_IRQ = 28, /*!< 44 log uart intr */
ADC_IRQ = 29, /*!< 45 adc intr */
RDP_IRQ = 30, /*!< 46 cpu rdp protection interrupt */
RTC_IRQ = 31, /*!< 47 rtc timer interrupt */
GDMA1_CHANNEL0_IRQ = 32, /*!< 48 GDMA1 channel 0 global interrupt */
GDMA1_CHANNEL1_IRQ = 33, /*!< 49 GDMA1 channel 1 global interrupt */
GDMA1_CHANNEL2_IRQ = 34, /*!< 50 GDMA1 channel 2 global interrupt */
GDMA1_CHANNEL3_IRQ = 35, /*!< 51 GDMA1 channel 3 global interrupt */
GDMA1_CHANNEL4_IRQ = 36, /*!< 52 GDMA1 channel 4 global interrupt */
GDMA1_CHANNEL5_IRQ = 37, /*!< 53 GDMA1 channel 5 global interrupt */
USB_IRQ = 38, /*!< 54 USOC interrupt */
RXI300_IRQ = 39, /*!< 55 RXI300 interrupt */
USB_SIE_IRQ = 40, /*!< 56 USB SIE interrupt */
};
/**
* @}
*/
/**
* @}
*/
/* Exported functions --------------------------------------------------------*/
/** @defgroup IRQ_Exported_Functions IRQ Exported Functions
* @{
*/
extern _LONG_CALL_ void VECTOR_TableInit(u32 StackP);
extern _LONG_CALL_ void VECTOR_TableInitForOS(void *PortSVC, void *PortPendSVH, void *PortSysTick);
extern _LONG_CALL_ BOOL VECTOR_IrqRegister(IRQ_FUN IrqFun, IRQn_Type IrqNum, u32 Data, u32 Priority);
extern _LONG_CALL_ BOOL VECTOR_IrqUnRegister(IRQn_Type IrqNum);
extern _LONG_CALL_ void VECTOR_IrqEn(IRQn_Type IrqNum, u32 Priority);
extern _LONG_CALL_ void VECTOR_IrqDis(IRQn_Type IrqNum);
#define InterruptForOSInit VECTOR_TableInitForOS
#define InterruptRegister VECTOR_IrqRegister
#define InterruptUnRegister VECTOR_IrqUnRegister
#define InterruptEn VECTOR_IrqEn
#define InterruptDis VECTOR_IrqDis
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/* Other Definitions --------------------------------------------------------*/
extern IRQ_FUN UserIrqFunTable[64];
extern u32 UserIrqDataTable[64];
extern HAL_VECTOR_FUN NewVectorTable[];
#define PERIPHERAL_IRQ_STATUS 0x04
#define PERIPHERAL_IRQ_MODE 0x08
#define PERIPHERAL_IRQ_EN 0x0C
#define LP_PERI_EXT_IRQ_STATUS 0x24
#define LP_PERI_EXT_IRQ_MODE 0x28
#define LP_PERI_EXT_IRQ_EN 0x2C
#define PERIPHERAL_IRQ_ALL_LEVEL 0
#endif //_RTL8710B_VECTOR_TABLE_H_
/******************* (C) COPYRIGHT 2016 Realtek Semiconductor *****END OF FILE****/

View file

@ -0,0 +1,148 @@
/**
******************************************************************************
* @file rtl8711b_rtc.h
* @author
* @version V1.0.0
* @date 2016-05-17
* @brief This file contains all the functions prototypes for the WDG firmware
* library.
******************************************************************************
* @attention
*
* This module is a confidential and proprietary property of RealTek and
* possession or use of this module requires written permission of RealTek.
*
* Copyright(c) 2016, Realtek Semiconductor Corporation. All rights reserved.
******************************************************************************
*/
#ifndef _RTL8711B_WDG_H_
#define _RTL8711B_WDG_H_
/** @addtogroup AmebaZ_Periph_Driver
* @{
*/
/** @defgroup WDG
* @brief WDG driver modules
* @{
*/
/** @addtogroup WDG
* @verbatim
*****************************************************************************************
* Introduction
*****************************************************************************************
* WDG:
* - Base Address: VENDOR_REG_BASE
* - Timer clk: NCO 32k
* - Generates MCU reset or NMI interrupt on expiry of a programmed time period,
* unless the program refreshes the watchdog
* - IRQ: WDG_IRQ & NMI
*
*****************************************************************************************
* WDG Register
*****************************************************************************************
* [31] R/W1C Wdt_to Watch dog timer timeout. 1 cycle pulse
* [30] R/W Wdt_mode 1: Reset system, 0: Interrupt CPU
* [29] R/W RSVD
* [28:25] R/W Cnt_limit 0: 0x001
* 1: 0x003
* 2: 0x007
* 3: 0x00F
* 4: 0x01F
* 5: 0x03F
* 6: 0x07F
* 7: 0x0FF
* 8: 0x1FF
* 9: 0x3FF
* 10: 0x7FF
* 11~15: 0xFFF"
* [24] W Wdt_clear Write 1 to clear timer
* [32:16] R/W Wdt_en_byte Set 0xA5 to enable watch dog timer
* [15:0] R/W BIT_VNDR_divfactor "Dividing factor.Watch dog timer is count with 32.768KHz/(divfactor+1).
* Minimum dividing factor is 1."
*
*****************************************************************************************
* How to use WGD
*****************************************************************************************
* To use WDG peripheral, the following steps are mandatory:
*
* 1. Get count ID and divisor factor according to WDG timeout period using
* WDG_Scalar(WDG_TEST_TIMEOUT, &CountProcess, &DivFacProcess);
*
* 2. Configure WDG with the corresponding configuration.
* WDG_Init(&WDG_InitStruct)
*
* 3. Activate the WDG peripheral:
WDG_Cmd(ENABLE).
*
* @note In interrupt mode, call WDG_IrqInit() function after WDG_Init()
*
* @note WDG_Refresh() function is used to clear timer, if call this function before timeout period,
* then MCU reset or NMI interrupt won't generate
*
*****************************************************************************************
* @endverbatim
*/
/* Exported types ------------------------------------------------------------*/
/** @defgroup WDG_Exported_Types WDG Exported Types
* @{
*/
/**
* @brief WDG Init structure definition
*/
typedef struct
{
u32 CountProcess; /*!< WDG parameter get from WDG_Scalar, Specifies count id of WDG
This parameter must be set to a value in the 0-11 range */
u32 DivFacProcess; /*!< WDG parameter get from WDG_Scalar, Specifies WDG timeout count divisor factor
This parameter must be set to a value in the 1-65535 range */
} WDG_InitTypeDef;
/**
* @}
*/
/** @defgroup WDG_Exported_Functions WDG Exported Functions
* @{
*/
_LONG_CALL_ void WDG_Scalar(u32 Period, u32 *pCountProcess, u32 *pDivFacProcess);
_LONG_CALL_ void WDG_Init(WDG_InitTypeDef *WDG_InitStruct);
_LONG_CALL_ void WDG_IrqInit(void *handler, u32 Id);
_LONG_CALL_ void WDG_Cmd(u32 NewState);
_LONG_CALL_ void WDG_Refresh(void);
/**
* @}
*/
/* Registers Definitions --------------------------------------------------------*/
/**************************************************************************//**
* @defgroup WDG_Register_Definitions WDG Register Definitions
* @{
*****************************************************************************/
/**************************************************************************//**
* @defgroup WDG_REG
* @{
*****************************************************************************/
#define WDG_BIT_CLEAR ((u32)0x00000001 << 24)
#define WDG_BIT_RST_MODE ((u32)0x00000001 << 30)
#define WDG_BIT_ISR_CLEAR ((u32)0x00000001 << 31)
/** @} */
/** @} */
/**
* @}
*/
/**
* @}
*/
#endif //_RTL8711B_WDG_H_
/******************* (C) COPYRIGHT 2016 Realtek Semiconductor *****END OF FILE****/

View file

@ -0,0 +1,138 @@
/*
* Routines to access hardware
*
* Copyright (c) 2013 Realtek Semiconductor Corp.
*
* This module is a confidential and proprietary property of RealTek and
* possession or use of this module requires written permission of RealTek.
*/
#ifndef _SECTION_CONFIG_H_
#define _SECTION_CONFIG_H_
#include "basic_types.h"
#define RAM_VECTOR_TABLE1_SECTION \
SECTION(".ram_vector_table1")
#define RAM_VECTOR_TABLE2_SECTION \
SECTION(".ram_vector_table2")
#define RAM_VECTOR_TABLE3_SECTION \
SECTION(".ram_vector_table3")
//3 //3 Hal Section
#define HAL_ROM_TEXT_SECTION \
SECTION(".hal.rom.text")
#define HAL_ROM_DATA_SECTION \
SECTION(".hal.rom.rodata")
#define BOOT_RAM_TEXT_SECTION \
SECTION(".boot.ram.text")
#define BOOT_RAM_RODATA_SECTION \
SECTION(".boot.rodata")
#define BOOT_RAM_DATA_SECTION \
SECTION(".boot.ram.data")
#define BOOT_RAM_BSS_SECTION \
SECTION(".boot.ram.bss")
#define BOOT_RAM_END_BSS_SECTION \
SECTION(".boot.ram.end.bss")
#define HAL_ROM_BSS_SECTION \
SECTION(".hal.rom.bss")
//3 Store the Image 1 validate code
#define IMAGE1_VALID_PATTEN_SECTION \
SECTION(".image1.validate.rodata")
#define IMAGE2_VALID_PATTEN_SECTION \
SECTION(".image2.validate.rodata")
//3 SRAM Config Section
#define SRAM_BD_DATA_SECTION \
SECTION(".bdsram.data")
#define SRAM_BF_DATA_SECTION \
SECTION(".bfsram.data")
#define IMAGE1_ENTRY_SECTION \
SECTION(".image1.entry.data")
#define IMAGE1_EXPORT_SYMB_SECTION \
SECTION(".image1.export.symb")
// USB OTG Section
#if 0
#define OTG_ROM_BSS_SECTION \
SECTION(".otg.rom.bss")
#define OTG_ROM_TEXT_SECTION \
SECTION(".otg.rom.text")
#define OTG_ROM_DATA_SECTION \
SECTION(".otg.rom.rodata")
#define START_OTG_RAM_FUN_SECTION \
SECTION(".ram.otg.data.a")
#define START_OTG_RAM_DATA_SECTION \
SECTION(".ram.otg.data.b")
#endif
#define IMAGE2_ENTRY_SECTION \
SECTION(".image2.entry.data")
#define IMAGE2_RAM_TEXT_SECTION \
SECTION(".image2.ram.text")
//3 Wlan Section
#define WLAN_ROM_TEXT_SECTION \
SECTION(".wlan.rom.text")
#define WLAN_ROM_DATA_SECTION \
SECTION(".wlan.rom.rodata")
#define WLAN_RAM_MAP_SECTION \
SECTION(".wlan_ram_map")
//3 Apple Section
#define APPLE_ROM_TEXT_SECTION \
SECTION(".apple.rom.text")
#define APPLE_ROM_DATA_SECTION \
SECTION(".apple.rom.rodata")
//3 Libc Section
#define LIBC_ROM_TEXT_SECTION \
SECTION(".libc.rom.text")
#define LIBC_ROM_DATA_SECTION \
SECTION(".libc.rom.rodata")
#define LIBC_RAM_BSS_SECTION \
SECTION(".libc.ram.bss")
#define LIBC_HEAP_SECTION \
SECTION(".heap.stdlib")
//3 SSL Section
#define SSL_ROM_TEXT_SECTION \
SECTION(".ssl.rom.text")
#define SSL_ROM_DATA_SECTION \
SECTION(".ssl.rom.rodata")
#define SSL_RAM_MAP_SECTION \
SECTION(".ssl_ram_map")
//FLASH RUN CODE
#define FLASH_BOOT_TEXT_SECTION SECTION(".flashboot.text")
#define IMAGE2_CUSTOM_SIGNATURE SECTION(".img2_custom_signature") /* 32B: for OTA update */
/** @brief Put .debug_trace symbol in .TRACE section to reduce code size. */
#define DEBUG_TRACE_DATA_SECTION SECTION(".debug_trace") //__attribute__((aligned(4)))
//RDP (read protect area just text)
#define RDP_TEXT_SECTION SECTION(".rdp.ram.text")
#define RDP_DATA_SECTION SECTION(".rdp.ram.data")
#endif //_SECTION_CONFIG_H_

View file

@ -0,0 +1,44 @@
/**
******************************************************************************
* @file rtl8710b_dsleepcfg.c
* @author
* @version V1.0.0
* @date 2016-05-17
* @brief This file provides firmware functions to manage the following
* functionalities of pin control:
* - dsleep wakeup event
* - dsleep power management
******************************************************************************
* @attention
*
* This module is a confidential and proprietary property of RealTek and
* possession or use of this module requires written permission of RealTek.
*
* Copyright(c) 2015, Realtek Semiconductor Corporation. All rights reserved.
******************************************************************************
*/
#include "ameba_soc.h"
/* if X can wakeup dsleep, it can wakeup dstandby & sleep */
/* if X can wakeup dstandby, it can wakeup sleep */
const PWRCFG_TypeDef dsleep_wevent_config[]=
{
// Module Status
{BIT_SYSON_WEVT_A33_AND_A33GPIO_MSK, ON}, /* dsleep: REGU A33 Timer & A33 wakepin wakeup*/
{0xFFFFFFFF, OFF}, /* Table end */
};
/* you should set BIT_SYSON_WEVT_GPIO_DSTBY_MSK ON if you use wakepin */
const WAKEPIN_TypeDef dsleep_wakepin_config[]=
{
// Module Status Polarity
{WAKUP_0_MASK, OFF, 1}, /* wakeup_0: GPIOA_18 */
{WAKUP_1_MASK, ON, 1}, /* wakeup_1: GPIOA_5 */
{WAKUP_2_MASK, OFF, 1}, /* wakeup_2: GPIOA_22 */
{WAKUP_3_MASK, OFF, 1}, /* wakeup_3: GPIOA_23 */
{0xFFFFFFFF, OFF, 0}, /* Table end */
};
/******************* (C) COPYRIGHT 2016 Realtek Semiconductor *****END OF FILE****/

View file

@ -0,0 +1,47 @@
/**
******************************************************************************
* @file rtl8710b_dstandbycfg.c
* @author
* @version V1.0.0
* @date 2016-05-17
* @brief This file provides firmware functions to manage the following
* functionalities of pin control:
* - dstandby wakeup event
* - dstandby power management
******************************************************************************
* @attention
*
* This module is a confidential and proprietary property of RealTek and
* possession or use of this module requires written permission of RealTek.
*
* Copyright(c) 2015, Realtek Semiconductor Corporation. All rights reserved.
******************************************************************************
*/
#include "ameba_soc.h"
/* if X can wakeup dsleep, it can wakeup dstandby & sleep */
/* if X can wakeup dstandby, it can wakeup sleep */
const PWRCFG_TypeDef dstandby_wevent_config[]=
{
// Module Status
{BIT_SYSON_WEVT_GPIO_DSTBY_MSK, ON}, /* dstandby: wakepin 0~3 wakeup */
{BIT_SYSON_WEVT_A33_AND_A33GPIO_MSK, ON}, /* dsleep: REGU A33 Timer & A33 wakepin wakeup*/
{BIT_SYSON_WEVT_RTC_MSK, OFF}, /* dstandby: RTC Wakeup */
{BIT_SYSON_WEVT_SYSTIM_MSK, OFF}, /* dstandby: SYS Timer(ANA Timer) Wakeup */
{0xFFFFFFFF, OFF}, /* Table end */
};
/* you should set BIT_SYSON_WEVT_GPIO_DSTBY_MSK ON if you use wakepin */
const WAKEPIN_TypeDef dstandby_wakepin_config[]=
{
// Module Status Polarity
{WAKUP_0, OFF, 0}, /* wakeup_0: GPIOA_18 */
{WAKUP_1, ON, 0}, /* wakeup_1: GPIOA_5 */
{WAKUP_2, OFF, 0}, /* wakeup_2: GPIOA_22 */
{WAKUP_3, OFF, 0}, /* wakeup_3: GPIOA_23 */
{0xFFFFFFFF, OFF, 0}, /* Table end */
};
/******************* (C) COPYRIGHT 2016 Realtek Semiconductor *****END OF FILE****/

View file

@ -0,0 +1,34 @@
/**
******************************************************************************
* @file rtl8710b_intfcfg.c
* @author
* @version V1.0.0
* @date 2016-05-17
* @brief This file provides firmware functions to manage the following
* functionalities:
* - uart mbed function config
******************************************************************************
* @attention
*
* This module is a confidential and proprietary property of RealTek and
* possession or use of this module requires written permission of RealTek.
*
* Copyright(c) 2015, Realtek Semiconductor Corporation. All rights reserved.
******************************************************************************
*/
#include "ameba_soc.h"
UARTCFG_TypeDef uart_config[2]=
{
/* UART0 */
{
.LOW_POWER_RX_ENABLE = DISABLE, /*Enable low power RX*/
},
/* UART1 */
{
.LOW_POWER_RX_ENABLE = DISABLE,
},
};
/******************* (C) COPYRIGHT 2016 Realtek Semiconductor *****END OF FILE****/

View file

@ -0,0 +1,69 @@
/**
******************************************************************************
* @file rtl8710b_pinmapcfg.c
* @author
* @version V1.0.0
* @date 2016-05-17
* @brief This file provides firmware functions to manage the following
* functionalities of pin control:
* - pinmux
* - active pad pull up & pull down
* - sleep pad pull up & pull down
******************************************************************************
* @attention
*
* This module is a confidential and proprietary property of RealTek and
* possession or use of this module requires written permission of RealTek.
*
* Copyright(c) 2015, Realtek Semiconductor Corporation. All rights reserved.
******************************************************************************
*/
#include "ameba_soc.h"
const PMAP_TypeDef pmap_func[]=
{
// Pin Name Func Select Func PU/PD Slp PU/PD DrvStrenth
{_PA_14, PINMUX_FUNCTION_SWD, GPIO_PuPd_NOPULL, GPIO_PuPd_UP, PAD_DRV_STRENGTH_0}, //SWD_CLK
{_PA_15, PINMUX_FUNCTION_SWD, GPIO_PuPd_NOPULL, GPIO_PuPd_UP, PAD_DRV_STRENGTH_0}, //SWD_DATA
{_PA_13, PINMUX_FUNCTION_PWM, GPIO_PuPd_NOPULL, GPIO_PuPd_UP, PAD_DRV_STRENGTH_0}, //PWM4
{_PA_0, PINMUX_FUNCTION_PWM, GPIO_PuPd_NOPULL, GPIO_PuPd_DOWN,PAD_DRV_STRENGTH_0}, //PWM2
{_PA_16, PINMUX_FUNCTION_PWM, GPIO_PuPd_NOPULL, GPIO_PuPd_UP, PAD_DRV_STRENGTH_0}, //PWM1
{_PA_17, PINMUX_FUNCTION_PWM, GPIO_PuPd_NOPULL, GPIO_PuPd_UP, PAD_DRV_STRENGTH_0}, //PWM2
{_PA_25, PINMUX_FUNCTION_UART, GPIO_PuPd_NOPULL, GPIO_PuPd_UP, PAD_DRV_STRENGTH_0}, //UART1_RXD
{_PA_26, PINMUX_FUNCTION_UART, GPIO_PuPd_NOPULL, GPIO_PuPd_UP, PAD_DRV_STRENGTH_0}, //UART1_TXD
{_PA_28, PINMUX_FUNCTION_I2C, GPIO_PuPd_UP, GPIO_PuPd_UP, PAD_DRV_STRENGTH_0}, //I2C1_SCL
{_PA_27, PINMUX_FUNCTION_I2C, GPIO_PuPd_UP, GPIO_PuPd_UP, PAD_DRV_STRENGTH_0}, //I2C1_SDA
{_PA_12, PINMUX_FUNCTION_PWM, GPIO_PuPd_NOPULL, GPIO_PuPd_UP, PAD_DRV_STRENGTH_0}, //PWM3
{_PA_4, PINMUX_FUNCTION_UART, GPIO_PuPd_NOPULL, GPIO_PuPd_UP, PAD_DRV_STRENGTH_0}, //UART0_TXD
{_PA_1, PINMUX_FUNCTION_UART, GPIO_PuPd_NOPULL, GPIO_PuPd_UP, PAD_DRV_STRENGTH_0}, //UART0_RXD
{_PA_3, PINMUX_FUNCTION_UART, GPIO_PuPd_NOPULL, GPIO_PuPd_UP, PAD_DRV_STRENGTH_0}, //UART0_RTS
{_PA_2, PINMUX_FUNCTION_UART, GPIO_PuPd_NOPULL, GPIO_PuPd_UP, PAD_DRV_STRENGTH_0}, //UART0_CTS
{_PA_6, PINMUX_FUNCTION_SPIF, GPIO_PuPd_UP, GPIO_PuPd_UP, PAD_DRV_STRENGTH_0}, //SPIC_CS
{_PA_7, PINMUX_FUNCTION_SPIF, GPIO_PuPd_UP, GPIO_PuPd_UP, PAD_DRV_STRENGTH_0}, //SPIC_DATA1
{_PA_8, PINMUX_FUNCTION_SPIF, GPIO_PuPd_UP, GPIO_PuPd_UP, PAD_DRV_STRENGTH_0}, //SPIC_DATA2
{_PA_9, PINMUX_FUNCTION_SPIF, GPIO_PuPd_UP, GPIO_PuPd_UP, PAD_DRV_STRENGTH_0}, //SPIC_DATA0
{_PA_10, PINMUX_FUNCTION_SPIF, GPIO_PuPd_UP, GPIO_PuPd_UP, PAD_DRV_STRENGTH_0}, //SPIC_CLK
{_PA_11, PINMUX_FUNCTION_SPIF, GPIO_PuPd_UP, GPIO_PuPd_UP, PAD_DRV_STRENGTH_0}, //SPIC_DATA3
{_PA_5, PINMUX_FUNCTION_PWM, GPIO_PuPd_UP, GPIO_PuPd_UP, PAD_DRV_STRENGTH_0}, //PWM4
{_PA_18, PINMUX_FUNCTION_SDIOD, GPIO_PuPd_NOPULL, GPIO_PuPd_UP, PAD_DRV_STRENGTH_0}, //SD_D2
{_PA_19, PINMUX_FUNCTION_SDIOD, GPIO_PuPd_NOPULL, GPIO_PuPd_UP, PAD_DRV_STRENGTH_0}, //SD_D3
{_PA_20, PINMUX_FUNCTION_SDIOD, GPIO_PuPd_NOPULL, GPIO_PuPd_UP, PAD_DRV_STRENGTH_0}, //SD_CMD
{_PA_21, PINMUX_FUNCTION_SDIOD, GPIO_PuPd_NOPULL, GPIO_PuPd_UP, PAD_DRV_STRENGTH_0}, //SD_CLK
{_PA_22, PINMUX_FUNCTION_SDIOD, GPIO_PuPd_UP, GPIO_PuPd_UP, PAD_DRV_STRENGTH_0}, //SD_D0
{_PA_23, PINMUX_FUNCTION_SDIOD, GPIO_PuPd_NOPULL, GPIO_PuPd_UP, PAD_DRV_STRENGTH_0}, //SD_D1
{_PB_0, PINMUX_FUNCTION_SPIM, GPIO_PuPd_NOPULL, GPIO_PuPd_UP, PAD_DRV_STRENGTH_0}, //SPI1_CS
{_PB_1, PINMUX_FUNCTION_SPIM, GPIO_PuPd_NOPULL, GPIO_PuPd_UP, PAD_DRV_STRENGTH_0}, //SPI1_CLK
{_PB_2, PINMUX_FUNCTION_SPIM, GPIO_PuPd_NOPULL, GPIO_PuPd_UP, PAD_DRV_STRENGTH_0}, //SPI1_MISO
{_PB_3, PINMUX_FUNCTION_SPIM, GPIO_PuPd_NOPULL, GPIO_PuPd_UP, PAD_DRV_STRENGTH_0}, //SPI1_MOSI
{_PB_4, PINMUX_FUNCTION_I2S, GPIO_PuPd_NOPULL, GPIO_PuPd_UP, PAD_DRV_STRENGTH_0}, //I2S_MCK
{_PB_5, PINMUX_FUNCTION_I2S, GPIO_PuPd_NOPULL, GPIO_PuPd_UP, PAD_DRV_STRENGTH_0}, //I2S_SD_TX
{_PA_24, PINMUX_FUNCTION_I2S, GPIO_PuPd_NOPULL, GPIO_PuPd_UP, PAD_DRV_STRENGTH_0}, //I2S_SD_RX
{_PA_31, PINMUX_FUNCTION_I2S, GPIO_PuPd_NOPULL, GPIO_PuPd_UP, PAD_DRV_STRENGTH_0}, //I2S_CLK
{_PB_6, PINMUX_FUNCTION_I2S, GPIO_PuPd_NOPULL, GPIO_PuPd_UP, PAD_DRV_STRENGTH_0}, //I2S_WS
{_PA_30, PINMUX_FUNCTION_UART, GPIO_PuPd_UP, GPIO_PuPd_UP, PAD_DRV_STRENGTH_0}, //UART2_log_TXD
{_PA_29, PINMUX_FUNCTION_UART, GPIO_PuPd_UP, GPIO_PuPd_UP, PAD_DRV_STRENGTH_0}, //UART2_log_RXD
{_PNC, PINMUX_FUNCTION_GPIO, GPIO_PuPd_NOPULL, GPIO_PuPd_NOPULL, PAD_DRV_STRENGTH_0}, //table end
};
/******************* (C) COPYRIGHT 2016 Realtek Semiconductor *****END OF FILE****/

View file

@ -0,0 +1,69 @@
/**
******************************************************************************
* @file rtl8710b_sleepcfg.c
* @author
* @version V1.0.0
* @date 2016-05-17
* @brief This file provides firmware functions to manage the following
* functionalities of pin control:
* - sleep wakeup event
* - sleep power management
******************************************************************************
* @attention
*
* This module is a confidential and proprietary property of RealTek and
* possession or use of this module requires written permission of RealTek.
*
* Copyright(c) 2015, Realtek Semiconductor Corporation. All rights reserved.
******************************************************************************
*/
#include "ameba_soc.h"
const PWRCFG_TypeDef sleep_pwrmgt_config[]=
{
// Module Status
{BIT_SYSON_PMOPT_SLP_XTAL_EN, OFF}, /* XTAL: 2.2mA */
{BIT_SYSON_PMOPT_SNZ_XTAL_EN, OFF}, /* ADC power save use it */
{BIT_SYSON_PMOPT_SNZ_SYSPLL_EN, OFF}, /* ADC power save use it */
{0xFFFFFFFF, OFF}, /* Table end */
};
/* if X can wakeup dsleep, it can wakeup dstandby & sleep */
/* if X can wakeup dstandby, it can wakeup sleep */
const PWRCFG_TypeDef sleep_wevent_config[]=
{
// Module Status
{BIT_SYSON_WEVT_GPIO_DSTBY_MSK, ON}, /* dstandby: wakepin 0~3 wakeup */
{BIT_SYSON_WEVT_A33_AND_A33GPIO_MSK, ON}, /* dsleep: REGU A33 Timer(1K low precision timer) & A33 wakepin wakeup*/
{BIT_SYSON_WEVT_ADC_MSK, ON}, /* sleep: ADC Wakeup */
{BIT_SYSON_WEVT_SDIO_MSK, OFF}, /* sleep: SDIO Wakeup */
{BIT_SYSON_WEVT_RTC_MSK, ON}, /* dstandby: RTC Wakeup */
{BIT_SYSON_WEVT_UART1_MSK, ON}, /* sleep: UART1 Wakeup */
{BIT_SYSON_WEVT_UART0_MSK, ON}, /* sleep: UART0 Wakeup */
{BIT_SYSON_WEVT_I2C1_MSK, OFF}, /* sleep: I2C1 Wakeup */
{BIT_SYSON_WEVT_I2C0_MSK, OFF}, /* sleep: I2C0 Wakeup */
{BIT_SYSON_WEVT_WLAN_MSK, ON}, /* sleep: WLAN Wakeup */
{BIT_SYSON_WEVT_I2C1_ADDRMATCH_MSK, OFF}, /* sleep: I2C1 Slave RX address Wakeup */
{BIT_SYSON_WEVT_I2C0_ADDRMATCH_MSK, OFF}, /* sleep: I2C0 Slave RX address Wakeup */
{BIT_SYSON_WEVT_USB_MSK, OFF}, /* sleep: USB Wakeup */
{BIT_SYSON_WEVT_GPIO_MSK, ON}, /* sleep: GPIO Wakeup */
{BIT_SYSON_WEVT_OVER_CURRENT_MSK, OFF}, /* sleep: REGU OVER_CURRENT Wakeup */
{BIT_SYSON_WEVT_SYSTIM_MSK, ON}, /* dstandby: 250K SYS Timer(ANA Timer) Wakeup */
{0xFFFFFFFF, OFF}, /* Table end */
};
/* you should set BIT_SYSON_WEVT_GPIO_DSTBY_MSK ON if you use wakepin */
const WAKEPIN_TypeDef sleep_wakepin_config[]=
{
// Module Status Polarity
{WAKUP_0, OFF, 0}, /* wakeup_0: GPIOA_18 */
{WAKUP_1, ON, 0}, /* wakeup_1: GPIOA_5 */
{WAKUP_2, OFF, 0}, /* wakeup_2: GPIOA_22 */
{WAKUP_3, OFF, 0}, /* wakeup_3: GPIOA_23 */
{0xFFFFFFFF, OFF, 0}, /* Table end */
};
/******************* (C) COPYRIGHT 2016 Realtek Semiconductor *****END OF FILE****/

View file

@ -0,0 +1,279 @@
/*
* Routines to access hardware
*
* Copyright (c) 2013 Realtek Semiconductor Corp.
*
* This module is a confidential and proprietary property of RealTek and
* possession or use of this module requires written permission of RealTek.
*/
#include "ameba_soc.h"
#include "build_info.h"
#include "strproc.h"
#include "system_8195a.h"
u32 random_seed;
#if defined ( __ICCARM__ )
#pragma section=".ram_image2.bss"
#pragma section=".ram_image2.skb.bss"
#pragma section=".rom.bss"
#pragma section=".ram.start.table"
#pragma section=".ram_image1.bss"
#pragma section=".image2.start.table1"
#pragma section=".image2.start.table2"
u8* __bss_start__;
u8* __bss_end__;
void __iar_data_init_app(void)
{
__bss_start__ = (u8*)__section_begin(".ram_image2.bss");
__bss_end__ = (u8*)__section_end(".ram_image2.skb.bss");
}
#endif
extern VOID SOCPS_WakeFromPG(VOID);
#if defined ( __ICCARM__ )
VOID
HalHardFaultHandler_user_define(u32 HardDefaultArg)
{
}
VOID
HalHardFaultHandler_Patch_c(u32 HardDefaultArg)
{
HalHardFaultHandler_user_define(HardDefaultArg);
INT_HardFault(HardDefaultArg);
}
VOID
HalHardFaultHandler_Patch_asm(void)
{
asm("TST LR, #4\n"
"ITE EQ\n"
"MRSEQ R0, MSP\n"
"MRSNE R0, PSP\n"
"B HalHardFaultHandler_Patch_c");
}
#endif
// Override original Interrupt Vector Table
VOID BOOT_VectorTableOverride(u32 StackP)
{
// Override NMI Handler
//4 Initial NMI
//NewVectorTable[2] = (HAL_VECTOR_FUN)HalNMIHandler_Patch;
#if 0//defined ( __ICCARM__ )
//Redefine Hardfault Handler
NewVectorTable[3] = (HAL_VECTOR_FUN)HalHardFaultHandler_Patch_asm;
#endif
}
void BOOT_Reason(void)
{
u32 backup_reg0 = BKUP_Read(BKUP_REG0);
DBG_8195A("boot reason: %x \n", backup_reg0);
}
extern u32 GlobalDebugEnable;
VOID BOOT_InitDebugFlg(VOID)
{
SYSTEM_DATA *SysData = (SYSTEM_DATA *)(SPI_FLASH_BASE + FLASH_SYSTEM_DATA_ADDR);
/* reset */
ConfigDebugErr = 0;
ConfigDebugWarn = 0;
ConfigDebugInfo = 0;
#if (defined(CONFIG_POST_SIM) || defined(CONFIG_CP))
return;
#endif
/* to initial ROM code using global variable */
#ifdef CONFIG_DEBUG_ERR_MSG
ConfigDebugErr = 0xFFFFFFFF;//_DBG_MISC_;]
#endif
#ifdef CONFIG_DEBUG_WARN_MSG
ConfigDebugWarn = 0xFFFFFFFF;
#endif
#ifdef CONFIG_DEBUG_INFO_MSG
ConfigDebugInfo = 0xFFFFFFFF;
#endif
if (SysData->UlogDbgEn == 0x0) {
ConfigDebugErr = 0;
ConfigDebugWarn = 0;
ConfigDebugInfo = 0;
GlobalDebugEnable = 0;
}
}
VOID BOOT_RTC_Init(VOID)
{
RTC_InitTypeDef RTC_InitStruct_temp;
RTC_AlarmTypeDef RTC_AlarmStruct_temp;
RTC_TimeTypeDef RTC_TimeStruct;
/* for 32K more stable */
NCO32K_Init(32768, XTAL_ClkGet(), 15, 2);
RTC_ClokSource(0);
RTC_StructInit(&RTC_InitStruct_temp);
RTC_Init(&RTC_InitStruct_temp);
/* 32760 need add need add 15 cycles (256Hz) every 4 min*/
//RTC_SmoothCalibConfig(RTC_CalibSign_Positive, 15,
// RTC_CalibPeriod_4MIN, RTC_Calib_Enable);
/* set time when power on */
RTC_GetTime(RTC_Format_BIN, &RTC_TimeStruct);
if (RTC_TimeStruct.RTC_Seconds == 0 && RTC_TimeStruct.RTC_Minutes == 0) {
RTC_TimeStructInit(&RTC_TimeStruct);
RTC_SetTime(RTC_Format_BIN, &RTC_TimeStruct);
}
/* set alarm */
RTC_AlarmStructInit(&RTC_AlarmStruct_temp);
RTC_AlarmStruct_temp.RTC_AlarmTime.RTC_Days = 1;
RTC_AlarmStruct_temp.RTC_AlarmTime.RTC_Hours = 1;
RTC_AlarmStruct_temp.RTC_AlarmTime.RTC_Minutes = 1;
RTC_AlarmStruct_temp.RTC_AlarmTime.RTC_Seconds = 30;
RTC_AlarmStruct_temp.RTC_AlarmMask = RTC_AlarmMask_Hours | RTC_AlarmMask_Minutes;
RTC_AlarmStruct_temp.RTC_Alarm2Mask = RTC_Alarm2Mask_Days;
RTC_SetAlarm(RTC_Format_BIN, &RTC_AlarmStruct_temp);
RTC_AlarmCmd(DISABLE);
/* RTC interrupt hander is reserved for user */
//InterruptRegister((IRQ_FUN)BOOT_RTC_Handler, RTC_IRQ, NULL, 4);
//InterruptEn(RTC_IRQ, 4);
}
VOID BOOT_PlatformInit(VOID)
{
u32 Temp = 0;
/* Set SPS lower voltage */
//Temp = ((HAL_READ32(SYSTEM_CTRL_BASE, REG_SYS_EFUSE_SYSCFG0)&0xf0ffffff)|0x6000000);
//HAL_WRITE32(SYSTEM_CTRL_BASE, REG_SYS_EFUSE_SYSCFG0, Temp);
/* Driving control of RF1 clock buffer, 11:large current, 00: small current */
Temp = HAL_READ32(SYSTEM_CTRL_BASE, REG_SYS_XTAL_CTRL1);
Temp &= ~(BIT_SYS_XTAL_DRV_RF1(3));
Temp |= BIT_SYS_XTAL_DRV_RF1(1);
HAL_WRITE32(SYSTEM_CTRL_BASE, REG_SYS_XTAL_CTRL1, Temp);
}
//3 Imgae 2
VOID BOOT_Image2(VOID)
{
int ret = 0;
#ifdef CONFIG_FPGA
MPU->RNR = 0; //0xE000ED00, 0x98 MPU Region RNRber Register
MPU->RBAR = 0; //0xE000ED00, 0x9C MPU Region Base Address Register
MPU->RASR = 0x6000027; //0xE000ED00, 0xA0 MPU Region Attribute and Size Register
MPU->CTRL = 7; //0xE000ED00, 0x94 MPU Control Register
#endif
#if defined ( __ICCARM__ )
__iar_data_init_app();
#endif
BOOT_InitDebugFlg();
BOOT_VectorTableOverride(0x1003EFFC);
/* set CPU clock if needed, default is 125MHz */
//CPU_ClkSet((u8)(CPU_CLOCK_SEL_VALUE));
//DelayUs(10);
#if (defined(CONFIG_CP))
CPTest_EnterImg2Ok();
#endif
DBG_8195A("===== Enter Image 2 ====\n");
//3 0) Vendor Config function
//4 Ram Bss Iitial
u32 BssLen = (__bss_end__ - __bss_start__);
_memset((void *) __bss_start__, 0, BssLen);
SystemCoreClockUpdate();
ret = boot_export_symbol.boot_system_init1();
//BOOT_PlatformInit();
#if (!defined(CONFIG_FPGA) && !defined(CONFIG_POST_SIM))
#if defined(CONFIG_OSC8M_8388608HZ)
OSC8M_Calibration(DISABLE, OSC32K_CALI_32KCYC_064, OSC8M_8388608HZ);
#elif defined(CONFIG_OSC8M_8192000HZ)
OSC8M_Calibration(DISABLE, OSC32K_CALI_32KCYC_064, OSC8M_8192000HZ);
#elif defined(CONFIG_OSC8M_8000000HZ)
OSC8M_Calibration(DISABLE, OSC32K_CALI_32KCYC_064, OSC8M_8000000HZ);
#elif defined(CONFIG_OSC8M_16777216HZ)
OSC8M_Calibration(DISABLE, OSC32K_CALI_32KCYC_064, OSC8M_16777216HZ);
#endif
DelayUs(90);
DelayUs(90);
#endif //CONFIG_FPGA
#ifdef CONFIG_CP
CPTest_OSCCalibrationOk();
#endif
/* Workaround for the GPIOA_7 didn't pull high: it may cause the
SDIO Device hardware be enabled automatically at power on and then
GPIOA[7:0] will be used for SDIO device */
#ifndef CONFIG_SDIO_DEVICE_EN
// SDIO Pin Mux off
SDIOD_PIN_FCTRL(OFF);
#endif
DBG_8195A("OSC8M: %x \n", OSC8M_Get());
BOOT_Reason();
BOOT_RTC_Init();
#if (!defined(CONFIG_FPGA))
random_seed = Gen_RandomSeed();
#endif
#if defined(CONFIG_WIFI_NORMAL) && defined(CONFIG_NETWORK)
rtw_efuse_boot_write();
#endif
ret = boot_export_symbol.boot_system_init2();
APP_Start();
#if defined ( __ICCARM__ )
// it is dummy code, but IAR linker need this
__iar_data_init3();
#endif
}
IMAGE2_VALID_PATTEN_SECTION
const u8 RAM_IMG2_VALID_PATTEN[20] = {
'R', 'T', 'K', 'W', 'i', 'n', 0x0, 0xff,
(FW_VERSION&0xff), ((FW_VERSION >> 8)&0xff),
(FW_SUBVERSION&0xff), ((FW_SUBVERSION >> 8)&0xff),
(FW_CHIP_ID&0xff), ((FW_CHIP_ID >> 8)&0xff),
(FW_CHIP_VER),
(FW_BUS_TYPE),
(FW_INFO_RSV1),
(FW_INFO_RSV2),
(FW_INFO_RSV3),
(FW_INFO_RSV4)
};
IMAGE2_ENTRY_SECTION
RAM_START_FUNCTION gImage2EntryFun0 = {
BOOT_Image2,
SOCPS_WakeFromPG
};