release SDK 3.0.9.1

add multiconnection SDK
This commit is contained in:
Dog_Egg 2021-06-24 13:53:31 +08:00
parent f6e9c61062
commit 6a068c71ca
45 changed files with 10274 additions and 8373 deletions

View File

@ -798,7 +798,8 @@ static uint8 MultiRole_processGAPMsg(gapEventHdr_t* pMsg)
if( info.value.role == Slave_Role )
{
gapBond_PairingMode[ pPkt->connectionHandle ] = GAPBOND_PAIRING_MODE_INITIATE ;
// gapBond_PairingMode[ pPkt->connectionHandle ] = GAPBOND_PAIRING_MODE_INITIATE ;
gapBond_PairingMode[ pPkt->connectionHandle ] = GAPBOND_PAIRING_MODE_NO_PAIRING ;
uint8 bondret = GAPBondMgr_LinkEst( pPkt->devAddrType, pPkt->devAddr, pPkt->connectionHandle, GAP_PROFILE_PERIPHERAL );
LOG("GAPBondMgr_LinkEst SLAVE bondret %d\n",bondret);
// varify if enable connection parameter update?

View File

@ -60,7 +60,7 @@ uint8 test_type;
// Scan duration in ms
#if ONLY_SCAN_MODE
#define DEFAULT_SCAN_DURATION 1400
#define DEFAULT_SCAN_DURATION 100 ///1400
#else
#define DEFAULT_SCAN_DURATION 5000
#endif
@ -433,6 +433,15 @@ void SimpleBLECentral_Init( uint8 task_id )
// Setup GAP
GAP_SetParamValue(TGAP_GEN_DISC_SCAN, DEFAULT_SCAN_DURATION);
GAP_SetParamValue(TGAP_LIM_DISC_SCAN, DEFAULT_SCAN_DURATION);
#if ONLY_SCAN_MODE
GAP_SetParamValue(TGAP_GEN_DISC_SCAN_INT, 5);
GAP_SetParamValue(TGAP_GEN_DISC_SCAN_WIND, 5);
GAP_SetParamValue(TGAP_LIM_DISC_SCAN_INT, 5);
GAP_SetParamValue(TGAP_LIM_DISC_SCAN_WIND, 5);
#endif
GAP_SetParamValue(TGAP_CONN_EST_INT_MIN, 30); // * 1.25ms // 30
GAP_SetParamValue(TGAP_CONN_EST_INT_MAX, 40);
GGS_SetParameter(GGS_DEVICE_NAME_ATT, GAP_DEVICE_NAME_LEN, (uint8*)simpleBLEDeviceName);

View File

@ -0,0 +1,242 @@
;/**************************************************************************//**
; * @file startup_ARMCM0.s
; * @brief CMSIS Core Device Startup File for
; * ARMCM0 Device Series
; * @version V5.00
; * @date 02. March 2016
; ******************************************************************************/
;/*
; * Copyright (c) 2009-2016 ARM Limited. All rights reserved.
; *
; * SPDX-License-Identifier: Apache-2.0
; *
; * Licensed under the Apache License, Version 2.0 (the License); you may
; * not use this file except in compliance with the License.
; * You may obtain a copy of the License at
; *
; * www.apache.org/licenses/LICENSE-2.0
; *
; * Unless required by applicable law or agreed to in writing, software
; * distributed under the License is distributed on an AS IS BASIS, WITHOUT
; * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
; * See the License for the specific language governing permissions and
; * limitations under the License.
; */
;/*
;//-------- <<< Use Configuration Wizard in Context Menu >>> ------------------
;*/
; <h> Stack Configuration
; <o> Stack Size (in Bytes) <0x0-0xFFFFFFFF:8>
; </h>
Stack_Size EQU 0x00000400
AREA STACK, NOINIT, READWRITE, ALIGN=3
Stack_Mem SPACE Stack_Size
__initial_sp
; <h> Heap Configuration
; <o> Heap Size (in Bytes) <0x0-0xFFFFFFFF:8>
; </h>
Heap_Size EQU 0x00000100
AREA HEAP, NOINIT, READWRITE, ALIGN=3
__heap_base
Heap_Mem SPACE Heap_Size
__heap_limit
PRESERVE8
THUMB
; Vector Table Mapped to Address 0 at Reset
AREA RESET, DATA, READONLY
EXPORT __Vectors
EXPORT __Vectors_End
EXPORT __Vectors_Size
__Vectors DCD __initial_sp ; Top of Stack
DCD Reset_Handler ; Reset Handler
DCD NMI_Handler ; NMI Handler
DCD HardFault_Handler ; Hard Fault Handler
DCD 0 ; Reserved
DCD 0 ; Reserved
DCD 0 ; Reserved
DCD 0 ; Reserved
DCD 0 ; Reserved
DCD 0 ; Reserved
DCD 0 ; Reserved
DCD SVC_Handler ; SVCall Handler
DCD 0 ; Reserved
DCD 0 ; Reserved
DCD PendSV_Handler ; PendSV Handler
DCD SysTick_Handler ; SysTick Handler
; External Interrupts
DCD WDT_IRQHandler ; 0: Watchdog Timer
DCD RTC_IRQHandler ; 1: Real Time Clock
DCD TIM0_IRQHandler ; 2: Timer0 / Timer1
DCD TIM2_IRQHandler ; 3: Timer2 / Timer3
DCD MCIA_IRQHandler ; 4: MCIa
DCD MCIB_IRQHandler ; 5: MCIb
DCD UART0_IRQHandler ; 6: UART0 - DUT FPGA
DCD UART1_IRQHandler ; 7: UART1 - DUT FPGA
DCD UART2_IRQHandler ; 8: UART2 - DUT FPGA
DCD UART4_IRQHandler ; 9: UART4 - not connected
DCD AACI_IRQHandler ; 10: AACI / AC97
DCD CLCD_IRQHandler ; 11: CLCD Combined Interrupt
DCD ENET_IRQHandler ; 12: Ethernet
DCD USBDC_IRQHandler ; 13: USB Device
DCD USBHC_IRQHandler ; 14: USB Host Controller
DCD CHLCD_IRQHandler ; 15: Character LCD
DCD FLEXRAY_IRQHandler ; 16: Flexray
DCD CAN_IRQHandler ; 17: CAN
DCD LIN_IRQHandler ; 18: LIN
DCD I2C_IRQHandler ; 19: I2C ADC/DAC
DCD 0 ; 20: Reserved
DCD 0 ; 21: Reserved
DCD 0 ; 22: Reserved
DCD 0 ; 23: Reserved
DCD 0 ; 24: Reserved
DCD 0 ; 25: Reserved
DCD 0 ; 26: Reserved
DCD 0 ; 27: Reserved
DCD CPU_CLCD_IRQHandler ; 28: Reserved - CPU FPGA CLCD
DCD 0 ; 29: Reserved - CPU FPGA
DCD UART3_IRQHandler ; 30: UART3 - CPU FPGA
DCD SPI_IRQHandler ; 31: SPI Touchscreen - CPU FPGA
__Vectors_End
__Vectors_Size EQU __Vectors_End - __Vectors
AREA |.text|, CODE, READONLY
; Reset Handler
Reset_Handler PROC
EXPORT Reset_Handler [WEAK]
IMPORT SystemInit
IMPORT __main
LDR R0, =SystemInit
BLX R0
LDR R0, =__main
BX R0
ENDP
; Dummy Exception Handlers (infinite loops which can be modified)
NMI_Handler PROC
EXPORT NMI_Handler [WEAK]
B .
ENDP
HardFault_Handler\
PROC
EXPORT HardFault_Handler [WEAK]
B .
ENDP
SVC_Handler PROC
EXPORT SVC_Handler [WEAK]
B .
ENDP
PendSV_Handler PROC
EXPORT PendSV_Handler [WEAK]
B .
ENDP
SysTick_Handler PROC
EXPORT SysTick_Handler [WEAK]
B .
ENDP
Default_Handler PROC
EXPORT WDT_IRQHandler [WEAK]
EXPORT RTC_IRQHandler [WEAK]
EXPORT TIM0_IRQHandler [WEAK]
EXPORT TIM2_IRQHandler [WEAK]
EXPORT MCIA_IRQHandler [WEAK]
EXPORT MCIB_IRQHandler [WEAK]
EXPORT UART0_IRQHandler [WEAK]
EXPORT UART1_IRQHandler [WEAK]
EXPORT UART2_IRQHandler [WEAK]
EXPORT UART3_IRQHandler [WEAK]
EXPORT UART4_IRQHandler [WEAK]
EXPORT AACI_IRQHandler [WEAK]
EXPORT CLCD_IRQHandler [WEAK]
EXPORT ENET_IRQHandler [WEAK]
EXPORT USBDC_IRQHandler [WEAK]
EXPORT USBHC_IRQHandler [WEAK]
EXPORT CHLCD_IRQHandler [WEAK]
EXPORT FLEXRAY_IRQHandler [WEAK]
EXPORT CAN_IRQHandler [WEAK]
EXPORT LIN_IRQHandler [WEAK]
EXPORT I2C_IRQHandler [WEAK]
EXPORT CPU_CLCD_IRQHandler [WEAK]
EXPORT SPI_IRQHandler [WEAK]
WDT_IRQHandler
RTC_IRQHandler
TIM0_IRQHandler
TIM2_IRQHandler
MCIA_IRQHandler
MCIB_IRQHandler
UART0_IRQHandler
UART1_IRQHandler
UART2_IRQHandler
UART3_IRQHandler
UART4_IRQHandler
AACI_IRQHandler
CLCD_IRQHandler
ENET_IRQHandler
USBDC_IRQHandler
USBHC_IRQHandler
CHLCD_IRQHandler
FLEXRAY_IRQHandler
CAN_IRQHandler
LIN_IRQHandler
I2C_IRQHandler
CPU_CLCD_IRQHandler
SPI_IRQHandler
B .
ENDP
ALIGN
; User Initial Stack & Heap
IF :DEF:__MICROLIB
EXPORT __initial_sp
EXPORT __heap_base
EXPORT __heap_limit
ELSE
IMPORT __use_two_region_memory
EXPORT __user_initial_stackheap
__user_initial_stackheap PROC
LDR R0, = Heap_Mem
LDR R1, =(Stack_Mem + Stack_Size)
LDR R2, = (Heap_Mem + Heap_Size)
LDR R3, = Stack_Mem
BX LR
ENDP
ALIGN
ENDIF
END

View File

@ -0,0 +1,56 @@
/**************************************************************************//**
@file system_ARMCM0.c
@brief CMSIS Device System Source File for
ARMCM0 Device Series
@version V5.00
@date 07. September 2016
******************************************************************************/
/*
Copyright (c) 2009-2016 ARM Limited. All rights reserved.
SPDX-License-Identifier: Apache-2.0
Licensed under the Apache License, Version 2.0 (the License); you may
not use this file except in compliance with the License.
You may obtain a copy of the License at
www.apache.org/licenses/LICENSE-2.0
Unless required by applicable law or agreed to in writing, software
distributed under the License is distributed on an AS IS BASIS, WITHOUT
WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
See the License for the specific language governing permissions and
limitations under the License.
*/
#include "ARMCM0.h"
/* ----------------------------------------------------------------------------
Define clocks
----------------------------------------------------------------------------*/
#define XTAL ( 5000000UL) /* Oscillator frequency */
#define SYSTEM_CLOCK (5U * XTAL)
/* ----------------------------------------------------------------------------
System Core Clock Variable
----------------------------------------------------------------------------*/
uint32_t SystemCoreClock = SYSTEM_CLOCK;
/* ----------------------------------------------------------------------------
System Core Clock update function
----------------------------------------------------------------------------*/
void SystemCoreClockUpdate (void)
{
SystemCoreClock = SYSTEM_CLOCK;
}
/* ----------------------------------------------------------------------------
System initialization function
----------------------------------------------------------------------------*/
void SystemInit (void)
{
SystemCoreClock = SYSTEM_CLOCK;
}

View File

@ -0,0 +1,20 @@
/*
* Auto generated Run-Time-Environment Component Configuration File
* *** Do not modify ! ***
*
* Project: 'simpleBleMulti'
* Target: 'Target 1'
*/
#ifndef RTE_COMPONENTS_H
#define RTE_COMPONENTS_H
/*
* Define the Device Header File:
*/
#define CMSIS_device_header "ARMCM0.h"
#endif /* RTE_COMPONENTS_H */

View File

@ -0,0 +1,208 @@
/**************************************************************************************************
*******
**************************************************************************************************/
#include "bus_dev.h"
#include "gpio.h"
#include "clock.h"
#include "timer.h"
#include "jump_function.h"
#include "pwrmgr.h"
#include "mcu.h"
#include "gpio.h"
#include "log.h"
#include "rf_phy_driver.h"
#include "flash.h"
#include "version.h"
#include "fs.h"
#define DEFAULT_UART_BAUD 115200
/*********************************************************************
LOCAL FUNCTION PROTOTYPES
*/
/*********************************************************************
EXTERNAL FUNCTIONS
*/
extern void init_config(void);
extern int app_main(void);
extern void hal_rom_boot_init(void);
/*********************************************************************
CONNECTION CONTEXT RELATE DEFINITION
*/
#define BLE_MAX_ALLOW_CONNECTION 2
#define BLE_MAX_ALLOW_PKT_PER_EVENT_TX 6
#define BLE_MAX_ALLOW_PKT_PER_EVENT_RX 6
#define BLE_PKT_VERSION BLE_PKT_VERSION_4_0 //BLE_PKT_VERSION_5_1 //BLE_PKT_VERSION_5_1
#define BLE_PKT_BUF_SIZE (((BLE_PKT_VERSION == BLE_PKT_VERSION_5_1) ? 1 : 0) * BLE_PKT51_LEN \
+ ((BLE_PKT_VERSION == BLE_PKT_VERSION_4_0) ? 1 : 0) * BLE_PKT40_LEN \
+ (sizeof(struct ll_pkt_desc) - 2))
#define BLE_MAX_ALLOW_PER_CONNECTION ( (BLE_MAX_ALLOW_PKT_PER_EVENT_TX * BLE_PKT_BUF_SIZE*2) \
+(BLE_MAX_ALLOW_PKT_PER_EVENT_RX * BLE_PKT_BUF_SIZE) \
+ BLE_PKT_BUF_SIZE )
#define BLE_CONN_BUF_SIZE (BLE_MAX_ALLOW_CONNECTION * BLE_MAX_ALLOW_PER_CONNECTION)
__align(4) uint8 g_pConnectionBuffer[BLE_CONN_BUF_SIZE];
llConnState_t pConnContext[BLE_MAX_ALLOW_CONNECTION];
/*********************************************************************
CTE IQ SAMPLE BUF config
*/
//#define BLE_SUPPORT_CTE_IQ_SAMPLE TRUE
#ifdef BLE_SUPPORT_CTE_IQ_SAMPLE
uint16 g_llCteSampleI[LL_CTE_MAX_SUPP_LEN * LL_CTE_SUPP_LEN_UNIT];
uint16 g_llCteSampleQ[LL_CTE_MAX_SUPP_LEN * LL_CTE_SUPP_LEN_UNIT];
#endif
/*********************************************************************
OSAL LARGE HEAP CONFIG
*/
#define LARGE_HEAP_SIZE (8*1024)
uint8 g_largeHeap[LARGE_HEAP_SIZE];
/*********************************************************************
GLOBAL VARIABLES
*/
volatile uint8 g_clk32K_config;
volatile sysclk_t g_spif_clk_config;
/*********************************************************************
EXTERNAL VARIABLES
*/
extern uint32_t __initial_sp;
static void hal_low_power_io_init(void)
{
//========= pull all io to gnd by default
ioinit_cfg_t ioInit[]=
{
//TSOP6252 10 IO
{GPIO_P02, GPIO_FLOATING },/*SWD*/
{GPIO_P03, GPIO_FLOATING },/*SWD*/
{GPIO_P09, GPIO_PULL_UP },/*UART TX*/
{GPIO_P10, GPIO_PULL_UP },/*UART RX*/
{GPIO_P11, GPIO_PULL_DOWN },
{GPIO_P14, GPIO_PULL_DOWN },
{GPIO_P15, GPIO_PULL_DOWN },
{GPIO_P16, GPIO_FLOATING },
{GPIO_P18, GPIO_PULL_DOWN },
{GPIO_P20, GPIO_PULL_DOWN },
#if(SDK_VER_CHIP==__DEF_CHIP_QFN32__)
//6222 23 IO
{GPIO_P00, GPIO_PULL_DOWN },
{GPIO_P01, GPIO_PULL_DOWN },
{GPIO_P07, GPIO_PULL_DOWN },
{GPIO_P17, GPIO_FLOATING },/*32k xtal*/
{GPIO_P23, GPIO_PULL_DOWN },
{GPIO_P24, GPIO_PULL_DOWN },
{GPIO_P25, GPIO_PULL_DOWN },
{GPIO_P26, GPIO_PULL_DOWN },
{GPIO_P27, GPIO_PULL_DOWN },
{GPIO_P31, GPIO_PULL_DOWN },
{GPIO_P32, GPIO_PULL_DOWN },
{GPIO_P33, GPIO_PULL_DOWN },
{GPIO_P34, GPIO_PULL_DOWN },
#endif
};
for(uint8_t i=0; i<sizeof(ioInit)/sizeof(ioinit_cfg_t); i++)
hal_gpio_pull_set(ioInit[i].pin,ioInit[i].type);
DCDC_CONFIG_SETTING(0x0a);
DCDC_REF_CLK_SETTING(1);
DIG_LDO_CURRENT_SETTING(0x01);
hal_pwrmgr_RAM_retention(RET_SRAM0|RET_SRAM1|RET_SRAM2);
//hal_pwrmgr_RAM_retention(RET_SRAM0);
hal_pwrmgr_RAM_retention_set();
hal_pwrmgr_LowCurrentLdo_enable();
}
static void ble_mem_init_config(void)
{
osal_mem_set_heap((osalMemHdr_t*)g_largeHeap, LARGE_HEAP_SIZE);
LL_InitConnectContext(pConnContext,
g_pConnectionBuffer,
BLE_MAX_ALLOW_CONNECTION,
BLE_MAX_ALLOW_PKT_PER_EVENT_TX,
BLE_MAX_ALLOW_PKT_PER_EVENT_RX,
BLE_PKT_VERSION);
#ifdef BLE_SUPPORT_CTE_IQ_SAMPLE
LL_EXT_Init_IQ_pBuff(g_llCteSampleI,g_llCteSampleQ);
#endif
}
static void hal_rfphy_init(void)
{
//============config the txPower
g_rfPhyTxPower = RF_PHY_TX_POWER_N2DBM ;
//============config BLE_PHY TYPE
g_rfPhyPktFmt = PKT_FMT_BLE1M;
//============config RF Frequency Offset
g_rfPhyFreqOffSet =RF_PHY_FREQ_FOFF_00KHZ;
//============config xtal 16M cap
XTAL16M_CAP_SETTING(0x09);
XTAL16M_CURRENT_SETTING(0x01);
hal_rom_boot_init();
NVIC_SetPriority((IRQn_Type)BB_IRQn, IRQ_PRIO_REALTIME);
NVIC_SetPriority((IRQn_Type)TIM1_IRQn, IRQ_PRIO_HIGH); //ll_EVT
NVIC_SetPriority((IRQn_Type)TIM2_IRQn, IRQ_PRIO_HIGH); //OSAL_TICK
NVIC_SetPriority((IRQn_Type)TIM4_IRQn, IRQ_PRIO_HIGH); //LL_EXA_ADV
//ble memory init and config
ble_mem_init_config();
}
static void hal_init(void)
{
hal_low_power_io_init();
clk_init(g_system_clk); //system init
hal_rtc_clock_config((CLK32K_e)g_clk32K_config);
hal_pwrmgr_init();
xflash_Ctx_t cfg =
{
.spif_ref_clk = SYS_CLK_DLL_64M,
.rd_instr = XFRD_FCMD_READ_DUAL
};
hal_spif_cache_init(cfg);
LOG_INIT();
hal_gpio_init();
hal_fs_init(0x1103C000,2);
}
/////////////////////////////////////////////////////////////////////////////////////////////////////////
int main(void)
{
g_system_clk = SYS_CLK_DLL_48M;//SYS_CLK_XTAL_16M;//SYS_CLK_DLL_64M;
g_clk32K_config = CLK_32K_RCOSC;//CLK_32K_XTAL;//CLK_32K_XTAL,CLK_32K_RCOSC
drv_irq_init();
init_config();
extern void ll_patch_multi(void);
ll_patch_multi();
hal_rfphy_init();
hal_init();
// if(hal_gpio_read(P20)==1)
// rf_phy_direct_test();
LOG("SDK Version ID %08x \n",SDK_VER_RELEASE_ID);
LOG("rfClk %d rcClk %d sysClk %d tpCap[%02x %02x]\n",g_rfPhyClkSel,g_clk32K_config,g_system_clk,g_rfPhyTpCal0,g_rfPhyTpCal1);
LOG("sizeof(struct ll_pkt_desc) = %d, buf size = %d\n", sizeof(struct ll_pkt_desc), BLE_CONN_BUF_SIZE);
LOG("sizeof(g_pConnectionBuffer) = %d, sizeof(pConnContext) = %d, sizeof(largeHeap)=%d \n",\
sizeof(g_pConnectionBuffer), sizeof(pConnContext),sizeof(g_largeHeap));
LOG("[REST CAUSE] %d\n ",g_system_reset_cause);
app_main();
}

View File

@ -0,0 +1,15 @@
FUNC void Setup1(void) {
SP = _RDWORD(0x00000000); // 设置堆栈指针
PC = _RDWORD(0x04); // 设置PC指针
_WDWORD(0xE000ED08, 0x00000000); // 设置中断向量表地址
_WDWORD(0x1fff0ff8, 0xdbdbbdbd);
_WDWORD(0x1fff0ffc, 0x1fff4800);
}
LOAD .\Objects\\simpleBleMulti.axf NOCODE
Setup1(); // 再调用Setup函数修改堆栈指针和PC指针 因为SP的值要从目标代码中读取
//g,main // 运行到main函数

View File

@ -0,0 +1,43 @@
; *************************************************************
; *** Scatter-Loading Description File generated by uVision ***
; *************************************************************
LR_IROM1 0x1fff1838 0x0E7C8 { ; load region size_region
ER_IROM1 0x1fff1838 0x0E7C8 { ; load address = execution address
*.o (RESET, +First)
*(InRoot$$Sections)
*.o(_section_standby_code_)
*.o(_section_sram_code_)
.ANY (+RO)
.ANY (+RW +ZI)
}
; ER_IROM2 0x1fff8000 0x08000 { ; load address = execution address
; rf_phy_driver.o(i.rf_phy_dtm*)
; rf_phy_driver.o(i.rf_phy_direct_*)
; }
}
LR_ROM_JT_GC 0x1fff0000 0x00800 {
JUMP_TABLE 0x1fff0000 0x00400 {
.ANY (jump_table_mem_area)
}
GOLBAL_CONFIG 0x1fff0400 0x00400 {
.ANY (global_config_area)
}
}
LR_ROM_XIP 0x11020000 0x020000 {
ER_ROM_XIP 0x11020000 0x01C000 { ; load address = execution address
gatt*.o(+RO)
gattservapp.o(+RO)
l2cap*.o(+RO)
att*.o(+RO)
linkdb.o(+RO)
sm*.o(+RO)
gap*.o(+RO)
; my_printf.o(+RO)
osal_snv.o(+RO)
*.o(_section_xip_code_)
multi*.o(+RO)
}
}

View File

@ -0,0 +1,680 @@
<?xml version="1.0" encoding="UTF-8" standalone="no" ?>
<Project xmlns:xsi="http://www.w3.org/2001/XMLSchema-instance" xsi:noNamespaceSchemaLocation="project_projx.xsd">
<SchemaVersion>2.1</SchemaVersion>
<Header>### uVision Project, (C) Keil Software</Header>
<Targets>
<Target>
<TargetName>Target 1</TargetName>
<ToolsetNumber>0x4</ToolsetNumber>
<ToolsetName>ARM-ADS</ToolsetName>
<pCCUsed>5050106::V5.05 update 1 (build 106)::ARMCC</pCCUsed>
<uAC6>0</uAC6>
<TargetOption>
<TargetCommonOption>
<Device>ARMCM0</Device>
<Vendor>ARM</Vendor>
<PackID>ARM.CMSIS.4.5.0</PackID>
<PackURL>http://www.keil.com/pack/</PackURL>
<Cpu>IRAM(0x20000000,0x20000) IROM(0x00000000,0x40000) CPUTYPE("Cortex-M0") CLOCK(12000000) ESEL ELITTLE</Cpu>
<FlashUtilSpec></FlashUtilSpec>
<StartupFile></StartupFile>
<FlashDriverDll>UL2CM3(-S0 -C0 -P0 -FD20000000 -FC1000 -FN1 -FF0NEW_DEVICE -FS00 -FL040000 -FP0($$Device:ARMCM0$Device\ARM\Flash\NEW_DEVICE.FLM))</FlashDriverDll>
<DeviceId>0</DeviceId>
<RegisterFile>$$Device:ARMCM0$Device\ARM\ARMCM0\Include\ARMCM0.h</RegisterFile>
<MemoryEnv></MemoryEnv>
<Cmp></Cmp>
<Asm></Asm>
<Linker></Linker>
<OHString></OHString>
<InfinionOptionDll></InfinionOptionDll>
<SLE66CMisc></SLE66CMisc>
<SLE66AMisc></SLE66AMisc>
<SLE66LinkerMisc></SLE66LinkerMisc>
<SFDFile>$$Device:ARMCM0$Device\ARM\SVD\ARMCM0.svd</SFDFile>
<bCustSvd>0</bCustSvd>
<UseEnv>0</UseEnv>
<BinPath></BinPath>
<IncludePath></IncludePath>
<LibPath></LibPath>
<RegisterFilePath></RegisterFilePath>
<DBRegisterFilePath></DBRegisterFilePath>
<TargetStatus>
<Error>0</Error>
<ExitCodeStop>0</ExitCodeStop>
<ButtonStop>0</ButtonStop>
<NotGenerated>0</NotGenerated>
<InvalidFlash>1</InvalidFlash>
</TargetStatus>
<OutputDirectory>.\Objects\</OutputDirectory>
<OutputName>simpleBleMulti</OutputName>
<CreateExecutable>1</CreateExecutable>
<CreateLib>0</CreateLib>
<CreateHexFile>0</CreateHexFile>
<DebugInformation>1</DebugInformation>
<BrowseInformation>1</BrowseInformation>
<ListingPath>.\Listings\</ListingPath>
<HexFormatSelection>1</HexFormatSelection>
<Merge32K>0</Merge32K>
<CreateBatchFile>0</CreateBatchFile>
<BeforeCompile>
<RunUserProg1>0</RunUserProg1>
<RunUserProg2>0</RunUserProg2>
<UserProg1Name></UserProg1Name>
<UserProg2Name></UserProg2Name>
<UserProg1Dos16Mode>0</UserProg1Dos16Mode>
<UserProg2Dos16Mode>0</UserProg2Dos16Mode>
<nStopU1X>0</nStopU1X>
<nStopU2X>0</nStopU2X>
</BeforeCompile>
<BeforeMake>
<RunUserProg1>0</RunUserProg1>
<RunUserProg2>0</RunUserProg2>
<UserProg1Name></UserProg1Name>
<UserProg2Name></UserProg2Name>
<UserProg1Dos16Mode>0</UserProg1Dos16Mode>
<UserProg2Dos16Mode>0</UserProg2Dos16Mode>
<nStopB1X>0</nStopB1X>
<nStopB2X>0</nStopB2X>
</BeforeMake>
<AfterMake>
<RunUserProg1>1</RunUserProg1>
<RunUserProg2>1</RunUserProg2>
<UserProg1Name>fromelf.exe --bin -o ./simpleBleMulti.bin ./Objects/simpleBleMulti.axf</UserProg1Name>
<UserProg2Name>fromelf.exe .\Objects\simpleBleMulti.axf --i32combined --output .\bin\simpleBleMulti.hex</UserProg2Name>
<UserProg1Dos16Mode>0</UserProg1Dos16Mode>
<UserProg2Dos16Mode>0</UserProg2Dos16Mode>
<nStopA1X>0</nStopA1X>
<nStopA2X>0</nStopA2X>
</AfterMake>
<SelectedForBatchBuild>0</SelectedForBatchBuild>
<SVCSIdString></SVCSIdString>
</TargetCommonOption>
<CommonProperty>
<UseCPPCompiler>0</UseCPPCompiler>
<RVCTCodeConst>0</RVCTCodeConst>
<RVCTZI>0</RVCTZI>
<RVCTOtherData>0</RVCTOtherData>
<ModuleSelection>0</ModuleSelection>
<IncludeInBuild>1</IncludeInBuild>
<AlwaysBuild>0</AlwaysBuild>
<GenerateAssemblyFile>0</GenerateAssemblyFile>
<AssembleAssemblyFile>0</AssembleAssemblyFile>
<PublicsOnly>0</PublicsOnly>
<StopOnExitCode>3</StopOnExitCode>
<CustomArgument></CustomArgument>
<IncludeLibraryModules></IncludeLibraryModules>
<ComprImg>1</ComprImg>
</CommonProperty>
<DllOption>
<SimDllName>SARMCM3.DLL</SimDllName>
<SimDllArguments> </SimDllArguments>
<SimDlgDll>DARMCM1.DLL</SimDlgDll>
<SimDlgDllArguments>-pCM0</SimDlgDllArguments>
<TargetDllName>SARMCM3.DLL</TargetDllName>
<TargetDllArguments> </TargetDllArguments>
<TargetDlgDll>TARMCM1.DLL</TargetDlgDll>
<TargetDlgDllArguments>-pCM0</TargetDlgDllArguments>
</DllOption>
<DebugOption>
<OPTHX>
<HexSelection>1</HexSelection>
<HexRangeLowAddress>0</HexRangeLowAddress>
<HexRangeHighAddress>0</HexRangeHighAddress>
<HexOffset>0</HexOffset>
<Oh166RecLen>16</Oh166RecLen>
</OPTHX>
</DebugOption>
<Utilities>
<Flash1>
<UseTargetDll>1</UseTargetDll>
<UseExternalTool>1</UseExternalTool>
<RunIndependent>0</RunIndependent>
<UpdateFlashBeforeDebugging>1</UpdateFlashBeforeDebugging>
<Capability>1</Capability>
<DriverSelection>4096</DriverSelection>
</Flash1>
<bUseTDR>1</bUseTDR>
<Flash2>BIN\UL2CM3.DLL</Flash2>
<Flash3>"" ()</Flash3>
<Flash4>.\ram.ini</Flash4>
<pFcarmOut></pFcarmOut>
<pFcarmGrp></pFcarmGrp>
<pFcArmRoot></pFcArmRoot>
<FcArmLst>0</FcArmLst>
</Utilities>
<TargetArmAds>
<ArmAdsMisc>
<GenerateListings>0</GenerateListings>
<asHll>1</asHll>
<asAsm>1</asAsm>
<asMacX>1</asMacX>
<asSyms>1</asSyms>
<asFals>1</asFals>
<asDbgD>1</asDbgD>
<asForm>1</asForm>
<ldLst>0</ldLst>
<ldmm>1</ldmm>
<ldXref>1</ldXref>
<BigEnd>0</BigEnd>
<AdsALst>1</AdsALst>
<AdsACrf>1</AdsACrf>
<AdsANop>0</AdsANop>
<AdsANot>0</AdsANot>
<AdsLLst>1</AdsLLst>
<AdsLmap>1</AdsLmap>
<AdsLcgr>1</AdsLcgr>
<AdsLsym>1</AdsLsym>
<AdsLszi>1</AdsLszi>
<AdsLtoi>1</AdsLtoi>
<AdsLsun>1</AdsLsun>
<AdsLven>1</AdsLven>
<AdsLsxf>1</AdsLsxf>
<RvctClst>0</RvctClst>
<GenPPlst>0</GenPPlst>
<AdsCpuType>"Cortex-M0"</AdsCpuType>
<RvctDeviceName></RvctDeviceName>
<mOS>0</mOS>
<uocRom>0</uocRom>
<uocRam>0</uocRam>
<hadIROM>1</hadIROM>
<hadIRAM>1</hadIRAM>
<hadXRAM>0</hadXRAM>
<uocXRam>0</uocXRam>
<RvdsVP>0</RvdsVP>
<hadIRAM2>0</hadIRAM2>
<hadIROM2>0</hadIROM2>
<StupSel>8</StupSel>
<useUlib>1</useUlib>
<EndSel>1</EndSel>
<uLtcg>0</uLtcg>
<nSecure>0</nSecure>
<RoSelD>3</RoSelD>
<RwSelD>3</RwSelD>
<CodeSel>0</CodeSel>
<OptFeed>0</OptFeed>
<NoZi1>0</NoZi1>
<NoZi2>0</NoZi2>
<NoZi3>0</NoZi3>
<NoZi4>0</NoZi4>
<NoZi5>0</NoZi5>
<Ro1Chk>0</Ro1Chk>
<Ro2Chk>0</Ro2Chk>
<Ro3Chk>0</Ro3Chk>
<Ir1Chk>0</Ir1Chk>
<Ir2Chk>0</Ir2Chk>
<Ra1Chk>0</Ra1Chk>
<Ra2Chk>0</Ra2Chk>
<Ra3Chk>0</Ra3Chk>
<Im1Chk>0</Im1Chk>
<Im2Chk>0</Im2Chk>
<OnChipMemories>
<Ocm1>
<Type>0</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</Ocm1>
<Ocm2>
<Type>0</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</Ocm2>
<Ocm3>
<Type>0</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</Ocm3>
<Ocm4>
<Type>0</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</Ocm4>
<Ocm5>
<Type>0</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</Ocm5>
<Ocm6>
<Type>0</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</Ocm6>
<IRAM>
<Type>0</Type>
<StartAddress>0x20000000</StartAddress>
<Size>0x20000</Size>
</IRAM>
<IROM>
<Type>1</Type>
<StartAddress>0x0</StartAddress>
<Size>0x40000</Size>
</IROM>
<XRAM>
<Type>0</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</XRAM>
<OCR_RVCT1>
<Type>1</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</OCR_RVCT1>
<OCR_RVCT2>
<Type>1</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</OCR_RVCT2>
<OCR_RVCT3>
<Type>1</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</OCR_RVCT3>
<OCR_RVCT4>
<Type>1</Type>
<StartAddress>0x20000000</StartAddress>
<Size>0x400</Size>
</OCR_RVCT4>
<OCR_RVCT5>
<Type>1</Type>
<StartAddress>0x1fff8000</StartAddress>
<Size>0x1f40</Size>
</OCR_RVCT5>
<OCR_RVCT6>
<Type>0</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</OCR_RVCT6>
<OCR_RVCT7>
<Type>0</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</OCR_RVCT7>
<OCR_RVCT8>
<Type>0</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</OCR_RVCT8>
<OCR_RVCT9>
<Type>0</Type>
<StartAddress>0x1fff6000</StartAddress>
<Size>0x2000</Size>
</OCR_RVCT9>
<OCR_RVCT10>
<Type>0</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</OCR_RVCT10>
</OnChipMemories>
<RvctStartVector></RvctStartVector>
</ArmAdsMisc>
<Cads>
<interw>1</interw>
<Optim>3</Optim>
<oTime>0</oTime>
<SplitLS>0</SplitLS>
<OneElfS>1</OneElfS>
<Strict>0</Strict>
<EnumInt>0</EnumInt>
<PlainCh>0</PlainCh>
<Ropi>0</Ropi>
<Rwpi>0</Rwpi>
<wLevel>2</wLevel>
<uThumb>0</uThumb>
<uSurpInc>0</uSurpInc>
<uC99>1</uC99>
<uGnu>0</uGnu>
<useXO>0</useXO>
<v6Lang>1</v6Lang>
<v6LangP>1</v6LangP>
<vShortEn>1</vShortEn>
<vShortWch>1</vShortWch>
<v6Lto>0</v6Lto>
<v6WtE>0</v6WtE>
<v6Rtti>0</v6Rtti>
<VariousControls>
<MiscControls>-DADV_NCONN_CFG=0x01 -DADV_CONN_CFG=0x02 -DSCAN_CFG=0x04 -DINIT_CFG=0x08 -DBROADCASTER_CFG=0x01 -DOBSERVER_CFG=0x02 -DPERIPHERAL_CFG=0x04 -DCENTRAL_CFG=0x08 -DHOST_CONFIG=0xc</MiscControls>
<Define>OSALMEM_METRICS=0 DBG_ROM_MAIN=0 MTU_SIZE=247 DEBUG_INFO=1 _BUILD_FOR_DTM_=0 ENABLE_LOG_ROM_=0 HOST_CONFIG=0xC HCI_TL_NONE=1 OSAL_CBTIMER_NUM_TASKS=1 CFG_CP PHY_MCU_TYPE=MCU_BUMBEE_M0 CFG_SLEEP_MODE=PWR_MODE_NO_SLEEP MULTI_DEBUG MAX_NUM_LL_CONN=5</Define>
<Undefine></Undefine>
<IncludePath>..\..\..\components\inc;..\..\..\components\ble\host;..\..\..\components\ble\hci;..\..\..\components\ble\controller;..\..\..\components\ble\include;..\..\..\components\osal\include;..\..\..\components\profiles\Roles;..\..\..\components\driver\uart;..\..\..\components\profiles\DevInfo;..\..\..\components\profiles\ota;..\..\..\components\profiles\ota_app;..\..\..\components\profiles\SimpleProfile;..\..\..\components\driver\log;..\..\..\components\driver\pwrmgr;..\..\..\components\driver\uart;..\..\..\components\driver\clock;..\..\..\components\driver\gpio;..\..\..\components\driver\adc;..\..\..\components\driver\kscan;..\..\..\components\driver\flash;..\..\..\components\driver\spi;..\..\..\components\driver\i2c;..\..\..\components\driver\i2s;..\..\..\components\driver\timer;..\..\..\components\driver\watchdog;..\..\..\components\driver\kscan;..\..\..\components\libraries\crc16;..\..\..\components\arch\cm0;..\..\..\lib;..\..\..\misc;.\source\multi_role;..\..\..\components\profiles\multiRole;..\..\..\components\libraries\fs</IncludePath>
</VariousControls>
</Cads>
<Aads>
<interw>1</interw>
<Ropi>0</Ropi>
<Rwpi>0</Rwpi>
<thumb>0</thumb>
<SplitLS>0</SplitLS>
<SwStkChk>0</SwStkChk>
<NoWarn>0</NoWarn>
<uSurpInc>0</uSurpInc>
<useXO>0</useXO>
<uClangAs>0</uClangAs>
<VariousControls>
<MiscControls></MiscControls>
<Define></Define>
<Undefine></Undefine>
<IncludePath></IncludePath>
</VariousControls>
</Aads>
<LDads>
<umfTarg>0</umfTarg>
<Ropi>0</Ropi>
<Rwpi>0</Rwpi>
<noStLib>0</noStLib>
<RepFail>0</RepFail>
<useFile>0</useFile>
<TextAddressRange>0</TextAddressRange>
<DataAddressRange>0</DataAddressRange>
<pXoBase></pXoBase>
<ScatterFile>.\scatter_load.sct</ScatterFile>
<IncludeLibs></IncludeLibs>
<IncludeLibsPath></IncludeLibsPath>
<Misc>..\..\..\misc\bb_rom_sym_m0.txt --keep=jump_table_base --keep=global_config</Misc>
<LinkerInputFile></LinkerInputFile>
<DisabledWarnings></DisabledWarnings>
</LDads>
</TargetArmAds>
</TargetOption>
<Groups>
<Group>
<GroupName>arch</GroupName>
<Files>
<File>
<FileName>main.c</FileName>
<FileType>1</FileType>
<FilePath>.\main.c</FilePath>
</File>
</Files>
</Group>
<Group>
<GroupName>driver</GroupName>
<Files>
<File>
<FileName>clock.c</FileName>
<FileType>1</FileType>
<FilePath>..\..\..\components\driver\clock\clock.c</FilePath>
</File>
<File>
<FileName>uart.c</FileName>
<FileType>1</FileType>
<FilePath>..\..\..\components\driver\uart\uart.c</FilePath>
</File>
<File>
<FileName>gpio.c</FileName>
<FileType>1</FileType>
<FilePath>..\..\..\components\driver\gpio\gpio.c</FilePath>
</File>
<File>
<FileName>timer.c</FileName>
<FileType>1</FileType>
<FilePath>..\..\..\components\driver\timer\timer.c</FilePath>
</File>
<File>
<FileName>pwrmgr.c</FileName>
<FileType>1</FileType>
<FilePath>..\..\..\components\driver\pwrmgr\pwrmgr.c</FilePath>
</File>
<File>
<FileName>my_printf.c</FileName>
<FileType>1</FileType>
<FilePath>..\..\..\components\driver\log\my_printf.c</FilePath>
</File>
<File>
<FileName>pwm.c</FileName>
<FileType>1</FileType>
<FilePath>..\..\..\components\driver\pwm\pwm.c</FilePath>
</File>
<File>
<FileName>flash.c</FileName>
<FileType>1</FileType>
<FilePath>..\..\..\components\driver\flash\flash.c</FilePath>
</File>
<File>
<FileName>fs.c</FileName>
<FileType>1</FileType>
<FilePath>..\..\..\components\libraries\fs\fs.c</FilePath>
</File>
<File>
<FileName>osal_snv.c</FileName>
<FileType>1</FileType>
<FilePath>..\..\..\components\osal\snv\osal_snv.c</FilePath>
</File>
</Files>
</Group>
<Group>
<GroupName>profile</GroupName>
<Files>
<File>
<FileName>multi.c</FileName>
<FileType>1</FileType>
<FilePath>..\..\..\components\profiles\multiRole\multi.c</FilePath>
</File>
<File>
<FileName>gap.c</FileName>
<FileType>1</FileType>
<FilePath>..\..\..\components\profiles\Roles\gap.c</FilePath>
</File>
<File>
<FileName>gapbondmgr.c</FileName>
<FileType>1</FileType>
<FilePath>..\..\..\components\profiles\Roles\gapbondmgr.c</FilePath>
</File>
<File>
<FileName>gapgattserver.c</FileName>
<FileType>1</FileType>
<FilePath>..\..\..\components\profiles\Roles\gapgattserver.c</FilePath>
</File>
<File>
<FileName>devinfoservice.c</FileName>
<FileType>1</FileType>
<FilePath>..\..\..\components\profiles\DevInfo\devinfoservice.c</FilePath>
</File>
<File>
<FileName>gattservapp.c</FileName>
<FileType>1</FileType>
<FilePath>..\..\..\components\profiles\GATT\gattservapp.c</FilePath>
</File>
<File>
<FileName>multiRoleProfile.c</FileName>
<FileType>1</FileType>
<FilePath>..\..\..\components\profiles\multiRole\multiRoleProfile.c</FilePath>
</File>
</Files>
</Group>
<Group>
<GroupName>jump</GroupName>
<Files>
<File>
<FileName>jump_table.c</FileName>
<FileType>1</FileType>
<FilePath>..\..\..\misc\jump_table.c</FilePath>
</File>
</Files>
</Group>
<Group>
<GroupName>app</GroupName>
<Files>
<File>
<FileName>multi_role.c</FileName>
<FileType>1</FileType>
<FilePath>.\source\multi_role\multi_role.c</FilePath>
</File>
<File>
<FileName>multi_role_Main.c</FileName>
<FileType>1</FileType>
<FilePath>.\source\multi_role\multi_role_Main.c</FilePath>
</File>
<File>
<FileName>OSAL_multi_role.c</FileName>
<FileType>1</FileType>
<FilePath>.\source\multi_role\OSAL_multi_role.c</FilePath>
</File>
<File>
<FileName>multi_timer.c</FileName>
<FileType>1</FileType>
<FilePath>.\source\multi_role\multi_timer.c</FilePath>
</File>
<File>
<FileName>multi_schedule.c</FileName>
<FileType>1</FileType>
<FilePath>.\source\multi_role\multi_schedule.c</FilePath>
</File>
</Files>
</Group>
<Group>
<GroupName>lib</GroupName>
<Files>
<File>
<FileName>rf.lib</FileName>
<FileType>4</FileType>
<FilePath>..\..\..\lib\rf.lib</FilePath>
</File>
<File>
<FileName>ble_host_multi5.lib</FileName>
<FileType>4</FileType>
<FilePath>..\..\..\lib\ble_host_multi5.lib</FilePath>
</File>
</Files>
</Group>
<Group>
<GroupName>::CMSIS</GroupName>
</Group>
<Group>
<GroupName>::Device</GroupName>
<GroupOption>
<CommonProperty>
<UseCPPCompiler>0</UseCPPCompiler>
<RVCTCodeConst>0</RVCTCodeConst>
<RVCTZI>0</RVCTZI>
<RVCTOtherData>0</RVCTOtherData>
<ModuleSelection>0</ModuleSelection>
<IncludeInBuild>1</IncludeInBuild>
<AlwaysBuild>2</AlwaysBuild>
<GenerateAssemblyFile>2</GenerateAssemblyFile>
<AssembleAssemblyFile>2</AssembleAssemblyFile>
<PublicsOnly>2</PublicsOnly>
<StopOnExitCode>11</StopOnExitCode>
<CustomArgument></CustomArgument>
<IncludeLibraryModules></IncludeLibraryModules>
<ComprImg>1</ComprImg>
</CommonProperty>
<GroupArmAds>
<Cads>
<interw>2</interw>
<Optim>0</Optim>
<oTime>2</oTime>
<SplitLS>2</SplitLS>
<OneElfS>2</OneElfS>
<Strict>2</Strict>
<EnumInt>2</EnumInt>
<PlainCh>2</PlainCh>
<Ropi>2</Ropi>
<Rwpi>2</Rwpi>
<wLevel>2</wLevel>
<uThumb>2</uThumb>
<uSurpInc>2</uSurpInc>
<uC99>2</uC99>
<uGnu>2</uGnu>
<useXO>2</useXO>
<v6Lang>0</v6Lang>
<v6LangP>0</v6LangP>
<vShortEn>2</vShortEn>
<vShortWch>2</vShortWch>
<v6Lto>2</v6Lto>
<v6WtE>2</v6WtE>
<v6Rtti>2</v6Rtti>
<VariousControls>
<MiscControls></MiscControls>
<Define></Define>
<Undefine></Undefine>
<IncludePath></IncludePath>
</VariousControls>
</Cads>
<Aads>
<interw>2</interw>
<Ropi>2</Ropi>
<Rwpi>2</Rwpi>
<thumb>2</thumb>
<SplitLS>2</SplitLS>
<SwStkChk>2</SwStkChk>
<NoWarn>2</NoWarn>
<uSurpInc>2</uSurpInc>
<useXO>2</useXO>
<uClangAs>2</uClangAs>
<VariousControls>
<MiscControls></MiscControls>
<Define></Define>
<Undefine></Undefine>
<IncludePath></IncludePath>
</VariousControls>
</Aads>
</GroupArmAds>
</GroupOption>
</Group>
</Groups>
</Target>
</Targets>
<RTE>
<apis/>
<components>
<component Cclass="CMSIS" Cgroup="CORE" Cvendor="ARM" Cversion="4.3.0" condition="Cortex-M Device">
<package name="CMSIS" schemaVersion="1.3" url="http://www.keil.com/pack/" vendor="ARM" version="4.5.0"/>
<targetInfos>
<targetInfo name="Target 1"/>
</targetInfos>
</component>
<component Cclass="Device" Cgroup="Startup" Cvendor="ARM" Cversion="1.0.1" condition="ARMCM0 CMSIS">
<package name="CMSIS" schemaVersion="1.3" url="http://www.keil.com/pack/" vendor="ARM" version="4.5.0"/>
<targetInfos>
<targetInfo name="Target 1"/>
</targetInfos>
</component>
</components>
<files>
<file attr="config" category="sourceAsm" condition="ARMCC" name="Device\ARM\ARMCM0\Source\ARM\startup_ARMCM0.s" version="1.0.0">
<instance index="0">RTE\Device\ARMCM0\startup_ARMCM0.s</instance>
<component Cclass="Device" Cgroup="Startup" Cvendor="ARM" Cversion="1.0.1" condition="ARMCM0 CMSIS"/>
<package name="CMSIS" schemaVersion="1.3" url="http://www.keil.com/pack/" vendor="ARM" version="4.5.0"/>
<targetInfos>
<targetInfo name="Target 1"/>
</targetInfos>
</file>
<file attr="config" category="sourceC" name="Device\ARM\ARMCM0\Source\system_ARMCM0.c" version="1.0.0">
<instance index="0">RTE\Device\ARMCM0\system_ARMCM0.c</instance>
<component Cclass="Device" Cgroup="Startup" Cvendor="ARM" Cversion="1.0.1" condition="ARMCM0 CMSIS"/>
<package name="CMSIS" schemaVersion="1.3" url="http://www.keil.com/pack/" vendor="ARM" version="4.5.0"/>
<targetInfos>
<targetInfo name="Target 1"/>
</targetInfos>
</file>
<file attr="config" category="sourceAsm" condition="ARMCC" name="Device\ARM\ARMCM4\Source\ARM\startup_ARMCM4.s" version="1.0.0">
<instance index="0" removed="1">RTE\Device\ARMCM4\startup_ARMCM4.s</instance>
<component Cclass="Device" Cgroup="Startup" Cvendor="ARM" Cversion="1.0.1" condition="ARMCM4 CMSIS"/>
<package name="CMSIS" schemaVersion="1.3" url="http://www.keil.com/pack/" vendor="ARM" version="4.5.0"/>
<targetInfos/>
</file>
<file attr="config" category="sourceC" name="Device\ARM\ARMCM4\Source\system_ARMCM4.c" version="1.0.0">
<instance index="0" removed="1">RTE\Device\ARMCM4\system_ARMCM4.c</instance>
<component Cclass="Device" Cgroup="Startup" Cvendor="ARM" Cversion="1.0.1" condition="ARMCM4 CMSIS"/>
<package name="CMSIS" schemaVersion="1.3" url="http://www.keil.com/pack/" vendor="ARM" version="4.5.0"/>
<targetInfos/>
</file>
<file attr="config" category="sourceAsm" condition="ARMCC" name="Device\ARM\ARMCM4\Source\ARM\startup_ARMCM4.s" version="1.0.0">
<instance index="0" removed="1">RTE\Device\ARMCM4_FP\startup_ARMCM4.s</instance>
<component Cclass="Device" Cgroup="Startup" Cvendor="ARM" Cversion="1.0.1" condition="ARMCM4 CMSIS"/>
<package name="CMSIS" schemaVersion="1.3" url="http://www.keil.com/pack/" vendor="ARM" version="4.5.0"/>
<targetInfos/>
</file>
<file attr="config" category="sourceC" name="Device\ARM\ARMCM4\Source\system_ARMCM4.c" version="1.0.0">
<instance index="0" removed="1">RTE\Device\ARMCM4_FP\system_ARMCM4.c</instance>
<component Cclass="Device" Cgroup="Startup" Cvendor="ARM" Cversion="1.0.1" condition="ARMCM4 CMSIS"/>
<package name="CMSIS" schemaVersion="1.3" url="http://www.keil.com/pack/" vendor="ARM" version="4.5.0"/>
<targetInfos/>
</file>
</files>
</RTE>
</Project>

View File

@ -0,0 +1,116 @@
/**************************************************************************************************
Filename: OSAL_simpleBLECentral.c
Revised: $Date: 2020-03-03 15:46:41 -0800 (Thu, 03 Mar 2011) $
Revision: $Revision: 12 $
Description: OSAL task initalization for Simple BLE Central app.
**************************************************************************************************/
/**************************************************************************************************
INCLUDES
**************************************************************************************************/
#include "OSAL.h"
#include "OSAL_Tasks.h"
/* LL */
#include "ll.h"
/* HCI */
#include "hci_tl.h"
#if defined ( OSAL_CBTIMER_NUM_TASKS )
#include "osal_cbTimer.h"
#endif
/* L2CAP */
#include "l2cap.h"
/* gap */
#include "gap.h"
#include "gapgattserver.h"
#include "gapbondmgr.h"
/* GATT */
#include "gatt.h"
#include "gattservapp.h"
/* Profiles */
#include "multi.h"
/* Application */
#include "multi_role.h"
/*********************************************************************
GLOBAL VARIABLES
*/
// The order in this table must be identical to the task initialization calls below in osalInitTask.
const pTaskEventHandlerFn tasksArr[] =
{
LL_ProcessEvent,
HCI_ProcessEvent,
#if defined ( OSAL_CBTIMER_NUM_TASKS )
OSAL_CBTIMER_PROCESS_EVENT( osal_CbTimerProcessEvent ), // task 3
#endif
L2CAP_ProcessEvent,
SM_ProcessEvent,
GAP_ProcessEvent,
GATT_ProcessEvent,
GAPBondMgr_ProcessEvent,
GATTServApp_ProcessEvent,
GAPMultiRole_ProcessEvent,
multiRoleApp_ProcessEvent
};
const uint8 tasksCnt = sizeof( tasksArr ) / sizeof( tasksArr[0] );
uint16* tasksEvents;
/*********************************************************************
FUNCTIONS
*********************************************************************/
/*********************************************************************
@fn osalInitTasks
@brief This function invokes the initialization function for each task.
@param void
@return none
*/
void osalInitTasks( void )
{
uint8 taskID = 0;
tasksEvents = (uint16*)osal_mem_alloc( sizeof( uint16 ) * tasksCnt);
osal_memset( tasksEvents, 0, (sizeof( uint16 ) * tasksCnt));
/* LL Task */
LL_Init( taskID++ );
/* HCI Task */
HCI_Init( taskID++ );
#if defined ( OSAL_CBTIMER_NUM_TASKS )
/* Callback Timer Tasks */
osal_CbTimerInit( taskID );
taskID += OSAL_CBTIMER_NUM_TASKS;
#endif
/* L2CAP Task */
L2CAP_Init( taskID++ );
/* SM Task */
SM_Init( taskID++ );
/* GAP Task */
GAP_Init( taskID++ );
/* GATT Task */
GATT_Init( taskID++ );
/* Profiles */
GAPBondMgr_Init( taskID++ );
GATTServApp_Init( taskID++ );
GAPMultiRole_Init( taskID++ );
/* Application */
multiRoleApp_Init( taskID );
}
/*********************************************************************
*********************************************************************/

View File

@ -0,0 +1,749 @@
/**************************************************************************************************
Filename: multi_role.c
Revised:
Revision:
Description: This file contains the Simple BLE Central sample application
for use with the Bluetooth Low Energy Protocol Stack.
**************************************************************************************************/
/*
TODO:list
1.multiple host lib
(1).single master host lib -- maximum connection number equal to one ( 2K SRAM )
(2).multi-role master host lib,maximum 8 commection supported
(3).simultaneously 8 SMP
2.multi role scheduler optimize(2's pointer)
3.scan and initiating default parameter : eg scan/initiating whitelist parameter and so on.
4.multi role active scan , no scan response data report
5.multi role project system clock 16MHz not supported
6.device in whitelist which has been bonded, automatically link after reset(shall detected this in scan done event call back function ).
7.what's high duty cycle in link mode
8.multi role as master's action after establish sussess(first connection and re-connection should support different action--can use user flash area)
*/
/*********************************************************************
INCLUDES
*/
#include <stdio.h>
#include <string.h>
#include "bcomdef.h"
#include "OSAL.h"
#include "OSAL_PwrMgr.h"
#include "OSAL_bufmgr.h"
#include "gatt.h"
#include "ll.h"
#include "hci.h"
#include "gap.h"
#include "gapgattserver.h"
#include "gattservapp.h"
#include "multi.h"
#include "gapbondmgr.h"
#include "ll_common.h"
#include "log.h"
#include "hci.h"
#include "error.h"
#include "gpio.h"
#include "pwrmgr.h"
#include "devinfoservice.h"
#include "gatt_profile_uuid.h"
#include "multiRoleProfile.h"
#include "multi_role.h"
#include "multi_schedule.h"
/*********************************************************************
MACROS
*/
/*********************************************************************
CONSTANTS
*/
// unit 1.25ms
#define DEFAULT_CONN_MIN_INTV 40
// Whether to enable automatic parameter update request when a connection is formed
#define DEFAULT_ENABLE_UPDATE_REQUEST TRUE
// Connection Pause Peripheral time value (in 1000ms)
#define DEFAULT_CONN_PAUSE_PERIPHERAL 1
#define DEFAULT_ADV_INTV 160
#define DEFAULT_SCAN_RSP_RSSI_MIN -70
#define DEFAULE_SCAN_MAX_NUM 5
// Scan duration in ms
#define DEFAULT_SCAN_DURATION 1000
// Slave latency to use if automatic parameter update request is enabled
#define DEFAULT_UPDATE_SLAVE_LATENCY 0
// Supervision timeout value (units of 10ms) if automatic parameter update request is enabled
#define DEFAULT_UPDATE_CONN_TIMEOUT 200
// Discovey mode (limited, general, all)
#define DEFAULT_DISCOVERY_MODE DEVDISC_MODE_ALL
// TRUE to use active scan
#define DEFAULT_DISCOVERY_ACTIVE_SCAN TRUE
// TRUE to use white list during discovery
#define DEFAULT_DISCOVERY_WHITE_LIST FALSE
// TRUE to use high scan duty cycle when creating link
#define DEFAULT_LINK_HIGH_DUTY_CYCLE FALSE
// TRUE to use white list when creating link
#define DEFAULT_LINK_WHITE_LIST FALSE
#define DEFAULT_ACTION_AFTER_LINK ( GAPMULTI_CENTRAL_MTU_EXCHANGE | GAPMULTI_CENTRAL_DLE_EXCHANGE | GAPMULTI_CENTRAL_SDP )
// Default passcode
#define DEFAULT_PASSCODE 123456
// Default GAP pairing mode
#define DEFAULT_PAIRING_MODE GAPBOND_PAIRING_MODE_NO_PAIRING /// GAPBOND_PAIRING_MODE_INITIATE
// Default MITM mode (TRUE to require passcode or OOB when pairing)
#define DEFAULT_MITM_MODE FALSE
// Default bonding mode, TRUE to bond
#define DEFAULT_BONDING_MODE FALSE /// TRUE
// Default GAP bonding I/O capabilities
#define DEFAULT_IO_CAPABILITIES GAPBOND_IO_CAP_DISPLAY_ONLY
// Default service discovery timer delay in ms
#define DEFAULT_SVC_DISCOVERY_DELAY 1000
// TRUE to filter discovery results on desired service UUID
#define DEFAULT_DEV_DISC_BY_SVC_UUID TRUE
#define INVALID_STATUS 0xFFFF
#define DEFAULT_ENABLE_HID FALSE
/*********************************************************************
GLOBAL VARIABLES
*/
uint16 MR_WakeupCnt = 0;
/*********************************************************************
EXTERNAL VARIABLES
*/
/*********************************************************************
EXTERNAL FUNCTIONS
*/
/*********************************************************************
LOCAL VARIABLES
*/
//static uint16 multiRole_wrChar_handle = 0;
// Task ID for internal task/event processing
uint8 multiRole_TaskId;
//
//MultiRoleApp_Link_t g_MRLink[MAX_CONNECTION_NUM];
/*********************************************************************
LOCAL FUNCTIONS
*/
#if ( MAX_CONNECTION_SLAVE_NUM > 0 )
static void multiRoleAPP_AdvInit(void);
static void multiRole_setup_adv_scanRspData(uint8 idx);
static void multiRoleProfileChangeCB( uint16 connHandle,uint16 paramID, uint16 len );
#endif
#if( MAX_CONNECTION_MASTER_NUM > 0)
static void multiRoleAPP_ScIn_Init(void);
static void multiRoleSDPCB(void* msg );
static void multiRoleNotifyCB(uint16 connHandle,uint16 len,uint8* data );
static void multiRoleEachScanCB( gapDeviceInfoEvent_t* pPkt );
static void multiRoleScanDoneCB( GAPMultiRolScanner_t* node );
#endif
static void multiRoleAPP_ComInit(void);
static void multiRoleEstablishCB( uint8 status, uint16 connHandle,GAPMultiRole_State_t role,uint8 perIdx,uint8* addr );
static void multiRoleTerminateCB( uint16 connHandle,GAPMultiRole_State_t role,uint8 perIdx,uint8 reason );
static void multiRoleApp_ProcessOSALMsg( osal_event_hdr_t* pMsg );
static void multiRoleAppProcessGATTMsg( gattMsgEvent_t* pMsg );
/*********************************************************************
LOCAL VARIABLES
*/
// TRUE if boot mouse enabled
uint8 hidBootMouseEnabled = FALSE;
/*********************************************************************
PROFILE CALLBACKS
*/
// GAP Role Callbacks
static const gapMultiRolesCBs_t multiRoleCB =
{
#if( MAX_CONNECTION_MASTER_NUM > 0)
multiRoleEachScanCB,
multiRoleScanDoneCB,
multiRoleSDPCB,
multiRoleNotifyCB,
#endif
multiRoleEstablishCB,
multiRoleTerminateCB,
};
#if ( MAX_CONNECTION_SLAVE_NUM > 0 )
// GATT Profile Callbacks
static multiProfileCBs_t multiRole_ProfileCBs =
{
multiRoleProfileChangeCB, // Charactersitic value change callback
// #else
};
#endif
/*********************************************************************
PUBLIC FUNCTIONS
*/
/*********************************************************************
@fn SimpleBLECentral_Init
@brief Initialization function for the Simple BLE Central App Task.
This is called during initialization and should contain
any application specific initialization (ie. hardware
initialization/setup, table initialization, power up
notification).
@param task_id - the ID assigned by OSAL. This ID should be
used to send messages and set timers.
@return none
*/
void multiRoleApp_Init( uint8 task_id )
{
multiRole_TaskId = task_id;
uint8 roleProfile = 0;
#if ( MAX_CONNECTION_SLAVE_NUM > 0 )
{
roleProfile |= GAP_PROFILE_PERIPHERAL;
multiRoleAPP_AdvInit();
if( SCH_SUCCESS == muliSchedule_config( MULTI_SCH_ADV_MODE, 0x31 ) )
{
LOG("Multi Role advertising scheduler success \n");
}
// Initialize GATT attributes
GGS_AddService( GATT_ALL_SERVICES ); // GAP
GATTServApp_AddService( GATT_ALL_SERVICES ); // GATT attributes
MultiProfile_AddService( GATT_ALL_SERVICES ); // Simple GATT Profile
MultiProfile_RegisterAppCBs(&multiRole_ProfileCBs);
}
#endif
#if ( MAX_CONNECTION_MASTER_NUM > 0 )
{
roleProfile |= GAP_PROFILE_CENTRAL;
multiRoleAPP_ScIn_Init();
LOG("Start muliSchedule_config \n");
uint8 ret = muliSchedule_config( MULTI_SCH_SCAN_MODE, 0x01 );
if( SCH_SUCCESS == ret )
{
LOG("Multi Role scanning scheduler success \n");
}
else
{
LOG("Multi Role scanning scheduler failure %d\n",ret);
}
}
#endif
GAPMultiRole_SetParameter( GAPMULTIROLE_PROFILEROLE,sizeof(uint8),&roleProfile);
multiRoleAPP_ComInit();
#if( DEFAULT_PAIRING_MODE > GAPBOND_PAIRING_MODE_NO_PAIRING)
// Setup the GAP Bond Manager
{
uint32 passkey = DEFAULT_PASSCODE;
uint8 pairMode = GAPBOND_PAIRING_MODE_INITIATE; // GAPBOND_PAIRING_MODE_NO_PAIRING
uint8 mitm = DEFAULT_MITM_MODE;
uint8 ioCap = DEFAULT_IO_CAPABILITIES;
uint8 bonding = DEFAULT_BONDING_MODE;
uint8 syncWL = TRUE;
GAPBondMgr_SetParameter( GAPBOND_DEFAULT_PASSCODE, sizeof( uint32 ), &passkey );
GAPBondMgr_SetParameter( GAPBOND_PAIRING_MODE, sizeof( uint8 ), &pairMode );
GAPBondMgr_SetParameter( GAPBOND_MITM_PROTECTION, sizeof( uint8 ), &mitm );
GAPBondMgr_SetParameter( GAPBOND_IO_CAPABILITIES, sizeof( uint8 ), &ioCap );
GAPBondMgr_SetParameter( GAPBOND_BONDING_ENABLED, sizeof( uint8 ), &bonding );
// If a bond is created, the HID Device should write the address of the
// HID Host in the HID Device controller's white list and set the HID
// Device controller's advertising filter policy to 'process scan and
// connection requests only from devices in the White List'.
GAPBondMgr_SetParameter( GAPBOND_AUTO_SYNC_WL, sizeof( uint8 ), &syncWL );
}
#endif
osal_set_event( multiRole_TaskId, START_DEVICE_EVT );
}
/*********************************************************************
@fn SimpleBLECentral_ProcessEvent
@brief Simple BLE Central Application Task event processor. This function
is called to process all events for the task. Events
include timers, messages and any other user defined events.
@param task_id - The OSAL assigned task ID.
@param events - events to process. This is a bit map and can
contain more than one event.
@return events not processed
*/
uint16 multiRoleApp_ProcessEvent( uint8 task_id, uint16 events )
{
VOID task_id; // OSAL required parameter that isn't used in this function
uint8 numConns;
if ( events & SYS_EVENT_MSG )
{
uint8* pMsg;
if ( (pMsg = osal_msg_receive( multiRole_TaskId )) != NULL )
{
multiRoleApp_ProcessOSALMsg( (osal_event_hdr_t*)pMsg );
// Release the OSAL message
VOID osal_msg_deallocate( pMsg );
}
// return unprocessed events
return (events ^ SYS_EVENT_MSG);
}
if ( events & START_DEVICE_EVT )
{
// Start the Device
GAPMultiRole_StartDevice( (gapMultiRolesCBs_t*)&multiRoleCB, &numConns);
if( numConns > MAX_NUM_LL_CONN )
LOG("MAX Connection NUM configuration error\n");
else
LOG("MAX available connection %d\n",numConns);
return ( events ^ START_DEVICE_EVT );
}
// Discard unknown events
return 0;
}
static void multiRoleAPP_ComInit(void)
{
uint16 desired_min_interval = DEFAULT_CONN_MIN_INTV ;
uint16 desired_slave_latency = DEFAULT_UPDATE_SLAVE_LATENCY;
uint16 desired_conn_timeout = DEFAULT_UPDATE_CONN_TIMEOUT;
GAPMultiRole_SetParameter( GAPMULTIROLE_MIN_CONN_INTERVAL, sizeof( uint16 ), &desired_min_interval);
GAPMultiRole_SetParameter( GAPMULTIROLE_MAX_CONN_INTERVAL, sizeof( uint16 ), &desired_min_interval);
GAPMultiRole_SetParameter( GAPMULTIROLE_SLAVE_LATENCY, sizeof( uint16 ), &desired_slave_latency);
GAPMultiRole_SetParameter( GAPMULTIROLE_TIMEOUT_MULTIPLIER, sizeof( uint16 ), &desired_conn_timeout);
}
/*********************************************************************
@fn simpleBLECentral_ProcessOSALMsg
@brief Process an incoming task message.
@param pMsg - message to process
@return none
*/
static void multiRoleApp_ProcessOSALMsg( osal_event_hdr_t* pMsg )
{
switch ( pMsg->event )
{
case GATT_MSG_EVENT:
multiRoleAppProcessGATTMsg( (gattMsgEvent_t*) pMsg );
break;
}
}
static void multiRoleAppProcessGATTMsg( gattMsgEvent_t* pMsg )
{
switch( pMsg->method )
{
case ATT_ERROR_RSP:
{
LOG("pMsg->msg.errorRsp.handle %d\n",pMsg->msg.errorRsp.handle);
LOG("pMsg->msg.errorRsp.reqOpcode %d\n",pMsg->msg.errorRsp.reqOpcode);
LOG("pMsg->msg.errorRsp.errCode %d\n",pMsg->msg.errorRsp.errCode);
}
break;
case ATT_WRITE_RSP:
{
attWriteReq_t pReq;
pReq.sig = 0;
pReq.cmd = 0;
pReq.handle = 14;//multiRole_wrChar_handle ;
pReq.len = 2;
pReq.value[0] = (unsigned char)(GATT_CLIENT_CFG_NOTIFY);
pReq.value[1] = (unsigned char)(GATT_CLIENT_CFG_NOTIFY >> 8);
bStatus_t status = GATT_WriteCharValue(pMsg->connHandle,&pReq,multiRole_TaskId);
if(status == SUCCESS)
{
// LOG("GATT_WriteCharValue success handle %d\n",pMsg->connHandle);
}
else
{
LOG("GATT_WriteCharValue ERROR %d\r\n",status);
}
}
break;
default:
break;
}
}
static void multiRoleEstablishCB( uint8 status,uint16 connHandle,GAPMultiRole_State_t role,uint8 perIdx,uint8* addr )
{
if( status == SUCCESS )
{
LOG("Establish success connHandle %d,role %d\n",connHandle,role);
LOG("Establish success connHandle %d,perIdx %d\n",connHandle,perIdx);
if( role == Master_Role )
{
#if( MAX_CONNECTION_MASTER_NUM > 0)
muliSchedule_config( MULTI_SCH_INITIATOR_MODE, 0x00 );
if( multiGetSlaveConnList() != NULL )
{
muliSchedule_config( MULTI_SCH_INITIATOR_MODE, 0x01 );
}
else if( multiLinkGetMasterConnNum() < MAX_CONNECTION_MASTER_NUM )
{
muliSchedule_config( MULTI_SCH_SCAN_MODE, 0x01 );
}
#endif
}
else
{
// slave role establish success, delete advertising schedule node
// uint8 en_flag = perIdx << 4;
muliSchedule_config( MULTI_SCH_ADV_MODE, 0x01 );
}
}
else
{
LOG("Establish failure status %d\n",status);
//
#if( MAX_CONNECTION_MASTER_NUM > 0)
muliSchedule_config( MULTI_SCH_INITIATOR_MODE, 0x00 );
if( multiGetSlaveConnList() != NULL )
{
muliSchedule_config( MULTI_SCH_INITIATOR_MODE, 0x01 );
}
#endif
}
}
static void multiRoleTerminateCB( uint16 connHandle,GAPMultiRole_State_t role,uint8 perIdx,uint8 reason )
{
LOG("Terminate connHandle %d,role %d,perIdx %d, reason %d\n",connHandle,role,perIdx,reason );
#if ( MAX_CONNECTION_SLAVE_NUM > 0 )
if( role == Slave_Role )
{
// 0x01 : enable flag
uint8 en_flag = ( 1 << ( 4 + perIdx) ) | 0x01 ;
if( SCH_SUCCESS == muliSchedule_config( MULTI_SCH_ADV_MODE, en_flag ) )
{
LOG("Multi Role advertising scheduler re-enable success \n");
}
}
#endif
#if( MAX_CONNECTION_MASTER_NUM > 0)
if( multiGetSlaveConnList() != NULL )
{
muliSchedule_config( MULTI_SCH_INITIATOR_MODE, 0x01 );
}
#endif
}
#if ( MAX_CONNECTION_SLAVE_NUM > 0 )
static void multiRoleAPP_AdvInit(void)
{
// advertising channel map
uint8 advChnMap = GAP_ADVCHAN_37 | GAP_ADVCHAN_38 | GAP_ADVCHAN_39;
GAPMultiRole_SetParameter( GAPMULTIROLE_ADV_CHANNEL_MAP, sizeof(uint8), &advChnMap);
// only support undirect connectable advertise
uint8 advType = LL_ADV_CONNECTABLE_UNDIRECTED_EVT;
GAPMultiRole_SetParameter( GAPMULTIROLE_ADV_EVENT_TYPE, sizeof( uint8 ), &advType);
// peripheral device delay of Conndelay seconds initiate parameter update request
uint8 param_update_enable = DEFAULT_ENABLE_UPDATE_REQUEST;
GAPMultiRole_SetParameter( GAPMULTIROLE_PARAM_UPDATE_ENABLE,sizeof( uint8 ), &param_update_enable);
uint16 Conndelay = DEFAULT_CONN_PAUSE_PERIPHERAL;
GAPMultiRole_SetParameter( TGAP_CONN_PAUSE_PERIPHERAL,sizeof(uint16), &Conndelay);
uint8 advFilterPolicy = GAP_FILTER_POLICY_ALL;
GAPMultiRole_SetParameter(GAPMULTIROLE_ADV_FILTER_POLICY,sizeof( uint8 ),&advFilterPolicy);
// limit & general & connection discovery mode use the same advertising interval
GAP_SetParamValue( TGAP_GEN_DISC_ADV_INT_MIN,DEFAULT_ADV_INTV);
GAP_SetParamValue( TGAP_GEN_DISC_ADV_INT_MAX,DEFAULT_ADV_INTV);
GAP_SetParamValue( TGAP_LIM_DISC_ADV_INT_MIN,DEFAULT_ADV_INTV);
GAP_SetParamValue( TGAP_LIM_DISC_ADV_INT_MIN,DEFAULT_ADV_INTV);
GAP_SetParamValue( TGAP_CONN_ADV_INT_MIN,DEFAULT_ADV_INTV);
GAP_SetParamValue( TGAP_CONN_ADV_INT_MAX,DEFAULT_ADV_INTV);
for( uint8 i=0; i<MAX_CONNECTION_SLAVE_NUM; i++)
multiRole_setup_adv_scanRspData(i);
// GAP GATT Attributes -- device name & appearance ...
uint8 simpleBLEDeviceName[GAP_DEVICE_NAME_LEN] = "Simple BLE MultiRole";
GGS_SetParameter( GGS_DEVICE_NAME_ATT, GAP_DEVICE_NAME_LEN, (uint8*) simpleBLEDeviceName );
}
void multiRoleProfileChangeCB( uint16 connHandle,uint16 paramID, uint16 len )
{
uint8 newValue[ATT_MTU_SIZE];
switch( paramID )
{
case MULTIPROFILE_CHAR1:
MultiProfile_GetParameter( connHandle,MULTIPROFILE_CHAR1, newValue );
MultiProfile_Notify(connHandle,MULTIPROFILE_CHAR2,len,newValue);
break;
case MULTIPROFILE_CHAR2:
MultiProfile_GetParameter( connHandle,MULTIPROFILE_CHAR2, newValue );
break;
default:
break;
}
}
static void multiRole_setup_adv_scanRspData(uint8 idx)
{
// Multi-role Advertising Data & Scan Response Data
uint8 gapMultiRole_AdvertData[] =
{
// flags
0x02,
GAP_ADTYPE_FLAGS,
GAP_ADTYPE_FLAGS_GENERAL | GAP_ADTYPE_FLAGS_BREDR_NOT_SUPPORTED
};
uint8 gapMultiRole_ScanRspData[] =
{
0x0C, // length of this data
GAP_ADTYPE_LOCAL_NAME_COMPLETE, // AD Type = Complete local name
'M','u','l','t','i','-','R','o','l','e','x'
};
uint8 bufLen = sizeof(gapMultiRole_ScanRspData);
gapMultiRole_ScanRspData[ bufLen-1 ] = idx + 0x30 ;
multiSchedule_advParam_init(idx,GAPMULTIROLE_ADVERT_DATA,sizeof( gapMultiRole_AdvertData ), gapMultiRole_AdvertData);
multiSchedule_advParam_init(idx,GAPMULTIROLE_SCAN_RSP_DATA,sizeof( gapMultiRole_ScanRspData ), gapMultiRole_ScanRspData);
}
#endif
#if( MAX_CONNECTION_MASTER_NUM > 0)
static void multiRoleAPP_ScIn_Init(void)
{
// expect connection parameter
uint16 EstMIN = DEFAULT_CONN_MIN_INTV;
GAP_SetParamValue( TGAP_CONN_EST_INT_MIN, EstMIN );
GAP_SetParamValue( TGAP_CONN_EST_INT_MAX, EstMIN );
GAP_SetParamValue( TGAP_CONN_EST_SUPERV_TIMEOUT,DEFAULT_UPDATE_CONN_TIMEOUT );
// default scan duration
GAP_SetParamValue( TGAP_GEN_DISC_SCAN, DEFAULT_SCAN_DURATION );
GAP_SetParamValue( TGAP_LIM_DISC_SCAN, DEFAULT_SCAN_DURATION );
uint8 maxScanNum = DEFAULE_SCAN_MAX_NUM;
GAPMultiRole_SetParameter(GAPMULTIROLE_MAX_SCAN_RES,sizeof( uint8 ), &maxScanNum);
uint8 scanMode = DEFAULT_DISCOVERY_MODE;
GAPMultiRole_SetParameter(GAPMULTIROLE_SCAN_MODE,sizeof( uint8 ), &scanMode);
uint8 activeScan = DEFAULT_DISCOVERY_ACTIVE_SCAN;
GAPMultiRole_SetParameter(GAPMULTIROLE_ACTIVE_SCAN,sizeof( uint8 ), &activeScan);
uint8 scanWhitelist = DEFAULT_DISCOVERY_WHITE_LIST;
GAPMultiRole_SetParameter(GAPMULTIROLE_SCAN_WHITELIST,sizeof( uint8 ), &scanWhitelist);
uint8 linkDutyCycle = DEFAULT_LINK_HIGH_DUTY_CYCLE;
GAPMultiRole_SetParameter(GAPMULTIROLE_LINK_HIGHDUTYCYCLE,sizeof( uint8 ), &linkDutyCycle);
uint8 linkWhitelist = DEFAULT_LINK_WHITE_LIST;
GAPMultiRole_SetParameter(GAPMULTIROLE_LINK_WHITELIST,sizeof( uint8 ), &linkWhitelist);
uint16 actionAfterLink = DEFAULT_ACTION_AFTER_LINK;
GAPMultiRole_SetParameter( GAPMULTIROLE_ACTION_AFTER_LINK, sizeof( uint16 ), &actionAfterLink );
GAP_SetParamValue( TGAP_SCAN_RSP_RSSI_MIN, ((uint16)DEFAULT_SCAN_RSP_RSSI_MIN) );
// prepare conn device MAC Addr
// attention : addr LSB First
uint8 addrType = ADDRTYPE_PUBLIC;
uint8 addr[B_ADDR_LEN]= {0x00,0x78,0x34,0x56,0x56,0x78};
for(uint8 i = 0; i < MAX_CONNECTION_MASTER_NUM ; i++)
{
addr[0] = 0x98 + i;
multiConfigSlaveList(addrType,addr);
}
LOG("multi-role as master add slave MAC address\n");
}
static void multiRoleSDPCB( void* msg )
{
GAPMultiRole_CentralSDP_t* sdp_info = (GAPMultiRole_CentralSDP_t*)msg;
// while( sdp_info )
{
// should display peer mac address
// MAC address display when connection established
LOG("connHandle = %d\n",sdp_info->connHandle);
GATTReadGroupRsp* primservice = sdp_info->service.PrimServ;
LOG("primary service \n" );
while( primservice )
{
LOG("start handle %d\n",primservice->StHandle);
LOG(" end handle %d\n",primservice->EGHandle);
// LOG(" uuid_Len %d\n",primservice->uuid_Len);
LOG(" uuid ");
for(uint8 k=0; k<primservice->uuid_Len; k++)
{
LOG("0x%02X,",primservice->uuid[k]);
}
LOG("\n\n");
primservice = primservice->next;
}
Characteristic* charac = sdp_info->service.Charac;
LOG("characteristic \n" );
while( charac )
{
LOG(" char handle %d\n",charac->charHandle);
LOG(" Properties 0x%02X\n",charac->Properties);
LOG("value handle %d\n",charac->valueHandle);
// LOG(" uuid_Len %d\n",charac->uuid_Len);
LOG(" uuid ");
for(uint8 k=0; k<charac->uuid_Len; k++)
{
LOG("0x%02X,",charac->uuid[k]);
}
LOG("\n\n");
// multiRole_wrChar_handle = charac->valueHandle;
if( charac->Properties & GATT_PROP_NOTIFY )
{
attWriteReq_t pReq;
pReq.sig = 0;
pReq.cmd = 0;
pReq.handle = charac->valueHandle + 1 ;
pReq.len = 2;
pReq.value[0] = (unsigned char)(GATT_CLIENT_CFG_NOTIFY);
pReq.value[1] = (unsigned char)(GATT_CLIENT_CFG_NOTIFY >> 8);
bStatus_t status = GATT_WriteCharValue(sdp_info->connHandle,&pReq,multiRole_TaskId);
if(status == SUCCESS)
{
// LOG("GATT_WriteCharValue Notify success handle %d\n",sdp_info->connHandle);
}
else
{
LOG("GATT_WriteCharValue Notify ERROR %d\r\n",status);
}
}
charac = charac->next;
}
// sdp_info = sdp_info->next;
}
}
static void multiRoleNotifyCB(uint16 connHandle,uint16 len,uint8* data )
{
LOG("Notify success connHanle %d,len %d\n",connHandle,len);
for(unsigned char i = 0; i < len; i++)
{
LOG( "0x%02X,",data[i]);
}
LOG("\n");
}
static void multiRoleEachScanCB( gapDeviceInfoEvent_t* pPkt )
{
// LOG( bdAddr2Str( pPkt->addr ) );
// LOG("\n");
// TODO: cancel disvocery check logic
// GAPMultiRole_CancelDiscovery();
// notes : Application can get more info form pointer pPkt
// eg:
// addrType , adv event type , rssi , advData ...
}
static void multiRoleScanDoneCB( GAPMultiRolScanner_t* node )
{
muliSchedule_config( MULTI_SCH_SCAN_MODE, 0x00 );
while( node )
{
if( ( multiDevInConfSlaveList( node->addr ) ) && ( multi_devInLinkList( node->addr ) == FALSE) )
{
multiAddSlaveConnList( node->addrtype,node->addr );
}
LOG("node %p\n",node);
LOG( bdAddr2Str( node->addr ) );
LOG("--addrtype %d\n",node->addrtype);
if( node->advDatalen > 0)
{
LOG("advDatalen %d\n",node->advDatalen);
for( uint8 i=0; i<node->advDatalen; i++)
LOG("0x%02X,",node->advData[i]);
LOG("\n");
}
if( node->scanRsplen > 0 )
{
LOG("scanRsplen %d\n",node->scanRsplen);
for( uint8 i=0; i<node->scanRsplen; i++)
LOG("0x%02X,",node->rspData[i]);
LOG("\n");
}
LOG("\n");
node = node->next;
}
if( multiGetSlaveConnList() != NULL )
{
muliSchedule_config( MULTI_SCH_INITIATOR_MODE, 0x01 );
}
else
{
muliSchedule_config( MULTI_SCH_SCAN_MODE, 0x01 );
}
}
#endif
/*********************************************************************
*********************************************************************/

View File

@ -0,0 +1,93 @@
/**************************************************************************************************
*******
**************************************************************************************************/
#ifndef MULTI_ROLE_H
#define MULTI_ROLE_H
#ifdef __cplusplus
extern "C"
{
#endif
/*********************************************************************
INCLUDES
*/
/*********************************************************************
CONSTANTS
*/
// Simple BLE Central Task Events
#define START_DEVICE_EVT 0x0001
#define BUP_OTA_PERIOD_EVT 0x0020
#define MULTIROLE_HID_SEND_REPORT_EVT 0x1000
#define MULTIROLE_HID_IDLE_EVT 0x2000
#define MULTIROLE_PERIOD_EVT 0x4000
/*********************************************************************
MACROS
*/
// LCD macros
#if HAL_LCD == TRUE
#define LCD_WRITE_STRING(str, option) HalLcdWriteString( (str), (option))
#define LCD_WRITE_SCREEN(line1, line2) HalLcdWriteScreen( (line1), (line2) )
#define LCD_WRITE_STRING_VALUE(title, value, format, line) HalLcdWriteStringValue( (title), (value), (format), (line) )
#else
#define LCD_WRITE_STRING(str, option)
#define LCD_WRITE_SCREEN(line1, line2)
#define LCD_WRITE_STRING_VALUE(title, value, format, line)
#endif
/*********************************************************************
Typedef
*/
//typedef struct
//{
// GAPMultiRole_states_t state;
// GAPMultiRole_State_t role;
//
// // SMP
// uint8 ConnSecure;
// uint8 PairingStarted;
// // slave
// uint8 notify;
// uint8 dle;
// uint8 MTUExchange;
//
// // master
// uint8 SDPDone;
//
// uint16 cccdHandle;
// uint16 enableCCCD;
// uint16 Char5ValueHandle;
// uint16 Char5isWrite;
//
//}MultiRoleApp_Link_t;
/*********************************************************************
FUNCTIONS
*/
/*
Task Initialization for the BLE Application
*/
extern void multiRoleApp_Init( uint8 task_id );
/*
Task Event Processor for the BLE Application
*/
extern uint16 multiRoleApp_ProcessEvent( uint8 task_id, uint16 events );
/*********************************************************************
*********************************************************************/
#ifdef __cplusplus
}
#endif
#endif /* SIMPLEBLECENTRAL_H */

View File

@ -0,0 +1,50 @@
/**************************************************************************************************
Filename: simpleBLECentral_Main.c
Revised: $Date: 2020-02-24 15:48:00 -0800 (Thu, 24 Feb 2011) $
Revision: $Revision: 11 $
Description: This file contains the main and callback functions for
the Simple BLE Central sample application.
**************************************************************************************************/
/**************************************************************************************************
Includes
**************************************************************************************************/
/* Hal Drivers */
/* OSAL */
#include "OSAL.h"
#include "OSAL_Tasks.h"
#include "OSAL_PwrMgr.h"
/**************************************************************************************************
FUNCTIONS
**************************************************************************************************/
/**************************************************************************************************
@fn main
@brief Start of application.
@param none
@return none
**************************************************************************************************
*/
int app_main(void)
{
/* Initialize the operating system */
osal_init_system();
osal_pwrmgr_device( PWRMGR_BATTERY );
/* Start OSAL */
osal_start_system(); // No Return from here
return 0;
}
/**************************************************************************************************
CALL-BACKS
**************************************************************************************************/
/*************************************************************************************************
**************************************************************************************************/

View File

@ -0,0 +1,182 @@
/*******************************************************************************************************
-----------------------------------------------------------------------------------------------------
@file : FileName multi role scheduler .h file
@author :
@date : 2020-12-4
@brief : used to schedule the multi role task list
@attention :
-----------------------------------------------------------------------------------------------------
Modification History
DATE NAME DESCRIPTION
-----------------------------------------------------------------------------------------------------
-----------------------------------------------------------------------------------------------------
*******************************************************************************************************/
#ifndef _MULTI_SCHEDULE_H
#define _MULTI_SCHEDULE_H
/*******************************************************************************************************
@ Description : MACRO DEFINE
@author :
*******************************************************************************************************/
// for scheduler mode
#define MULTI_ADV_PARAM_MODE 0x01 // advertising parameter
#define MULTI_SCH_SCAN_MODE 0x02
#define MULTI_SCH_INITIATOR_MODE 0x04
#define MULTI_SCH_ADV_MODE 0x08 // scheduler advertising list
#define MULTI_SCH_MODE MULTI_SCH_SCAN_MODE | MULTI_SCH_INITIATOR_MODE | MULTI_SCH_ADV_MODE
#define MULTI_LINK_MODE 0x10
// scheduler error code
#define SCH_SUCCESS 0x00
#define SCH_LIST_NULL 0x01
#define SCH_INVALID_ERROR_CODE 0xFF
/*******************************************************************************************************
@ Description : typedef -- multi role advertising parameter structure
Modification History
DATE DESCRIPTION
2020-12-7 first add for multi role advertising parameter support
------------------------------------------------------------------------------
@author :
*******************************************************************************************************/
// advertising parameter structure
typedef struct
{
uint8 AdvDataLen;
uint8* pAdvData;
uint8 ScanRspDataLen;
uint8* pScanRspData;
} multiAdvParam_t;
// schedule advertising structure
typedef struct pAdv
{
// idx : indicate which advertising parameter
uint8 idx;
// advertising parameter
multiAdvParam_t advParam;
struct pAdv* next;
} multisch_adv_t;
/*******************************************************************************************************
@ Description : API FUNCTIONS ---- multi role for multi.c
@author :
*******************************************************************************************************/
/*******************************************************************************************************
*******************************************************************************************************
@ Description : multi role scheduler init
@ Parameters :
: [IN]
: [OUT]
@ Return : Success: Failure:
@ Other :
Modification History
DATE DESCRIPTION
------------------------------------------------------------------------------
@author :
*******************************************************************************************************
*******************************************************************************************************/
void multiSchedule_init(uint8 taskid);
/*******************************************************************************************************
*******************************************************************************************************
@ Description : multi role schedule advertising parameter init
@ Parameters :
: [IN] idx:the index of the advertising parameter , which want to be insert
param:advertising data or scan response data
len:the length of the data
pValue: the pointer of the value
: [OUT] None
@ Return : None
@ Other :
Modification History
DATE DESCRIPTION
------------------------------------------------------------------------------
@author :
*******************************************************************************************************
*******************************************************************************************************/
void multiSchedule_advParam_init(uint8 idx,uint16 param, uint8 len, void* pValue);
/*******************************************************************************************************
*******************************************************************************************************
@ Description : multi role schedule advertising param index delete
@ Parameters :
: [IN] idx : the advertising parameter index,which want to be deleted
: [OUT] None
@ Return : Success: Failure:
@ Other :
Modification History
DATE DESCRIPTION
------------------------------------------------------------------------------
@author :
*******************************************************************************************************
*******************************************************************************************************/
void multiSchedule_advParam_del( uint8 idx);
/*******************************************************************************************************
@ Description : API FUNCTIONS ---- multi role for multi_role.c
@author :
*******************************************************************************************************/
/*******************************************************************************************************
*******************************************************************************************************
@ Description : multi role schedule config
@ Parameters :
: [IN] mode : adv mode , scan mode or initiator mode
en_flag : enable or disable mode.for advertising en_flag bit0:enable/disable,
bit4-bit7:advertising index
: [OUT]
@ Return : None
@ Other : when enable schedule, will create the list,otherwise delete the list node
Modification History
DATE DESCRIPTION
------------------------------------------------------------------------------
@author :
*******************************************************************************************************
*******************************************************************************************************/
uint8 muliSchedule_config(uint8 mode, uint8 en_flag);
/*******************************************************************************************************
*******************************************************************************************************
@ Description : multi role schedule process: advertising , scanning , initiating
@ Parameters : None
: [IN] None
: [OUT] None
@ Return : None
@ Other :
Modification History
DATE DESCRIPTION
------------------------------------------------------------------------------
@author :
********************************************************************************************************
********************************************************************************************************/
void multiScheduleProcess(void);
/*******************************************************************************************************
*******************************************************************************************************
@ Description : multiLinkStatusGetSlaveConnHandle
@ Parameters :
: [IN] idx : advertising parameter index
: [OUT]
@ Return : 16bit value connhandle
@ Other :
Modification History
DATE DESCRIPTION
------------------------------------------------------------------------------
@author :
*******************************************************************************************************
*******************************************************************************************************/
uint16 multiLinkStatusGetSlaveConnHandle( uint8 idx);
uint8 multiLinkConnParamUpdate( gapLinkUpdateEvent_t* pPkt );
extern uint8 multiLinkGetMasterConnNum(void);
#endif

View File

@ -0,0 +1,111 @@
/*
All rights reserved
*/
#include "types.h"
#include "multi_timer.h"
#include "osal.h"
#include "osal_memory.h"
//timer handle list head.
struct multiTimer* head_handle = NULL;
//Timer ticks
static uint32 _timer_ticks = 0;
/**
@brief Initializes the timer struct handle.
@param handle: the timer handle strcut.
@param timeout_cb: timeout callback.
@param repeat: repeat interval time.
@retval None
*/
void multitimer_init(struct multiTimer* handle, void(*timeout_cb)(uint16 idx), uint32 timeout, uint32 repeat,uint32 id)
{
osal_memset(handle, sizeof(struct multiTimer), 0);
handle->timeout_cb = timeout_cb;
handle->timeout = _timer_ticks + timeout;
handle->repeat = repeat;
handle->id = id;
}
/**
@brief Start the timer work, add the handle into work list.
@param btn: target handle strcut.
@retval 0: succeed. -1: already exist.
*/
int multitimer_start(struct multiTimer* handle)
{
struct multiTimer* target = head_handle;
while(target)
{
if(target == handle) return -1; //already exist.
target = target->next;
}
handle->next = head_handle;
head_handle = handle;
return 0;
}
/**
@brief Stop the timer work, remove the handle off work list.
@param handle: target handle strcut.
@retval None
*/
void multitimer_stop(struct multiTimer* handle)
{
struct multiTimer** curr;
for(curr = &head_handle; *curr; )
{
struct multiTimer* entry = *curr;
if (entry == handle)
{
*curr = entry->next;
osal_mem_free(entry);
}
else
curr = &entry->next;
}
}
/**
@brief main loop.
@param None.
@retval None
*/
void multitimer_loop()
{
struct multiTimer* target;
for(target=head_handle; target; target=target->next)
{
if(_timer_ticks >= target->timeout)
{
target->timeout_cb(target->id);
if(target->repeat == 0)
{
multitimer_stop(target);
}
else
{
target->timeout = _timer_ticks + target->repeat;
}
}
}
}
/**
@brief background ticks, timer repeat invoking interval 1ms.
@param None.
@retval None.
*/
void multitimer_ticks( uint32 tick )
{
_timer_ticks += tick ;
}

View File

@ -0,0 +1,36 @@
/*
Copyright (c) 2016 Zibin Zheng <znbin@qq.com>
All rights reserved
*/
#ifndef _MULTI_TIMER_H_
#define _MULTI_TIMER_H_
typedef struct multiTimer
{
uint32 valid;
uint32 id;
uint32 timeout;
uint32 repeat;
void (*timeout_cb)(uint16 idx);
struct multiTimer* next;
} multiTimer;
#ifdef __cplusplus
extern "C" {
#endif
void multitimer_init(struct multiTimer* handle, void(*timeout_cb)(uint16 idx), uint32 timeout, uint32 repeat,uint32 id);
int multitimer_start(struct multiTimer* handle);
void multitimer_stop(struct multiTimer* handle);
void multitimer_ticks(uint32 tick);
void multitimer_loop(void);
// void timer_again(struct Timer* handle);
// void timer_set_repeat(struct Timer* handle, uint32_t repeat);
#ifdef __cplusplus
}
#endif
#endif

View File

@ -0,0 +1,253 @@
;/**************************************************************************//**
; * @file startup_ARMCM0.s
; * @brief CMSIS Core Device Startup File for
; * ARMCM0 Device Series
; * @version V1.08
; * @date 23. November 2012
; *
; * @note
; *
; ******************************************************************************/
;/* Copyright (c) 2011 - 2012 ARM LIMITED
;
; All rights reserved.
; Redistribution and use in source and binary forms, with or without
; modification, are permitted provided that the following conditions are met:
; - Redistributions of source code must retain the above copyright
; notice, this list of conditions and the following disclaimer.
; - Redistributions in binary form must reproduce the above copyright
; notice, this list of conditions and the following disclaimer in the
; documentation and/or other materials provided with the distribution.
; - Neither the name of ARM nor the names of its contributors may be used
; to endorse or promote products derived from this software without
; specific prior written permission.
; *
; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
; ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE
; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
; POSSIBILITY OF SUCH DAMAGE.
; ---------------------------------------------------------------------------*/
;/*
;//-------- <<< Use Configuration Wizard in Context Menu >>> ------------------
;*/
; <h> Stack Configuration
; <o> Stack Size (in Bytes) <0x0-0xFFFFFFFF:8>
; </h>
Stack_Size EQU 0x00000400
AREA STACK, NOINIT, READWRITE, ALIGN=3
Stack_Mem SPACE Stack_Size
__initial_sp
; <h> Heap Configuration
; <o> Heap Size (in Bytes) <0x0-0xFFFFFFFF:8>
; </h>
Heap_Size EQU 0x00000C00
AREA HEAP, NOINIT, READWRITE, ALIGN=3
__heap_base
Heap_Mem SPACE Heap_Size
__heap_limit
PRESERVE8
THUMB
; Vector Table Mapped to Address 0 at Reset
AREA RESET, DATA, READONLY
EXPORT __Vectors
EXPORT __Vectors_End
EXPORT __Vectors_Size
__Vectors DCD __initial_sp ; Top of Stack
DCD Reset_Handler ; Reset Handler
DCD NMI_Handler ; NMI Handler
DCD HardFault_Handler ; Hard Fault Handler
DCD 0 ; Reserved
DCD 0 ; Reserved
DCD 0 ; Reserved
DCD 0 ; Reserved
DCD 0 ; Reserved
DCD 0 ; Reserved
DCD 0 ; Reserved
DCD SVC_Handler ; SVCall Handler
DCD 0 ; Reserved
DCD 0 ; Reserved
DCD PendSV_Handler ; PendSV Handler
DCD SysTick_Handler ; SysTick Handler
; External Interrupts
DCD WDT_IRQHandler ; 0: Watchdog Timer
DCD RTC_IRQHandler ; 1: Real Time Clock
DCD TIM0_IRQHandler ; 2: Timer0 / Timer1
DCD TIM2_IRQHandler ; 3: Timer2 / Timer3
DCD MCIA_IRQHandler ; 4: MCIa
DCD MCIB_IRQHandler ; 5: MCIb
DCD UART0_IRQHandler ; 6: UART0 - DUT FPGA
DCD UART1_IRQHandler ; 7: UART1 - DUT FPGA
DCD UART2_IRQHandler ; 8: UART2 - DUT FPGA
DCD UART4_IRQHandler ; 9: UART4 - not connected
DCD AACI_IRQHandler ; 10: AACI / AC97
DCD CLCD_IRQHandler ; 11: CLCD Combined Interrupt
DCD ENET_IRQHandler ; 12: Ethernet
DCD USBDC_IRQHandler ; 13: USB Device
DCD USBHC_IRQHandler ; 14: USB Host Controller
DCD CHLCD_IRQHandler ; 15: Character LCD
DCD FLEXRAY_IRQHandler ; 16: Flexray
DCD CAN_IRQHandler ; 17: CAN
DCD LIN_IRQHandler ; 18: LIN
DCD I2C_IRQHandler ; 19: I2C ADC/DAC
DCD 0 ; 20: Reserved
DCD 0 ; 21: Reserved
DCD 0 ; 22: Reserved
DCD 0 ; 23: Reserved
DCD 0 ; 24: Reserved
DCD 0 ; 25: Reserved
DCD 0 ; 26: Reserved
DCD 0 ; 27: Reserved
DCD CPU_CLCD_IRQHandler ; 28: Reserved - CPU FPGA CLCD
DCD 0 ; 29: Reserved - CPU FPGA
DCD UART3_IRQHandler ; 30: UART3 - CPU FPGA
DCD SPI_IRQHandler ; 31: SPI Touchscreen - CPU FPGA
__Vectors_End
__Vectors_Size EQU __Vectors_End - __Vectors
AREA |.text|, CODE, READONLY
; Reset Handler
Reset_Handler PROC
EXPORT Reset_Handler [WEAK]
IMPORT SystemInit
IMPORT __main
LDR R0, =SystemInit
BLX R0
LDR R0, =__main
BX R0
ENDP
; Dummy Exception Handlers (infinite loops which can be modified)
NMI_Handler PROC
EXPORT NMI_Handler [WEAK]
B .
ENDP
HardFault_Handler\
PROC
EXPORT HardFault_Handler [WEAK]
B .
ENDP
SVC_Handler PROC
EXPORT SVC_Handler [WEAK]
B .
ENDP
PendSV_Handler PROC
EXPORT PendSV_Handler [WEAK]
B .
ENDP
SysTick_Handler PROC
EXPORT SysTick_Handler [WEAK]
B .
ENDP
Default_Handler PROC
EXPORT WDT_IRQHandler [WEAK]
EXPORT RTC_IRQHandler [WEAK]
EXPORT TIM0_IRQHandler [WEAK]
EXPORT TIM2_IRQHandler [WEAK]
EXPORT MCIA_IRQHandler [WEAK]
EXPORT MCIB_IRQHandler [WEAK]
EXPORT UART0_IRQHandler [WEAK]
EXPORT UART1_IRQHandler [WEAK]
EXPORT UART2_IRQHandler [WEAK]
EXPORT UART3_IRQHandler [WEAK]
EXPORT UART4_IRQHandler [WEAK]
EXPORT AACI_IRQHandler [WEAK]
EXPORT CLCD_IRQHandler [WEAK]
EXPORT ENET_IRQHandler [WEAK]
EXPORT USBDC_IRQHandler [WEAK]
EXPORT USBHC_IRQHandler [WEAK]
EXPORT CHLCD_IRQHandler [WEAK]
EXPORT FLEXRAY_IRQHandler [WEAK]
EXPORT CAN_IRQHandler [WEAK]
EXPORT LIN_IRQHandler [WEAK]
EXPORT I2C_IRQHandler [WEAK]
EXPORT CPU_CLCD_IRQHandler [WEAK]
EXPORT SPI_IRQHandler [WEAK]
WDT_IRQHandler
RTC_IRQHandler
TIM0_IRQHandler
TIM2_IRQHandler
MCIA_IRQHandler
MCIB_IRQHandler
UART0_IRQHandler
UART1_IRQHandler
UART2_IRQHandler
UART3_IRQHandler
UART4_IRQHandler
AACI_IRQHandler
CLCD_IRQHandler
ENET_IRQHandler
USBDC_IRQHandler
USBHC_IRQHandler
CHLCD_IRQHandler
FLEXRAY_IRQHandler
CAN_IRQHandler
LIN_IRQHandler
I2C_IRQHandler
CPU_CLCD_IRQHandler
SPI_IRQHandler
B .
ENDP
ALIGN
; User Initial Stack & Heap
IF :DEF:__MICROLIB
EXPORT __initial_sp
EXPORT __heap_base
EXPORT __heap_limit
ELSE
IMPORT __use_two_region_memory
EXPORT __user_initial_stackheap
__user_initial_stackheap PROC
LDR R0, = Heap_Mem
LDR R1, =(Stack_Mem + Stack_Size)
LDR R2, = (Heap_Mem + Heap_Size)
LDR R3, = Stack_Mem
BX LR
ENDP
ALIGN
ENDIF
END

View File

@ -0,0 +1,82 @@
/**************************************************************************//**
@file system_ARMCM0.c
@brief CMSIS Device System Source File for
ARMCM0 Device Series
@version V1.09
@date 27. August 2014
@note
******************************************************************************/
/* Copyright (c) 2011 - 2014 ARM LIMITED
All rights reserved.
Redistribution and use in source and binary forms, with or without
modification, are permitted provided that the following conditions are met:
- Redistributions of source code must retain the above copyright
notice, this list of conditions and the following disclaimer.
- Redistributions in binary form must reproduce the above copyright
notice, this list of conditions and the following disclaimer in the
documentation and/or other materials provided with the distribution.
- Neither the name of ARM nor the names of its contributors may be used
to endorse or promote products derived from this software without
specific prior written permission.
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE
LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
POSSIBILITY OF SUCH DAMAGE.
---------------------------------------------------------------------------*/
#include "ARMCM0.h"
/* ----------------------------------------------------------------------------
Define clocks
----------------------------------------------------------------------------*/
#define __HSI ( 8000000UL)
#define __XTAL ( 5000000UL) /* Oscillator frequency */
#define __SYSTEM_CLOCK (5*__XTAL)
/* ----------------------------------------------------------------------------
System Core Clock Variable
----------------------------------------------------------------------------*/
uint32_t SystemCoreClock = __SYSTEM_CLOCK;/* System Core Clock Frequency */
/**
Update SystemCoreClock variable
@param none
@return none
@brief Updates the SystemCoreClock with current core Clock
retrieved from cpu registers.
*/
void SystemCoreClockUpdate (void)
{
SystemCoreClock = __SYSTEM_CLOCK;
}
/**
Initialize the system
@param none
@return none
@brief Setup the microcontroller system.
Initialize the System.
*/
void SystemInit (void)
{
SystemCoreClock = __SYSTEM_CLOCK;
}

View File

@ -0,0 +1,21 @@
/*
* Auto generated Run-Time-Environment Configuration File
* *** Do not modify ! ***
*
* Project: 'adc'
* Target: 'adc'
*/
#ifndef RTE_COMPONENTS_H
#define RTE_COMPONENTS_H
/*
* Define the Device Header File:
*/
#define CMSIS_device_header "ARMCM0.h"
#endif /* RTE_COMPONENTS_H */

View File

@ -0,0 +1,30 @@
; *************************************************************
; *** Scatter-Loading Description File generated by uVision ***
; *************************************************************
LR_IROM1 0x1fff1838 0x0000E7C8 { ; load region size_region
ER_IROM1 0x1fff1838 0x0000E7C8 { ; load address = execution address
*.o (RESET, +First)
*(InRoot$$Sections)
*.o(.rev16_text,.revsh_text,.text)
.ANY (+RO)
.ANY (+RW +ZI)
}
}
LR_IROM2 0x1fff0000 0x00800 {
JUMP_TABLE 0x1fff0000 0x00400 {
.ANY (jump_table_mem_area)
}
GOLBAL_CONFIG 0x1fff0400 0x00400 {
.ANY (global_config_area)
}
}
;LR_IROM23 0x11032000 0x10000 {
;ER_IROM3 0x11032000 0x10000 {
;gpio_demo.o (+RO)
;core_*.o (+RO)
;}
;}

File diff suppressed because one or more lines are too long

View File

@ -0,0 +1,548 @@
<?xml version="1.0" encoding="UTF-8" standalone="no" ?>
<ProjectOpt xmlns:xsi="http://www.w3.org/2001/XMLSchema-instance" xsi:noNamespaceSchemaLocation="project_optx.xsd">
<SchemaVersion>1.0</SchemaVersion>
<Header>### uVision Project, (C) Keil Software</Header>
<Extensions>
<cExt>*.c</cExt>
<aExt>*.s*; *.src; *.a*</aExt>
<oExt>*.obj; *.o</oExt>
<lExt>*.lib</lExt>
<tExt>*.txt; *.h; *.inc</tExt>
<pExt>*.plm</pExt>
<CppX>*.cpp</CppX>
<nMigrate>0</nMigrate>
</Extensions>
<DaveTm>
<dwLowDateTime>0</dwLowDateTime>
<dwHighDateTime>0</dwHighDateTime>
</DaveTm>
<Target>
<TargetName>adc</TargetName>
<ToolsetNumber>0x4</ToolsetNumber>
<ToolsetName>ARM-ADS</ToolsetName>
<TargetOption>
<CLKADS>12000000</CLKADS>
<OPTTT>
<gFlags>1</gFlags>
<BeepAtEnd>1</BeepAtEnd>
<RunSim>0</RunSim>
<RunTarget>1</RunTarget>
<RunAbUc>0</RunAbUc>
</OPTTT>
<OPTHX>
<HexSelection>1</HexSelection>
<FlashByte>65535</FlashByte>
<HexRangeLowAddress>0</HexRangeLowAddress>
<HexRangeHighAddress>0</HexRangeHighAddress>
<HexOffset>0</HexOffset>
</OPTHX>
<OPTLEX>
<PageWidth>79</PageWidth>
<PageLength>66</PageLength>
<TabStop>8</TabStop>
<ListingPath>.\Listings\</ListingPath>
</OPTLEX>
<ListingPage>
<CreateCListing>1</CreateCListing>
<CreateAListing>1</CreateAListing>
<CreateLListing>1</CreateLListing>
<CreateIListing>0</CreateIListing>
<AsmCond>1</AsmCond>
<AsmSymb>1</AsmSymb>
<AsmXref>0</AsmXref>
<CCond>1</CCond>
<CCode>0</CCode>
<CListInc>0</CListInc>
<CSymb>0</CSymb>
<LinkerCodeListing>0</LinkerCodeListing>
</ListingPage>
<OPTXL>
<LMap>1</LMap>
<LComments>1</LComments>
<LGenerateSymbols>1</LGenerateSymbols>
<LLibSym>1</LLibSym>
<LLines>1</LLines>
<LLocSym>1</LLocSym>
<LPubSym>1</LPubSym>
<LXref>0</LXref>
<LExpSel>0</LExpSel>
</OPTXL>
<OPTFL>
<tvExp>1</tvExp>
<tvExpOptDlg>0</tvExpOptDlg>
<IsCurrentTarget>1</IsCurrentTarget>
</OPTFL>
<CpuCode>7</CpuCode>
<DebugOpt>
<uSim>0</uSim>
<uTrg>1</uTrg>
<sLdApp>1</sLdApp>
<sGomain>1</sGomain>
<sRbreak>1</sRbreak>
<sRwatch>1</sRwatch>
<sRmem>1</sRmem>
<sRfunc>1</sRfunc>
<sRbox>1</sRbox>
<tLdApp>1</tLdApp>
<tGomain>1</tGomain>
<tRbreak>1</tRbreak>
<tRwatch>1</tRwatch>
<tRmem>1</tRmem>
<tRfunc>0</tRfunc>
<tRbox>1</tRbox>
<tRtrace>1</tRtrace>
<sRSysVw>1</sRSysVw>
<tRSysVw>1</tRSysVw>
<sRunDeb>0</sRunDeb>
<sLrtime>0</sLrtime>
<bEvRecOn>1</bEvRecOn>
<bSchkAxf>0</bSchkAxf>
<bTchkAxf>0</bTchkAxf>
<nTsel>0</nTsel>
<sDll></sDll>
<sDllPa></sDllPa>
<sDlgDll></sDlgDll>
<sDlgPa></sDlgPa>
<sIfile></sIfile>
<tDll></tDll>
<tDllPa></tDllPa>
<tDlgDll></tDlgDll>
<tDlgPa></tDlgPa>
<tIfile></tIfile>
<pMon>BIN\UL2CM3.DLL</pMon>
</DebugOpt>
<TargetDriverDllRegistry>
<SetRegEntry>
<Number>0</Number>
<Key>UL2CM3</Key>
<Name>UL2CM3(-S0 -C0 -P0 -FD20000000 -FC1000)</Name>
</SetRegEntry>
</TargetDriverDllRegistry>
<Breakpoint/>
<Tracepoint>
<THDelay>0</THDelay>
</Tracepoint>
<DebugFlag>
<trace>0</trace>
<periodic>0</periodic>
<aLwin>0</aLwin>
<aCover>0</aCover>
<aSer1>0</aSer1>
<aSer2>0</aSer2>
<aPa>0</aPa>
<viewmode>0</viewmode>
<vrSel>0</vrSel>
<aSym>0</aSym>
<aTbox>0</aTbox>
<AscS1>0</AscS1>
<AscS2>0</AscS2>
<AscS3>0</AscS3>
<aSer3>0</aSer3>
<eProf>0</eProf>
<aLa>0</aLa>
<aPa1>0</aPa1>
<AscS4>0</AscS4>
<aSer4>0</aSer4>
<StkLoc>0</StkLoc>
<TrcWin>0</TrcWin>
<newCpu>0</newCpu>
<uProt>0</uProt>
</DebugFlag>
<LintExecutable></LintExecutable>
<LintConfigFile></LintConfigFile>
<bLintAuto>0</bLintAuto>
<bAutoGenD>0</bAutoGenD>
<LntExFlags>0</LntExFlags>
<pMisraName></pMisraName>
<pszMrule></pszMrule>
<pSingCmds></pSingCmds>
<pMultCmds></pMultCmds>
<pMisraNamep></pMisraNamep>
<pszMrulep></pszMrulep>
<pSingCmdsp></pSingCmdsp>
<pMultCmdsp></pMultCmdsp>
</TargetOption>
</Target>
<Group>
<GroupName>main</GroupName>
<tvExp>1</tvExp>
<tvExpOptDlg>0</tvExpOptDlg>
<cbSel>0</cbSel>
<RteFlg>0</RteFlg>
<File>
<GroupNumber>1</GroupNumber>
<FileNumber>1</FileNumber>
<FileType>1</FileType>
<tvExp>0</tvExp>
<tvExpOptDlg>0</tvExpOptDlg>
<bDave2>0</bDave2>
<PathWithFileName>.\source\main.c</PathWithFileName>
<FilenameWithoutPath>main.c</FilenameWithoutPath>
<RteFlg>0</RteFlg>
<bShared>0</bShared>
</File>
<File>
<GroupNumber>1</GroupNumber>
<FileNumber>2</FileNumber>
<FileType>1</FileType>
<tvExp>0</tvExp>
<tvExpOptDlg>0</tvExpOptDlg>
<bDave2>0</bDave2>
<PathWithFileName>.\source\adc_demo.c</PathWithFileName>
<FilenameWithoutPath>adc_demo.c</FilenameWithoutPath>
<RteFlg>0</RteFlg>
<bShared>0</bShared>
</File>
<File>
<GroupNumber>1</GroupNumber>
<FileNumber>3</FileNumber>
<FileType>1</FileType>
<tvExp>0</tvExp>
<tvExpOptDlg>0</tvExpOptDlg>
<bDave2>0</bDave2>
<PathWithFileName>.\source\adc_Main.c</PathWithFileName>
<FilenameWithoutPath>adc_Main.c</FilenameWithoutPath>
<RteFlg>0</RteFlg>
<bShared>0</bShared>
</File>
<File>
<GroupNumber>1</GroupNumber>
<FileNumber>4</FileNumber>
<FileType>1</FileType>
<tvExp>0</tvExp>
<tvExpOptDlg>0</tvExpOptDlg>
<bDave2>0</bDave2>
<PathWithFileName>.\source\OSAL_adc.c</PathWithFileName>
<FilenameWithoutPath>OSAL_adc.c</FilenameWithoutPath>
<RteFlg>0</RteFlg>
<bShared>0</bShared>
</File>
<File>
<GroupNumber>1</GroupNumber>
<FileNumber>5</FileNumber>
<FileType>1</FileType>
<tvExp>0</tvExp>
<tvExpOptDlg>0</tvExpOptDlg>
<bDave2>0</bDave2>
<PathWithFileName>.\source\adc.c</PathWithFileName>
<FilenameWithoutPath>adc.c</FilenameWithoutPath>
<RteFlg>0</RteFlg>
<bShared>0</bShared>
</File>
<File>
<GroupNumber>1</GroupNumber>
<FileNumber>6</FileNumber>
<FileType>5</FileType>
<tvExp>0</tvExp>
<tvExpOptDlg>0</tvExpOptDlg>
<bDave2>0</bDave2>
<PathWithFileName>.\source\adc.h</PathWithFileName>
<FilenameWithoutPath>adc.h</FilenameWithoutPath>
<RteFlg>0</RteFlg>
<bShared>0</bShared>
</File>
<File>
<GroupNumber>1</GroupNumber>
<FileNumber>7</FileNumber>
<FileType>1</FileType>
<tvExp>0</tvExp>
<tvExpOptDlg>0</tvExpOptDlg>
<bDave2>0</bDave2>
<PathWithFileName>.\source\timer.c</PathWithFileName>
<FilenameWithoutPath>timer.c</FilenameWithoutPath>
<RteFlg>0</RteFlg>
<bShared>0</bShared>
</File>
<File>
<GroupNumber>1</GroupNumber>
<FileNumber>8</FileNumber>
<FileType>1</FileType>
<tvExp>0</tvExp>
<tvExpOptDlg>0</tvExpOptDlg>
<bDave2>0</bDave2>
<PathWithFileName>.\source\pwm.c</PathWithFileName>
<FilenameWithoutPath>pwm.c</FilenameWithoutPath>
<RteFlg>0</RteFlg>
<bShared>0</bShared>
</File>
<File>
<GroupNumber>1</GroupNumber>
<FileNumber>9</FileNumber>
<FileType>5</FileType>
<tvExp>0</tvExp>
<tvExpOptDlg>0</tvExpOptDlg>
<bDave2>0</bDave2>
<PathWithFileName>.\source\pwm.h</PathWithFileName>
<FilenameWithoutPath>pwm.h</FilenameWithoutPath>
<RteFlg>0</RteFlg>
<bShared>0</bShared>
</File>
<File>
<GroupNumber>1</GroupNumber>
<FileNumber>10</FileNumber>
<FileType>5</FileType>
<tvExp>0</tvExp>
<tvExpOptDlg>0</tvExpOptDlg>
<bDave2>0</bDave2>
<PathWithFileName>.\source\timer.h</PathWithFileName>
<FilenameWithoutPath>timer.h</FilenameWithoutPath>
<RteFlg>0</RteFlg>
<bShared>0</bShared>
</File>
<File>
<GroupNumber>1</GroupNumber>
<FileNumber>11</FileNumber>
<FileType>5</FileType>
<tvExp>0</tvExp>
<tvExpOptDlg>0</tvExpOptDlg>
<bDave2>0</bDave2>
<PathWithFileName>.\source\readme.txt</PathWithFileName>
<FilenameWithoutPath>readme.txt</FilenameWithoutPath>
<RteFlg>0</RteFlg>
<bShared>0</bShared>
</File>
</Group>
<Group>
<GroupName>driver</GroupName>
<tvExp>1</tvExp>
<tvExpOptDlg>0</tvExpOptDlg>
<cbSel>0</cbSel>
<RteFlg>0</RteFlg>
<File>
<GroupNumber>2</GroupNumber>
<FileNumber>12</FileNumber>
<FileType>1</FileType>
<tvExp>0</tvExp>
<tvExpOptDlg>0</tvExpOptDlg>
<bDave2>0</bDave2>
<PathWithFileName>..\..\..\components\driver\clock\clock.c</PathWithFileName>
<FilenameWithoutPath>clock.c</FilenameWithoutPath>
<RteFlg>0</RteFlg>
<bShared>0</bShared>
</File>
<File>
<GroupNumber>2</GroupNumber>
<FileNumber>13</FileNumber>
<FileType>1</FileType>
<tvExp>0</tvExp>
<tvExpOptDlg>0</tvExpOptDlg>
<bDave2>0</bDave2>
<PathWithFileName>..\..\..\components\driver\gpio\gpio.c</PathWithFileName>
<FilenameWithoutPath>gpio.c</FilenameWithoutPath>
<RteFlg>0</RteFlg>
<bShared>0</bShared>
</File>
<File>
<GroupNumber>2</GroupNumber>
<FileNumber>14</FileNumber>
<FileType>1</FileType>
<tvExp>0</tvExp>
<tvExpOptDlg>0</tvExpOptDlg>
<bDave2>0</bDave2>
<PathWithFileName>..\..\..\components\driver\log\my_printf.c</PathWithFileName>
<FilenameWithoutPath>my_printf.c</FilenameWithoutPath>
<RteFlg>0</RteFlg>
<bShared>0</bShared>
</File>
<File>
<GroupNumber>2</GroupNumber>
<FileNumber>15</FileNumber>
<FileType>1</FileType>
<tvExp>0</tvExp>
<tvExpOptDlg>0</tvExpOptDlg>
<bDave2>0</bDave2>
<PathWithFileName>..\..\..\components\driver\uart\uart.c</PathWithFileName>
<FilenameWithoutPath>uart.c</FilenameWithoutPath>
<RteFlg>0</RteFlg>
<bShared>0</bShared>
</File>
<File>
<GroupNumber>2</GroupNumber>
<FileNumber>16</FileNumber>
<FileType>1</FileType>
<tvExp>0</tvExp>
<tvExpOptDlg>0</tvExpOptDlg>
<bDave2>0</bDave2>
<PathWithFileName>..\..\..\components\driver\pwrmgr\pwrmgr.c</PathWithFileName>
<FilenameWithoutPath>pwrmgr.c</FilenameWithoutPath>
<RteFlg>0</RteFlg>
<bShared>0</bShared>
</File>
<File>
<GroupNumber>2</GroupNumber>
<FileNumber>17</FileNumber>
<FileType>1</FileType>
<tvExp>0</tvExp>
<tvExpOptDlg>0</tvExpOptDlg>
<bDave2>0</bDave2>
<PathWithFileName>..\..\..\components\driver\flash\flash.c</PathWithFileName>
<FilenameWithoutPath>flash.c</FilenameWithoutPath>
<RteFlg>0</RteFlg>
<bShared>0</bShared>
</File>
</Group>
<Group>
<GroupName>jump</GroupName>
<tvExp>0</tvExp>
<tvExpOptDlg>0</tvExpOptDlg>
<cbSel>0</cbSel>
<RteFlg>0</RteFlg>
<File>
<GroupNumber>3</GroupNumber>
<FileNumber>18</FileNumber>
<FileType>1</FileType>
<tvExp>0</tvExp>
<tvExpOptDlg>0</tvExpOptDlg>
<bDave2>0</bDave2>
<PathWithFileName>..\..\..\misc\jump_table.c</PathWithFileName>
<FilenameWithoutPath>jump_table.c</FilenameWithoutPath>
<RteFlg>0</RteFlg>
<bShared>0</bShared>
</File>
</Group>
<Group>
<GroupName>rf</GroupName>
<tvExp>0</tvExp>
<tvExpOptDlg>0</tvExpOptDlg>
<cbSel>0</cbSel>
<RteFlg>0</RteFlg>
<File>
<GroupNumber>4</GroupNumber>
<FileNumber>19</FileNumber>
<FileType>4</FileType>
<tvExp>0</tvExp>
<tvExpOptDlg>0</tvExpOptDlg>
<bDave2>0</bDave2>
<PathWithFileName>..\..\..\lib\rf.lib</PathWithFileName>
<FilenameWithoutPath>rf.lib</FilenameWithoutPath>
<RteFlg>0</RteFlg>
<bShared>0</bShared>
</File>
</Group>
<Group>
<GroupName>coremark</GroupName>
<tvExp>0</tvExp>
<tvExpOptDlg>0</tvExpOptDlg>
<cbSel>0</cbSel>
<RteFlg>0</RteFlg>
<File>
<GroupNumber>5</GroupNumber>
<FileNumber>20</FileNumber>
<FileType>1</FileType>
<tvExp>0</tvExp>
<tvExpOptDlg>0</tvExpOptDlg>
<bDave2>0</bDave2>
<PathWithFileName>..\..\..\components\coremark\core_list_join.c</PathWithFileName>
<FilenameWithoutPath>core_list_join.c</FilenameWithoutPath>
<RteFlg>0</RteFlg>
<bShared>0</bShared>
</File>
<File>
<GroupNumber>5</GroupNumber>
<FileNumber>21</FileNumber>
<FileType>1</FileType>
<tvExp>0</tvExp>
<tvExpOptDlg>0</tvExpOptDlg>
<bDave2>0</bDave2>
<PathWithFileName>..\..\..\components\coremark\core_main.c</PathWithFileName>
<FilenameWithoutPath>core_main.c</FilenameWithoutPath>
<RteFlg>0</RteFlg>
<bShared>0</bShared>
</File>
<File>
<GroupNumber>5</GroupNumber>
<FileNumber>22</FileNumber>
<FileType>1</FileType>
<tvExp>0</tvExp>
<tvExpOptDlg>0</tvExpOptDlg>
<bDave2>0</bDave2>
<PathWithFileName>..\..\..\components\coremark\core_matrix.c</PathWithFileName>
<FilenameWithoutPath>core_matrix.c</FilenameWithoutPath>
<RteFlg>0</RteFlg>
<bShared>0</bShared>
</File>
<File>
<GroupNumber>5</GroupNumber>
<FileNumber>23</FileNumber>
<FileType>1</FileType>
<tvExp>0</tvExp>
<tvExpOptDlg>0</tvExpOptDlg>
<bDave2>0</bDave2>
<PathWithFileName>..\..\..\components\coremark\core_portme.c</PathWithFileName>
<FilenameWithoutPath>core_portme.c</FilenameWithoutPath>
<RteFlg>0</RteFlg>
<bShared>0</bShared>
</File>
<File>
<GroupNumber>5</GroupNumber>
<FileNumber>24</FileNumber>
<FileType>1</FileType>
<tvExp>0</tvExp>
<tvExpOptDlg>0</tvExpOptDlg>
<bDave2>0</bDave2>
<PathWithFileName>..\..\..\components\coremark\core_state.c</PathWithFileName>
<FilenameWithoutPath>core_state.c</FilenameWithoutPath>
<RteFlg>0</RteFlg>
<bShared>0</bShared>
</File>
<File>
<GroupNumber>5</GroupNumber>
<FileNumber>25</FileNumber>
<FileType>1</FileType>
<tvExp>0</tvExp>
<tvExpOptDlg>0</tvExpOptDlg>
<bDave2>0</bDave2>
<PathWithFileName>..\..\..\components\coremark\core_util.c</PathWithFileName>
<FilenameWithoutPath>core_util.c</FilenameWithoutPath>
<RteFlg>0</RteFlg>
<bShared>0</bShared>
</File>
</Group>
<Group>
<GroupName>cli</GroupName>
<tvExp>0</tvExp>
<tvExpOptDlg>0</tvExpOptDlg>
<cbSel>0</cbSel>
<RteFlg>0</RteFlg>
<File>
<GroupNumber>6</GroupNumber>
<FileNumber>26</FileNumber>
<FileType>1</FileType>
<tvExp>0</tvExp>
<tvExpOptDlg>0</tvExpOptDlg>
<bDave2>0</bDave2>
<PathWithFileName>..\..\..\components\libraries\cliface\cliface.c</PathWithFileName>
<FilenameWithoutPath>cliface.c</FilenameWithoutPath>
<RteFlg>0</RteFlg>
<bShared>0</bShared>
</File>
</Group>
<Group>
<GroupName>::CMSIS</GroupName>
<tvExp>0</tvExp>
<tvExpOptDlg>0</tvExpOptDlg>
<cbSel>0</cbSel>
<RteFlg>1</RteFlg>
</Group>
<Group>
<GroupName>::Device</GroupName>
<tvExp>0</tvExp>
<tvExpOptDlg>0</tvExpOptDlg>
<cbSel>0</cbSel>
<RteFlg>1</RteFlg>
</Group>
</ProjectOpt>

View File

@ -0,0 +1,750 @@
<?xml version="1.0" encoding="UTF-8" standalone="no" ?>
<Project xmlns:xsi="http://www.w3.org/2001/XMLSchema-instance" xsi:noNamespaceSchemaLocation="project_projx.xsd">
<SchemaVersion>2.1</SchemaVersion>
<Header>### uVision Project, (C) Keil Software</Header>
<Targets>
<Target>
<TargetName>adc</TargetName>
<ToolsetNumber>0x4</ToolsetNumber>
<ToolsetName>ARM-ADS</ToolsetName>
<pCCUsed>5060750::V5.06 update 6 (build 750)::ARMCC</pCCUsed>
<uAC6>0</uAC6>
<TargetOption>
<TargetCommonOption>
<Device>ARMCM0</Device>
<Vendor>ARM</Vendor>
<PackID>ARM.CMSIS.5.6.0</PackID>
<PackURL>http://www.keil.com/pack/</PackURL>
<Cpu>IRAM(0x20000000,0x20000) IROM(0x00000000,0x40000) CPUTYPE("Cortex-M0") CLOCK(12000000) ESEL ELITTLE</Cpu>
<FlashUtilSpec></FlashUtilSpec>
<StartupFile></StartupFile>
<FlashDriverDll>UL2CM3(-S0 -C0 -P0 -FD20000000 -FC1000 -FN1 -FF0NEW_DEVICE -FS00 -FL040000 -FP0($$Device:ARMCM0$Device\ARM\Flash\NEW_DEVICE.FLM))</FlashDriverDll>
<DeviceId>0</DeviceId>
<RegisterFile>$$Device:ARMCM0$Device\ARM\ARMCM0\Include\ARMCM0.h</RegisterFile>
<MemoryEnv></MemoryEnv>
<Cmp></Cmp>
<Asm></Asm>
<Linker></Linker>
<OHString></OHString>
<InfinionOptionDll></InfinionOptionDll>
<SLE66CMisc></SLE66CMisc>
<SLE66AMisc></SLE66AMisc>
<SLE66LinkerMisc></SLE66LinkerMisc>
<SFDFile>$$Device:ARMCM0$Device\ARM\SVD\ARMCM0.svd</SFDFile>
<bCustSvd>0</bCustSvd>
<UseEnv>0</UseEnv>
<BinPath></BinPath>
<IncludePath></IncludePath>
<LibPath></LibPath>
<RegisterFilePath></RegisterFilePath>
<DBRegisterFilePath></DBRegisterFilePath>
<TargetStatus>
<Error>0</Error>
<ExitCodeStop>0</ExitCodeStop>
<ButtonStop>0</ButtonStop>
<NotGenerated>0</NotGenerated>
<InvalidFlash>1</InvalidFlash>
</TargetStatus>
<OutputDirectory>.\Objects\</OutputDirectory>
<OutputName>adc</OutputName>
<CreateExecutable>1</CreateExecutable>
<CreateLib>0</CreateLib>
<CreateHexFile>1</CreateHexFile>
<DebugInformation>1</DebugInformation>
<BrowseInformation>1</BrowseInformation>
<ListingPath>.\Listings\</ListingPath>
<HexFormatSelection>1</HexFormatSelection>
<Merge32K>0</Merge32K>
<CreateBatchFile>0</CreateBatchFile>
<BeforeCompile>
<RunUserProg1>0</RunUserProg1>
<RunUserProg2>0</RunUserProg2>
<UserProg1Name></UserProg1Name>
<UserProg2Name></UserProg2Name>
<UserProg1Dos16Mode>0</UserProg1Dos16Mode>
<UserProg2Dos16Mode>0</UserProg2Dos16Mode>
<nStopU1X>0</nStopU1X>
<nStopU2X>0</nStopU2X>
</BeforeCompile>
<BeforeMake>
<RunUserProg1>0</RunUserProg1>
<RunUserProg2>0</RunUserProg2>
<UserProg1Name></UserProg1Name>
<UserProg2Name></UserProg2Name>
<UserProg1Dos16Mode>0</UserProg1Dos16Mode>
<UserProg2Dos16Mode>0</UserProg2Dos16Mode>
<nStopB1X>0</nStopB1X>
<nStopB2X>0</nStopB2X>
</BeforeMake>
<AfterMake>
<RunUserProg1>1</RunUserProg1>
<RunUserProg2>1</RunUserProg2>
<UserProg1Name>fromelf.exe --bin -o ./bin ./Objects/adc.axf</UserProg1Name>
<UserProg2Name>fromelf.exe .\Objects\adc.axf --i32combined --output .\bin\adc.hex</UserProg2Name>
<UserProg1Dos16Mode>0</UserProg1Dos16Mode>
<UserProg2Dos16Mode>0</UserProg2Dos16Mode>
<nStopA1X>0</nStopA1X>
<nStopA2X>0</nStopA2X>
</AfterMake>
<SelectedForBatchBuild>0</SelectedForBatchBuild>
<SVCSIdString></SVCSIdString>
</TargetCommonOption>
<CommonProperty>
<UseCPPCompiler>0</UseCPPCompiler>
<RVCTCodeConst>0</RVCTCodeConst>
<RVCTZI>0</RVCTZI>
<RVCTOtherData>0</RVCTOtherData>
<ModuleSelection>0</ModuleSelection>
<IncludeInBuild>1</IncludeInBuild>
<AlwaysBuild>0</AlwaysBuild>
<GenerateAssemblyFile>0</GenerateAssemblyFile>
<AssembleAssemblyFile>0</AssembleAssemblyFile>
<PublicsOnly>0</PublicsOnly>
<StopOnExitCode>3</StopOnExitCode>
<CustomArgument></CustomArgument>
<IncludeLibraryModules></IncludeLibraryModules>
<ComprImg>1</ComprImg>
</CommonProperty>
<DllOption>
<SimDllName>SARMCM3.DLL</SimDllName>
<SimDllArguments> </SimDllArguments>
<SimDlgDll>DARMCM1.DLL</SimDlgDll>
<SimDlgDllArguments>-pCM0</SimDlgDllArguments>
<TargetDllName>SARMCM3.DLL</TargetDllName>
<TargetDllArguments> </TargetDllArguments>
<TargetDlgDll>TARMCM1.DLL</TargetDlgDll>
<TargetDlgDllArguments>-pCM0</TargetDlgDllArguments>
</DllOption>
<DebugOption>
<OPTHX>
<HexSelection>1</HexSelection>
<HexRangeLowAddress>0</HexRangeLowAddress>
<HexRangeHighAddress>0</HexRangeHighAddress>
<HexOffset>0</HexOffset>
<Oh166RecLen>16</Oh166RecLen>
</OPTHX>
</DebugOption>
<Utilities>
<Flash1>
<UseTargetDll>1</UseTargetDll>
<UseExternalTool>0</UseExternalTool>
<RunIndependent>0</RunIndependent>
<UpdateFlashBeforeDebugging>1</UpdateFlashBeforeDebugging>
<Capability>1</Capability>
<DriverSelection>4096</DriverSelection>
</Flash1>
<bUseTDR>1</bUseTDR>
<Flash2>BIN\UL2CM3.DLL</Flash2>
<Flash3>"" ()</Flash3>
<Flash4>.\ram.ini</Flash4>
<pFcarmOut></pFcarmOut>
<pFcarmGrp></pFcarmGrp>
<pFcArmRoot></pFcArmRoot>
<FcArmLst>0</FcArmLst>
</Utilities>
<TargetArmAds>
<ArmAdsMisc>
<GenerateListings>0</GenerateListings>
<asHll>1</asHll>
<asAsm>1</asAsm>
<asMacX>1</asMacX>
<asSyms>1</asSyms>
<asFals>1</asFals>
<asDbgD>1</asDbgD>
<asForm>1</asForm>
<ldLst>0</ldLst>
<ldmm>1</ldmm>
<ldXref>1</ldXref>
<BigEnd>0</BigEnd>
<AdsALst>1</AdsALst>
<AdsACrf>1</AdsACrf>
<AdsANop>0</AdsANop>
<AdsANot>0</AdsANot>
<AdsLLst>1</AdsLLst>
<AdsLmap>1</AdsLmap>
<AdsLcgr>1</AdsLcgr>
<AdsLsym>1</AdsLsym>
<AdsLszi>1</AdsLszi>
<AdsLtoi>1</AdsLtoi>
<AdsLsun>1</AdsLsun>
<AdsLven>1</AdsLven>
<AdsLsxf>1</AdsLsxf>
<RvctClst>0</RvctClst>
<GenPPlst>0</GenPPlst>
<AdsCpuType>"Cortex-M0"</AdsCpuType>
<RvctDeviceName></RvctDeviceName>
<mOS>0</mOS>
<uocRom>0</uocRom>
<uocRam>0</uocRam>
<hadIROM>1</hadIROM>
<hadIRAM>1</hadIRAM>
<hadXRAM>0</hadXRAM>
<uocXRam>0</uocXRam>
<RvdsVP>0</RvdsVP>
<RvdsMve>0</RvdsMve>
<hadIRAM2>0</hadIRAM2>
<hadIROM2>0</hadIROM2>
<StupSel>8</StupSel>
<useUlib>1</useUlib>
<EndSel>1</EndSel>
<uLtcg>0</uLtcg>
<nSecure>0</nSecure>
<RoSelD>3</RoSelD>
<RwSelD>3</RwSelD>
<CodeSel>0</CodeSel>
<OptFeed>0</OptFeed>
<NoZi1>0</NoZi1>
<NoZi2>0</NoZi2>
<NoZi3>0</NoZi3>
<NoZi4>0</NoZi4>
<NoZi5>0</NoZi5>
<Ro1Chk>0</Ro1Chk>
<Ro2Chk>0</Ro2Chk>
<Ro3Chk>0</Ro3Chk>
<Ir1Chk>0</Ir1Chk>
<Ir2Chk>0</Ir2Chk>
<Ra1Chk>0</Ra1Chk>
<Ra2Chk>0</Ra2Chk>
<Ra3Chk>0</Ra3Chk>
<Im1Chk>0</Im1Chk>
<Im2Chk>0</Im2Chk>
<OnChipMemories>
<Ocm1>
<Type>0</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</Ocm1>
<Ocm2>
<Type>0</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</Ocm2>
<Ocm3>
<Type>0</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</Ocm3>
<Ocm4>
<Type>0</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</Ocm4>
<Ocm5>
<Type>0</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</Ocm5>
<Ocm6>
<Type>0</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</Ocm6>
<IRAM>
<Type>0</Type>
<StartAddress>0x20000000</StartAddress>
<Size>0x20000</Size>
</IRAM>
<IROM>
<Type>1</Type>
<StartAddress>0x0</StartAddress>
<Size>0x40000</Size>
</IROM>
<XRAM>
<Type>0</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</XRAM>
<OCR_RVCT1>
<Type>1</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</OCR_RVCT1>
<OCR_RVCT2>
<Type>1</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</OCR_RVCT2>
<OCR_RVCT3>
<Type>1</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</OCR_RVCT3>
<OCR_RVCT4>
<Type>1</Type>
<StartAddress>0x20000000</StartAddress>
<Size>0x400</Size>
</OCR_RVCT4>
<OCR_RVCT5>
<Type>1</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</OCR_RVCT5>
<OCR_RVCT6>
<Type>0</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</OCR_RVCT6>
<OCR_RVCT7>
<Type>0</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</OCR_RVCT7>
<OCR_RVCT8>
<Type>0</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</OCR_RVCT8>
<OCR_RVCT9>
<Type>0</Type>
<StartAddress>0x1fff1000</StartAddress>
<Size>0x3800</Size>
</OCR_RVCT9>
<OCR_RVCT10>
<Type>0</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</OCR_RVCT10>
</OnChipMemories>
<RvctStartVector></RvctStartVector>
</ArmAdsMisc>
<Cads>
<interw>1</interw>
<Optim>4</Optim>
<oTime>0</oTime>
<SplitLS>0</SplitLS>
<OneElfS>1</OneElfS>
<Strict>0</Strict>
<EnumInt>0</EnumInt>
<PlainCh>0</PlainCh>
<Ropi>0</Ropi>
<Rwpi>0</Rwpi>
<wLevel>2</wLevel>
<uThumb>0</uThumb>
<uSurpInc>0</uSurpInc>
<uC99>1</uC99>
<uGnu>0</uGnu>
<useXO>0</useXO>
<v6Lang>1</v6Lang>
<v6LangP>1</v6LangP>
<vShortEn>1</vShortEn>
<vShortWch>1</vShortWch>
<v6Lto>0</v6Lto>
<v6WtE>0</v6WtE>
<v6Rtti>0</v6Rtti>
<VariousControls>
<MiscControls>-DADV_NCONN_CFG=0x01 -DADV_CONN_CFG=0x02 -DSCAN_CFG=0x04 -DINIT_CFG=0x08 -DBROADCASTER_CFG=0x01 -DOBSERVER_CFG=0x02 -DPERIPHERAL_CFG=0x04 -DCENTRAL_CFG=0x08 -DHOST_CONFIG=0xc</MiscControls>
<Define>CFG_CP HCI_TL_NONE=1 OSALMEM_METRICS=0 PHY_MCU_TYPE=MCU_BUMBEE_M0 MAIN_HAS_NOARGC MAIN_HAS_NORETURN DEBUG_INFO=1 CFG_SLEEP_MODE=PWR_MODE_SLEEP</Define>
<Undefine></Undefine>
<IncludePath>..\..\..\components\inc;.\source;..\..\..\components\driver\clock;..\..\..\components\driver\gpio;..\..\..\components\arch\cm0;..\..\..\components\ble\include;..\..\..\components\ble\controller;..\..\..\components\ble\hci;..\..\..\components\ble\host;..\..\..\components\libraries\secure;..\..\..\components\osal\include;..\..\..\misc;..\..\..\components\driver\uart;..\..\..\components\driver\log;..\..\..\components\driver\adc;..\..\..\components\driver\pwrmgr;..\..\..\components\driver\timer;..\..\..\components\driver\spi;..\..\..\components\libraries\cliface;..\..\..\components\driver\pwm;..\..\..\components\driver\kscan;..\..\..\components\driver\dma;..\..\..\components\driver\flash;..\..\..\components\driver\spiflash;..\..\..\components\driver\watchdog;.\source</IncludePath>
</VariousControls>
</Cads>
<Aads>
<interw>1</interw>
<Ropi>0</Ropi>
<Rwpi>0</Rwpi>
<thumb>0</thumb>
<SplitLS>0</SplitLS>
<SwStkChk>0</SwStkChk>
<NoWarn>0</NoWarn>
<uSurpInc>0</uSurpInc>
<useXO>0</useXO>
<uClangAs>0</uClangAs>
<VariousControls>
<MiscControls></MiscControls>
<Define></Define>
<Undefine></Undefine>
<IncludePath></IncludePath>
</VariousControls>
</Aads>
<LDads>
<umfTarg>0</umfTarg>
<Ropi>0</Ropi>
<Rwpi>0</Rwpi>
<noStLib>0</noStLib>
<RepFail>0</RepFail>
<useFile>0</useFile>
<TextAddressRange>0</TextAddressRange>
<DataAddressRange>0</DataAddressRange>
<pXoBase></pXoBase>
<ScatterFile>.\adc.sct</ScatterFile>
<IncludeLibs></IncludeLibs>
<IncludeLibsPath></IncludeLibsPath>
<Misc>..\..\..\misc\bb_rom_sym_m0.txt --keep=jump_table_base --keep=global_config</Misc>
<LinkerInputFile></LinkerInputFile>
<DisabledWarnings></DisabledWarnings>
</LDads>
</TargetArmAds>
</TargetOption>
<Groups>
<Group>
<GroupName>main</GroupName>
<Files>
<File>
<FileName>main.c</FileName>
<FileType>1</FileType>
<FilePath>.\source\main.c</FilePath>
</File>
<File>
<FileName>adc_demo.c</FileName>
<FileType>1</FileType>
<FilePath>.\source\adc_demo.c</FilePath>
</File>
<File>
<FileName>adc_Main.c</FileName>
<FileType>1</FileType>
<FilePath>.\source\adc_Main.c</FilePath>
</File>
<File>
<FileName>OSAL_adc.c</FileName>
<FileType>1</FileType>
<FilePath>.\source\OSAL_adc.c</FilePath>
</File>
<File>
<FileName>adc.c</FileName>
<FileType>1</FileType>
<FilePath>.\source\adc.c</FilePath>
</File>
<File>
<FileName>adc.h</FileName>
<FileType>5</FileType>
<FilePath>.\source\adc.h</FilePath>
</File>
<File>
<FileName>timer.c</FileName>
<FileType>1</FileType>
<FilePath>.\source\timer.c</FilePath>
</File>
<File>
<FileName>pwm.c</FileName>
<FileType>1</FileType>
<FilePath>.\source\pwm.c</FilePath>
</File>
<File>
<FileName>pwm.h</FileName>
<FileType>5</FileType>
<FilePath>.\source\pwm.h</FilePath>
</File>
<File>
<FileName>timer.h</FileName>
<FileType>5</FileType>
<FilePath>.\source\timer.h</FilePath>
</File>
<File>
<FileName>readme.txt</FileName>
<FileType>5</FileType>
<FilePath>.\source\readme.txt</FilePath>
</File>
</Files>
</Group>
<Group>
<GroupName>driver</GroupName>
<Files>
<File>
<FileName>clock.c</FileName>
<FileType>1</FileType>
<FilePath>..\..\..\components\driver\clock\clock.c</FilePath>
</File>
<File>
<FileName>gpio.c</FileName>
<FileType>1</FileType>
<FilePath>..\..\..\components\driver\gpio\gpio.c</FilePath>
</File>
<File>
<FileName>my_printf.c</FileName>
<FileType>1</FileType>
<FilePath>..\..\..\components\driver\log\my_printf.c</FilePath>
</File>
<File>
<FileName>uart.c</FileName>
<FileType>1</FileType>
<FilePath>..\..\..\components\driver\uart\uart.c</FilePath>
</File>
<File>
<FileName>pwrmgr.c</FileName>
<FileType>1</FileType>
<FilePath>..\..\..\components\driver\pwrmgr\pwrmgr.c</FilePath>
</File>
<File>
<FileName>flash.c</FileName>
<FileType>1</FileType>
<FilePath>..\..\..\components\driver\flash\flash.c</FilePath>
</File>
</Files>
</Group>
<Group>
<GroupName>jump</GroupName>
<Files>
<File>
<FileName>jump_table.c</FileName>
<FileType>1</FileType>
<FilePath>..\..\..\misc\jump_table.c</FilePath>
</File>
</Files>
</Group>
<Group>
<GroupName>rf</GroupName>
<Files>
<File>
<FileName>rf.lib</FileName>
<FileType>4</FileType>
<FilePath>..\..\..\lib\rf.lib</FilePath>
</File>
</Files>
</Group>
<Group>
<GroupName>coremark</GroupName>
<GroupOption>
<CommonProperty>
<UseCPPCompiler>0</UseCPPCompiler>
<RVCTCodeConst>0</RVCTCodeConst>
<RVCTZI>0</RVCTZI>
<RVCTOtherData>0</RVCTOtherData>
<ModuleSelection>0</ModuleSelection>
<IncludeInBuild>0</IncludeInBuild>
<AlwaysBuild>2</AlwaysBuild>
<GenerateAssemblyFile>2</GenerateAssemblyFile>
<AssembleAssemblyFile>2</AssembleAssemblyFile>
<PublicsOnly>2</PublicsOnly>
<StopOnExitCode>11</StopOnExitCode>
<CustomArgument></CustomArgument>
<IncludeLibraryModules></IncludeLibraryModules>
<ComprImg>1</ComprImg>
</CommonProperty>
<GroupArmAds>
<Cads>
<interw>2</interw>
<Optim>0</Optim>
<oTime>2</oTime>
<SplitLS>2</SplitLS>
<OneElfS>2</OneElfS>
<Strict>2</Strict>
<EnumInt>2</EnumInt>
<PlainCh>2</PlainCh>
<Ropi>2</Ropi>
<Rwpi>2</Rwpi>
<wLevel>0</wLevel>
<uThumb>2</uThumb>
<uSurpInc>2</uSurpInc>
<uC99>2</uC99>
<uGnu>2</uGnu>
<useXO>2</useXO>
<v6Lang>0</v6Lang>
<v6LangP>0</v6LangP>
<vShortEn>2</vShortEn>
<vShortWch>2</vShortWch>
<v6Lto>2</v6Lto>
<v6WtE>2</v6WtE>
<v6Rtti>2</v6Rtti>
<VariousControls>
<MiscControls></MiscControls>
<Define></Define>
<Undefine></Undefine>
<IncludePath></IncludePath>
</VariousControls>
</Cads>
<Aads>
<interw>2</interw>
<Ropi>2</Ropi>
<Rwpi>2</Rwpi>
<thumb>2</thumb>
<SplitLS>2</SplitLS>
<SwStkChk>2</SwStkChk>
<NoWarn>2</NoWarn>
<uSurpInc>2</uSurpInc>
<useXO>2</useXO>
<uClangAs>2</uClangAs>
<VariousControls>
<MiscControls></MiscControls>
<Define></Define>
<Undefine></Undefine>
<IncludePath></IncludePath>
</VariousControls>
</Aads>
</GroupArmAds>
</GroupOption>
<Files>
<File>
<FileName>core_list_join.c</FileName>
<FileType>1</FileType>
<FilePath>..\..\..\components\coremark\core_list_join.c</FilePath>
</File>
<File>
<FileName>core_main.c</FileName>
<FileType>1</FileType>
<FilePath>..\..\..\components\coremark\core_main.c</FilePath>
</File>
<File>
<FileName>core_matrix.c</FileName>
<FileType>1</FileType>
<FilePath>..\..\..\components\coremark\core_matrix.c</FilePath>
</File>
<File>
<FileName>core_portme.c</FileName>
<FileType>1</FileType>
<FilePath>..\..\..\components\coremark\core_portme.c</FilePath>
</File>
<File>
<FileName>core_state.c</FileName>
<FileType>1</FileType>
<FilePath>..\..\..\components\coremark\core_state.c</FilePath>
</File>
<File>
<FileName>core_util.c</FileName>
<FileType>1</FileType>
<FilePath>..\..\..\components\coremark\core_util.c</FilePath>
</File>
</Files>
</Group>
<Group>
<GroupName>cli</GroupName>
<GroupOption>
<CommonProperty>
<UseCPPCompiler>0</UseCPPCompiler>
<RVCTCodeConst>0</RVCTCodeConst>
<RVCTZI>0</RVCTZI>
<RVCTOtherData>0</RVCTOtherData>
<ModuleSelection>0</ModuleSelection>
<IncludeInBuild>0</IncludeInBuild>
<AlwaysBuild>2</AlwaysBuild>
<GenerateAssemblyFile>2</GenerateAssemblyFile>
<AssembleAssemblyFile>2</AssembleAssemblyFile>
<PublicsOnly>2</PublicsOnly>
<StopOnExitCode>11</StopOnExitCode>
<CustomArgument></CustomArgument>
<IncludeLibraryModules></IncludeLibraryModules>
<ComprImg>1</ComprImg>
</CommonProperty>
<GroupArmAds>
<Cads>
<interw>2</interw>
<Optim>0</Optim>
<oTime>2</oTime>
<SplitLS>2</SplitLS>
<OneElfS>2</OneElfS>
<Strict>2</Strict>
<EnumInt>2</EnumInt>
<PlainCh>2</PlainCh>
<Ropi>2</Ropi>
<Rwpi>2</Rwpi>
<wLevel>0</wLevel>
<uThumb>2</uThumb>
<uSurpInc>2</uSurpInc>
<uC99>2</uC99>
<uGnu>2</uGnu>
<useXO>2</useXO>
<v6Lang>0</v6Lang>
<v6LangP>0</v6LangP>
<vShortEn>2</vShortEn>
<vShortWch>2</vShortWch>
<v6Lto>2</v6Lto>
<v6WtE>2</v6WtE>
<v6Rtti>2</v6Rtti>
<VariousControls>
<MiscControls></MiscControls>
<Define></Define>
<Undefine></Undefine>
<IncludePath></IncludePath>
</VariousControls>
</Cads>
<Aads>
<interw>2</interw>
<Ropi>2</Ropi>
<Rwpi>2</Rwpi>
<thumb>2</thumb>
<SplitLS>2</SplitLS>
<SwStkChk>2</SwStkChk>
<NoWarn>2</NoWarn>
<uSurpInc>2</uSurpInc>
<useXO>2</useXO>
<uClangAs>2</uClangAs>
<VariousControls>
<MiscControls></MiscControls>
<Define></Define>
<Undefine></Undefine>
<IncludePath></IncludePath>
</VariousControls>
</Aads>
</GroupArmAds>
</GroupOption>
<Files>
<File>
<FileName>cliface.c</FileName>
<FileType>1</FileType>
<FilePath>..\..\..\components\libraries\cliface\cliface.c</FilePath>
</File>
</Files>
</Group>
<Group>
<GroupName>::CMSIS</GroupName>
</Group>
<Group>
<GroupName>::Device</GroupName>
</Group>
</Groups>
</Target>
</Targets>
<RTE>
<apis/>
<components>
<component Cclass="CMSIS" Cgroup="CORE" Cvendor="ARM" Cversion="4.3.0" condition="Cortex-M Device">
<package name="CMSIS" schemaVersion="1.3" url="http://www.keil.com/pack/" vendor="ARM" version="4.5.0"/>
<targetInfos>
<targetInfo name="adc"/>
</targetInfos>
</component>
<component Cclass="Device" Cgroup="Startup" Cvendor="ARM" Cversion="1.0.1" condition="ARMCM0 CMSIS">
<package name="CMSIS" schemaVersion="1.3" url="http://www.keil.com/pack/" vendor="ARM" version="4.5.0"/>
<targetInfos>
<targetInfo name="adc"/>
</targetInfos>
</component>
</components>
<files>
<file attr="config" category="sourceAsm" condition="ARMCC" name="Device\ARM\ARMCM0\Source\ARM\startup_ARMCM0.s" version="1.0.0">
<instance index="0">RTE\Device\ARMCM0\startup_ARMCM0.s</instance>
<component Cclass="Device" Cgroup="Startup" Cvendor="ARM" Cversion="1.2.0" condition="ARMCM0 CMSIS"/>
<package name="CMSIS" schemaVersion="1.3" url="http://www.keil.com/pack/" vendor="ARM" version="5.6.0"/>
<targetInfos>
<targetInfo name="adc"/>
</targetInfos>
</file>
<file attr="config" category="sourceC" name="Device\ARM\ARMCM0\Source\system_ARMCM0.c" version="1.0.0">
<instance index="0">RTE\Device\ARMCM0\system_ARMCM0.c</instance>
<component Cclass="Device" Cgroup="Startup" Cvendor="ARM" Cversion="1.2.0" condition="ARMCM0 CMSIS"/>
<package name="CMSIS" schemaVersion="1.3" url="http://www.keil.com/pack/" vendor="ARM" version="5.6.0"/>
<targetInfos>
<targetInfo name="adc"/>
</targetInfos>
</file>
<file attr="config" category="sourceAsm" condition="ARMCC" name="Device\ARM\ARMCM4\Source\ARM\startup_ARMCM4.s" version="1.0.0">
<instance index="0" removed="1">RTE\Device\ARMCM4\startup_ARMCM4.s</instance>
<component Cclass="Device" Cgroup="Startup" Cvendor="ARM" Cversion="1.0.1" condition="ARMCM4 CMSIS"/>
<package name="CMSIS" schemaVersion="1.3" url="http://www.keil.com/pack/" vendor="ARM" version="4.5.0"/>
<targetInfos/>
</file>
<file attr="config" category="sourceC" name="Device\ARM\ARMCM4\Source\system_ARMCM4.c" version="1.0.0">
<instance index="0" removed="1">RTE\Device\ARMCM4\system_ARMCM4.c</instance>
<component Cclass="Device" Cgroup="Startup" Cvendor="ARM" Cversion="1.0.1" condition="ARMCM4 CMSIS"/>
<package name="CMSIS" schemaVersion="1.3" url="http://www.keil.com/pack/" vendor="ARM" version="4.5.0"/>
<targetInfos/>
</file>
<file attr="config" category="sourceAsm" condition="ARMCC" name="Device\ARM\ARMCM4\Source\ARM\startup_ARMCM4.s" version="1.0.0">
<instance index="0" removed="1">RTE\Device\ARMCM4_FP\startup_ARMCM4.s</instance>
<component Cclass="Device" Cgroup="Startup" Cvendor="ARM" Cversion="1.0.1" condition="ARMCM4 CMSIS"/>
<package name="CMSIS" schemaVersion="1.3" url="http://www.keil.com/pack/" vendor="ARM" version="4.5.0"/>
<targetInfos/>
</file>
<file attr="config" category="sourceC" name="Device\ARM\ARMCM4\Source\system_ARMCM4.c" version="1.0.0">
<instance index="0" removed="1">RTE\Device\ARMCM4_FP\system_ARMCM4.c</instance>
<component Cclass="Device" Cgroup="Startup" Cvendor="ARM" Cversion="1.0.1" condition="ARMCM4 CMSIS"/>
<package name="CMSIS" schemaVersion="1.3" url="http://www.keil.com/pack/" vendor="ARM" version="4.5.0"/>
<targetInfos/>
</file>
</files>
</RTE>
</Project>

View File

@ -0,0 +1,10 @@
FUNC void Setup(void) {
_WDWORD(0x4000f0a8, 0x00000000);
SP = _RDWORD(0x1fff1838);
PC = _RDWORD(0x1fff183c);
_WDWORD(0x4000f0cc, 0x1fff1839);
}
LOAD .\Objects\adc.axf INCREMENTAL
Setup();

View File

@ -0,0 +1,56 @@
FUNC void EraseChip(void) {
unsigned long position;
unsigned long wait;
unsigned long i;
i = 6;
do
{
wait = 0x100;
_WDWORD(0x4000c890, 0x06000001);
while(wait--);
wait = 0x100000;
_WDWORD(0x4000c894, i*0x1000+0x1000);
_WDWORD(0x4000c890, 0x200a0001);
i--;
while(wait--);
}while(i!=0);
wait = 0x100;
_WDWORD(0x4000c890, 0x06000001);
while(wait--);
wait = 0x300000;
_WDWORD(0x4000c894, 0x8000);
_WDWORD(0x4000c890, 0x520a0001);
while(wait--);
i = 7;
do
{
wait = 0x100;
_WDWORD(0x4000c890, 0x06000001);
while(wait--);
wait = 0x300000;
_WDWORD(0x4000c894, i*0x10000);
_WDWORD(0x4000c890, 0xd80a0001);
i--;
while(wait--);
}while(i!=0);
}
FUNC void Setup(void) {
_WDWORD(0x4000f0a8, 0x00000000);
// SP = _RDWORD(0x1fff2000);
// PC = _RDWORD(0x1fff2004);
SP = _RDWORD(0x0);
PC = _RDWORD(0x4);
// _WDWORD(0x4000f0cc, 0x1fff2001);
}
EraseChip();
LOAD .\Objects\adc.axf NOCODE
LOAD .\Objects\adc.hexf
Setup();

View File

@ -0,0 +1,50 @@
; *************************************************************
; *** Scatter-Loading Description File generated by uVision ***
; *************************************************************
LR_IROM1 0x1fff1838 0x000E7C8 { ; load region size_region
ER_IROM1 0x1fff1838 0x000E7C8 { ; load address = execution address
*.o (RESET, +First)
*(InRoot$$Sections)
*.o(_section_sram_code_)
.ANY (+RO)
.ANY (+RW +ZI)
}
}
LR_ROM_JT_GC 0x1fff0000 0x00800 {
JUMP_TABLE 0x1fff0000 0x00400 {
.ANY (jump_table_mem_area)
}
GOLBAL_CONFIG 0x1fff0400 0x00400 {
.ANY (global_config_area)
}
}
LR_ROM_XIP 0x11020000 0x030000 {
ER_ROM_XIP 0x11020000 0x030000 { ; load address = execution address
;libethermind_mesh_models.o(+RO)
;libethermind_utils.o(+RO)
;libethermind_mesh_core.o(+RO)
;appl_*.o(+RO)
;;;;;
;devinfoservice.o(+RO)
gatt*.o(+RO)
gattservapp.o(+RO)
l2cap*.o(+RO)
att*.o(+RO)
linkdb.o(+RO)
sm*.o(+RO)
gap*.o(+RO)
simpleblecentral.o(+RO)
central.o(+RO)
;observer.o(+RO)
*.o(_section_xip_code_)
}
}

View File

@ -0,0 +1,63 @@
/**************************************************************************************************
THIS IS EMPTY HEADER
**************************************************************************************************/
/**************************************************************************************************
Filename: OSAL_heartrate.c
Revised: $Date: 2011-03-30 20:15:59 -0700 (Wed, 30 Mar 2011) $
Revision: $Revision: 16 $
**************************************************************************************************/
/**************************************************************************************************
INCLUDES
**************************************************************************************************/
#include "rom_sym_def.h"
#include "OSAL.h"
#include "OSAL_Tasks.h"
#include "ll.h"
/* Application */
#include "adc_demo.h"
/*********************************************************************
GLOBAL VARIABLES
*/
// The order in this table must be identical to the task initialization calls below in osalInitTask.
const pTaskEventHandlerFn tasksArr[] =
{
LL_ProcessEvent,
adc_ProcessEvent
};
const uint8 tasksCnt = sizeof( tasksArr ) / sizeof( tasksArr[0] );
uint16* tasksEvents;
/*********************************************************************
FUNCTIONS
*********************************************************************/
/*********************************************************************
@fn osalInitTasks
@brief This function invokes the initialization function for each task.
@param void
@return none
*/
void osalInitTasks( void )
{
uint8 taskID = 0;
tasksEvents = (uint16*)osal_mem_alloc( sizeof( uint16 ) * tasksCnt);
osal_memset( tasksEvents, 0, (sizeof( uint16 ) * tasksCnt));
LL_Init( taskID++);
/*
Application
*/
adc_Init( taskID );
}
/*********************************************************************
*********************************************************************/

View File

@ -0,0 +1,700 @@
/**************************************************************************************************
*******
**************************************************************************************************/
/*******************************************************************************
@file adc.c
@brief Contains all functions support for adc driver
@version 0.0
@date 18. Oct. 2017
@author qing.han
*******************************************************************************/
#include <string.h>
#include "error.h"
#include "gpio.h"
#include "pwrmgr.h"
#include "clock.h"
#include "adc.h"
#include "log.h"
#include "jump_function.h"
#include "version.h"
static bool mAdc_init_flg = FALSE;
static adc_Ctx_t mAdc_Ctx;
static uint8_t adc_cal_read_flag = 0;
static uint16_t adc_cal_postive = 0x0fff;
static uint16_t adc_cal_negtive = 0x0fff;
gpio_pin_e s_pinmap[ADC_CH_NUM] =
{
GPIO_DUMMY, //ADC_CH0 =0,
GPIO_DUMMY, //ADC_CH1 =1,
P11, //ADC_CH1N =2,
P23, //ADC_CH1P =3, ADC_CH1DIFF = 3,
P24, //ADC_CH2N =4,
P14, //ADC_CH2P =5, ADC_CH2DIFF = 5,
P15, //ADC_CH3N =6,
P20, //ADC_CH3P =7, ADC_CH3DIFF = 7,
GPIO_DUMMY, //ADC_CH_VOICE =8,
};
static void set_sampling_resolution(adc_CH_t channel, bool is_high_resolution,bool is_differential_mode)
{
uint8_t aio = 0;
uint8_t diff_aio = 0;
switch(channel)
{
case ADC_CH1N_P11:
aio = 0;
diff_aio = 1;
break;
case ADC_CH1P_P23:
aio = 1;
diff_aio = 0;
break;
case ADC_CH2N_P24:
aio = 2;
diff_aio = 3;
break;
case ADC_CH2P_P14:
aio = 3;
diff_aio = 2;
break;
case ADC_CH3N_P15:
aio = 4;
diff_aio = 7;
break;
case ADC_CH3P_P20:
aio = 7;
diff_aio = 4;
break;
default:
return;
}
if(is_high_resolution)
{
if(is_differential_mode)
{
subWriteReg(&(AP_AON->PMCTL2_1),(diff_aio+8),(diff_aio+8),0);
subWriteReg(&(AP_AON->PMCTL2_1),diff_aio,diff_aio,1);
}
subWriteReg(&(AP_AON->PMCTL2_1),(aio+8),(aio+8),0);
subWriteReg(&(AP_AON->PMCTL2_1),aio,aio,1);
}
else
{
if(is_differential_mode)
{
subWriteReg(&(AP_AON->PMCTL2_1),(diff_aio+8),(diff_aio+8),1);
subWriteReg(&(AP_AON->PMCTL2_1),diff_aio,diff_aio,0);
}
subWriteReg(&(AP_AON->PMCTL2_1),(aio+8),(aio+8),1);
subWriteReg(&(AP_AON->PMCTL2_1),aio,aio,0);
}
}
static void set_sampling_resolution_auto(uint8_t channel, uint8_t is_high_resolution,uint8_t is_differential_mode)
{
uint8_t i_channel;
adc_CH_t a_channel;
AP_AON->PMCTL2_1 = 0x00;
for(i_channel =2; i_channel<(ADC_CH_NUM-1); i_channel++)
{
if(channel & BIT(i_channel))
{
a_channel = (adc_CH_t)i_channel;
set_sampling_resolution(a_channel,
(is_high_resolution & BIT(i_channel)),
(is_differential_mode & BIT(i_channel)));
}
}
}
static void set_differential_mode(void)
{
subWriteReg(&( AP_PCRM->ANA_CTL),8,8,0);
subWriteReg(&( AP_PCRM->ANA_CTL),11,11,0);
}
static void disable_analog_pin(adc_CH_t channel)
{
int index = (int)channel;
gpio_pin_e pin = s_pinmap[index];
if(pin == GPIO_DUMMY)
return;
hal_gpio_cfg_analog_io(pin,Bit_DISABLE);
hal_gpio_pin_init(pin,GPIO_INPUT); //ie=0,oen=1 set to imput
hal_gpio_pull_set(pin,GPIO_FLOATING); //
}
static void clear_adcc_cfg(void)
{
memset(&mAdc_Ctx, 0, sizeof(mAdc_Ctx));
}
/////////////// adc ////////////////////////////
/**************************************************************************************
@fn hal_ADC_IRQHandler
@brief This function process for adc interrupt
input parameters
@param None.
output parameters
@param None.
@return None.
**************************************************************************************/
void __attribute__((used)) hal_ADC_IRQHandler(void)
{
int ch,status,ch2,n;
uint16_t adc_data[MAX_ADC_SAMPLE_SIZE];
status = GET_IRQ_STATUS;
MASK_ADC_INT;
if(status == mAdc_Ctx.all_channel)
{
for (ch = 2; ch <= ADC_CH9; ch++)
{
if (status & BIT(ch))
{
AP_ADCC->intr_mask &= ~BIT(ch);
for (n = 0; n < (MAX_ADC_SAMPLE_SIZE-3); n++)
{
adc_data[n] = (uint16_t)(read_reg(ADC_CH_BASE + (ch * 0x80) + ((n+2) * 4))&0xfff);
adc_data[n+1] = (uint16_t)((read_reg(ADC_CH_BASE + (ch * 0x80) + ((n+2) * 4))>>16)&0xfff);
}
AP_ADCC->intr_clear = BIT(ch);
if(mAdc_Ctx.enable == FALSE)
continue;
ch2=(ch%2)?(ch-1):(ch+1);
if (mAdc_Ctx.evt_handler[ch2])
{
adc_Evt_t evt;
evt.type = HAL_ADC_EVT_DATA;
evt.ch = (adc_CH_t)ch2;
evt.data = adc_data;
evt.size = MAX_ADC_SAMPLE_SIZE-3;
mAdc_Ctx.evt_handler[ch2](&evt);
}
AP_ADCC->intr_mask |= BIT(ch);
}
}
if(mAdc_Ctx.continue_mode == FALSE)
{
hal_adc_stop();
}
}
ENABLE_ADC_INT;
}
static void adc_wakeup_hdl(void)
{
NVIC_SetPriority((IRQn_Type)ADCC_IRQn, IRQ_PRIO_HAL);
}
/**************************************************************************************
@fn hal_adc_init
@brief This function process for adc initial
input parameters
@param ADC_MODE_e mode: adc sample mode select;1:SAM_MANNUAL(mannual mode),0:SAM_AUTO(auto mode)
ADC_CH_e adc_pin: adc pin select;ADC_CH0~ADC_CH7 and ADC_CH_VOICE
ADC_SEMODE_e semode: signle-ended mode negative side enable; 1:SINGLE_END(single-ended mode) 0:DIFF(Differentail mode)
IO_CONTROL_e amplitude: input signal amplitude, 0:BELOW_1V,1:UP_1V
output parameters
@param None.
@return None.
**************************************************************************************/
void hal_adc_init(void)
{
mAdc_init_flg = TRUE;
hal_pwrmgr_register(MOD_ADCC,NULL,adc_wakeup_hdl);
clear_adcc_cfg();
}
int hal_adc_clock_config(adc_CLOCK_SEL_t clk)
{
if(!mAdc_init_flg)
{
return PPlus_ERR_NOT_REGISTED;
}
subWriteReg(0x4000F000 + 0x7c,2,1,clk);
return PPlus_SUCCESS;
}
int hal_adc_start(void)
{
if(!mAdc_init_flg)
{
return PPlus_ERR_NOT_REGISTED;
}
mAdc_Ctx.enable = TRUE;
hal_pwrmgr_lock(MOD_ADCC);
JUMP_FUNCTION(ADCC_IRQ_HANDLER) = (uint32_t)&hal_ADC_IRQHandler;
//ENABLE_ADC;
AP_PCRM->ANA_CTL |= BIT(3);
AP_PCRM->ANA_CTL |= BIT(0);//new
//ADC_IRQ_ENABLE;
NVIC_EnableIRQ((IRQn_Type)ADCC_IRQn);
//ENABLE_ADC_INT;
AP_ADCC->intr_mask = 0x1ff;
//disableSleep();
return PPlus_SUCCESS;
}
int hal_adc_config_channel(adc_Cfg_t cfg, adc_Hdl_t evt_handler)
{
uint8_t i;
uint8_t chn_sel,evt_index;
gpio_pin_e pin,pin_neg;
if(!mAdc_init_flg)
{
return PPlus_ERR_NOT_REGISTED;
}
if(mAdc_Ctx.enable)
{
return PPlus_ERR_BUSY;
}
if(evt_handler == NULL)
{
return PPlus_ERR_INVALID_PARAM;
}
if(cfg.channel & BIT(0)/*||channel == ADC_CH1*/ )
{
return PPlus_ERR_NOT_SUPPORTED;
}
if((!cfg.channel & BIT(1))&&(cfg.is_differential_mode && (cfg.channel & BIT(1))))
{
return PPlus_ERR_INVALID_PARAM;
}
if(cfg.is_differential_mode != 0)
{
if((cfg.is_differential_mode != 0x80) && (cfg.is_differential_mode != 0x20) && (cfg.is_differential_mode != 0x08))
{
return PPlus_ERR_INVALID_PARAM;
}
}
mAdc_Ctx.continue_mode = cfg.is_continue_mode;
mAdc_Ctx.all_channel = cfg.channel & 0x03;
for(i=2; i<8; i++)
{
if(cfg.channel & BIT(i))
{
if(i%2)
{
mAdc_Ctx.all_channel |= BIT(i-1);
}
else
{
mAdc_Ctx.all_channel |= BIT(i+1);
}
}
}
if((AP_PCR->SW_CLK & BIT(MOD_ADCC)) == 0)
{
hal_clk_gate_enable(MOD_ADCC);
}
//CLK_1P28M_ENABLE;
AP_PCRM->CLKSEL |= BIT(6);
//ENABLE_XTAL_OUTPUT; //enable xtal 16M output,generate the 32M dll clock
AP_PCRM->CLKHF_CTL0 |= BIT(18);
//ENABLE_DLL; //enable DLL
AP_PCRM->CLKHF_CTL1 |= BIT(7);
//ADC_DBLE_CLOCK_DISABLE; //disable double 32M clock,we are now use 32M clock,should enable bit<13>, diable bit<21>
AP_PCRM->CLKHF_CTL1 &= ~BIT(21);//check
//subWriteReg(0x4000F044,21,20,3);
//ADC_CLOCK_ENABLE; //adc clock enbale,always use clk_32M
AP_PCRM->CLKHF_CTL1 |= BIT(13);
//subWriteReg(0x4000f07c,4,4,1); //set adc mode,1:mannual,0:auto mode
AP_PCRM->ADC_CTL4 |= BIT(4);
AP_PCRM->ADC_CTL4 |= BIT(0);
set_sampling_resolution_auto(cfg.channel, cfg.is_high_resolution,cfg.is_differential_mode);
AP_PCRM->ADC_CTL0 &= ~BIT(20);
AP_PCRM->ADC_CTL0 &= ~BIT(4);
AP_PCRM->ADC_CTL1 &= ~BIT(20);
AP_PCRM->ADC_CTL1 &= ~BIT(4);
AP_PCRM->ADC_CTL2 &= ~BIT(20);
AP_PCRM->ADC_CTL2 &= ~BIT(4);
AP_PCRM->ADC_CTL3 &= ~BIT(20);
AP_PCRM->ADC_CTL3 &= ~BIT(4);
AP_PCRM->ANA_CTL &= ~BIT(23);//disable micbias
if(cfg.is_differential_mode == 0)
{
AP_PCRM->ADC_CTL4 &= ~BIT(4); //enable auto mode
for(i=2; i<8; i++)
{
if(cfg.channel & BIT(i))
{
gpio_pin_e pin = s_pinmap[i];
hal_gpio_pull_set(pin,GPIO_FLOATING);
hal_gpio_ds_control(pin, Bit_ENABLE);
hal_gpio_cfg_analog_io(pin, Bit_ENABLE);
switch (i)
{
case 0:
AP_PCRM->ADC_CTL0 |= BIT(20);
break;
case 1:
AP_PCRM->ADC_CTL0 |= BIT(4);
break;
case 2:
AP_PCRM->ADC_CTL1 |= BIT(20);
break;
case 3:
AP_PCRM->ADC_CTL1 |= BIT(4);
break;
case 4:
AP_PCRM->ADC_CTL2 |= BIT(20);
break;
case 5:
AP_PCRM->ADC_CTL2 |= BIT(4);
break;
case 6:
AP_PCRM->ADC_CTL3 |= BIT(20);
break;
case 7:
AP_PCRM->ADC_CTL3 |= BIT(4);
break;
default:
break;
}
mAdc_Ctx.evt_handler[i] = evt_handler;
}
}
}
else
{
switch(cfg.is_differential_mode)
{
case 0x80:
pin = P20;
pin_neg = P15;
chn_sel = 0x04;
evt_index = 7;
break;
case 0x20:
pin = P14;
pin_neg = P24;
chn_sel = 0x03;
evt_index = 5;
break;
case 0x08:
pin = P23;
pin_neg = P11;
chn_sel = 0x02;
evt_index = 3;
break;
case 0x02:
pin = P18;
pin_neg = P25;
chn_sel = 0x01;
evt_index = 1;
*(volatile int*)(0x4000F020) = 0x0060;
break;
default:
break;
}
hal_gpio_ds_control(pin, Bit_ENABLE);
subWriteReg(0x4000f048,7,5,chn_sel);
set_differential_mode();
//LOG("%d %d %x\n",pin,pin_neg,*(volatile int*)0x40003800);
hal_gpio_pull_set(pin,GPIO_FLOATING);
hal_gpio_pull_set(pin_neg,GPIO_FLOATING);
hal_gpio_cfg_analog_io(pin,Bit_ENABLE);
hal_gpio_cfg_analog_io(pin_neg,Bit_ENABLE);
//LOG("%d %d %x\n",pin,pin_neg,*(volatile int*)0x40003800);
mAdc_Ctx.all_channel = (cfg.is_differential_mode >> 1);
mAdc_Ctx.evt_handler[evt_index] = evt_handler;
}
return PPlus_SUCCESS;
}
int hal_adc_stop(void)
{
int i;
if(!mAdc_init_flg)
{
return PPlus_ERR_NOT_REGISTED;
}
//MASK_ADC_INT;
AP_ADCC->intr_mask = 0x1ff;
NVIC_DisableIRQ((IRQn_Type)ADCC_IRQn);
JUMP_FUNCTION(ADCC_IRQ_HANDLER) = 0;
ADC_INIT_TOUT(to);
AP_ADCC->intr_clear = 0x1FF;
while(AP_ADCC->intr_status != 0)
{
ADC_CHECK_TOUT(to, ADC_OP_TIMEOUT, "hal_adc_clear_int_status timeout\n");
AP_ADCC->intr_clear = 0x1FF;
}
//DISABLE_ADC;
AP_PCRM->ANA_CTL &= ~BIT(3);
//ADC_CLOCK_DISABLE;
AP_PCRM->CLKHF_CTL1 &= ~BIT(13);
for(i =0; i< ADC_CH_NUM; i++)
{
if(mAdc_Ctx.evt_handler[i])
{
disable_analog_pin((adc_CH_t)i);
}
}
AP_PCRM->ANA_CTL &= ~BIT(0);//Power down analog LDO
hal_clk_gate_disable(MOD_ADCC);
clear_adcc_cfg();
//enableSleep();
hal_pwrmgr_unlock(MOD_ADCC);
return PPlus_SUCCESS;
}
/**************************************************************************************
@fn hal_adc_value
@brief This function process for get adc value
input parameters
@param ADC_CH_e adc_pin: adc pin select;ADC_CH0~ADC_CH7 and ADC_CH_VOICE
output parameters
@param None.
@return ADC value
**************************************************************************************/
static void hal_adc_load_calibration_value(void)
{
if(adc_cal_read_flag==FALSE)
{
adc_cal_read_flag = TRUE;
adc_cal_negtive = read_reg(0x11001000)&0x0fff;
adc_cal_postive = (read_reg(0x11001000)>>16)&0x0fff;
LOG("AD_CAL[%x %x]\n",adc_cal_negtive,adc_cal_postive);
}
}
#if(SDK_VER_CHIP==__DEF_CHIP_QFN32__)
const unsigned int adc_Lambda[ADC_CH_NUM] =
{
0, //ADC_CH0 =0,
0, //ADC_CH1 =1,
4519602,//P11
4308639,//P23
4263287,//P24
4482718,//P14
4180401,//P15
4072069,//P20
0,//GPIO_DUMMY, //ADC_CH_VOICE =8,
};
#elif(SDK_VER_CHIP == __DEF_CHIP_TSOP16__)
const unsigned int adc_Lambda[ADC_CH_NUM] =
{
0, //ADC_CH0 =0,
0, //ADC_CH1 =1,
4488156,//P11
4308639,//P23,
4263287,//P24,
4467981,//P14
4142931,//P15
4054721,//P20
0,//GPIO_DUMMY, //ADC_CH_VOICE =8,
};
#endif
float hal_adc_value_cal(adc_CH_t ch,uint16_t* buf, uint32_t size, uint8_t high_resol, uint8_t diff_mode)
{
uint32_t i;
int adc_sum = 0;
volatile float result = 0.0;
for (i = 0; i < size; i++)
{
adc_sum += (buf[i]&0xfff);
}
hal_adc_load_calibration_value();
result = ((float)adc_sum)/size;
//LOG("adc_sum:%10d %10d ",adc_sum,adc_sum/(MAX_ADC_SAMPLE_SIZE-3));
if((adc_cal_postive!=0xfff)&&(adc_cal_negtive!=0xfff))
{
float delta = ((int)(adc_cal_postive-adc_cal_negtive))/2.0;
if(ch&0x01)
{
result = (diff_mode) ? ((result-2048-delta)*2/(adc_cal_postive+adc_cal_negtive))
: ((result-delta) /(adc_cal_postive+adc_cal_negtive));
}
else
{
result = (diff_mode) ? ((result-2048-delta)*2/(adc_cal_postive+adc_cal_negtive))
: ((result+delta) /(adc_cal_postive+adc_cal_negtive));
}
}
else
{
result = (diff_mode) ? (float)(result / 2048 -1) : (float)(result /4096);
}
if(high_resol == TRUE)
{
result *= 0.8;
}
else
{
result = (float)result *(float)adc_Lambda[ch]*0.8/1000000;
}
return result;
}
void adc_init_r(ADC_CH_R_e adc_pin,ADC_SEMODE_R_e semode,IO_CONTROL_R_e amplitude)
{
ENABLE_XTAL_OUTPUT_R; //enable xtal 16M output,generate the 32M dll clock
ENABLE_DLL_R; //enable DLL
ADC_DBLE_CLOCK_DISABLE_R; //disable double 32M clock,we are now use 32M clock,should enable bit<13>
ADC_CLOCK_ENABLE_R; //adc clock enbale,always use clk_32M
//write_reg(0x4000f07c,0); //?reset time and clksel and max rate,80k sample
subWriteReg(0x4000f07c,4,4,1);//set adc mode,1:mannual,0:auto mode
// subWriteReg(&AP_ADCC->compare_cfg[0],29,24,16);
// subWriteReg(&AP_ADCC->compare_cfg[1],29,24,16);
// subWriteReg(&AP_ADCC->compare_cfg[2],29,24,16);
// subWriteReg(&AP_ADCC->compare_cfg[3],29,24,16);
// subWriteReg(&AP_ADCC->compare_cfg[4],29,24,16);
// subWriteReg(&AP_ADCC->compare_cfg[5],29,24,16);
// subWriteReg(&AP_ADCC->compare_cfg[6],29,24,16);
// subWriteReg(&AP_ADCC->compare_cfg[7],29,24,16);
// subWriteReg(0x4000F070,18,15,0x00);
//normal adcpin
subWriteReg(0x4000f048,7,5,((adc_pin>>1)+1)); // 100 for p20 ; 100 for p15 aio4
switch(adc_pin)
{
case ADC_P23_CH2:
subWriteReg(0x4000f048,11,11,0);
subWriteReg(0x4000f048,8,8,semode);
hal_gpio_cfg_analog_io(P23,Bit_ENABLE);
subWriteReg(&(AP_AON->PMCTL2_1),9,9,amplitude);
subWriteReg(&(AP_AON->PMCTL2_1),1,1,(1-amplitude));
break;
case ADC_P11_CH3:
subWriteReg(0x4000f048,8,8,0);
subWriteReg(0x4000f048,11,11,semode);
hal_gpio_cfg_analog_io(P11,Bit_ENABLE);
subWriteReg(&(AP_AON->PMCTL2_1),8,8,amplitude);
subWriteReg(&(AP_AON->PMCTL2_1),0,0,(1-amplitude));
break;
case ADC_P14_CH4:
subWriteReg(0x4000f048,11,11,0);
subWriteReg(0x4000f048,8,8,semode);
hal_gpio_cfg_analog_io(P14,Bit_ENABLE);
subWriteReg(&(AP_AON->PMCTL2_1),11,11,amplitude);
subWriteReg(&(AP_AON->PMCTL2_1),3,3,(1-amplitude));
break;
case ADC_P24_CH5:
subWriteReg(0x4000f048,8,8,0);
subWriteReg(0x4000f048,11,11,semode);
hal_gpio_cfg_analog_io(P24,Bit_ENABLE);
subWriteReg(&(AP_AON->PMCTL2_1),10,10,amplitude);
subWriteReg(&(AP_AON->PMCTL2_1),2,2,(1-amplitude));
break;
case ADC_P20_CH6:
subWriteReg(0x4000f048,11,11,0);
subWriteReg(0x4000f048,8,8,semode);
hal_gpio_cfg_analog_io(P20,Bit_ENABLE);
subWriteReg(&(AP_AON->PMCTL2_1),15,15,amplitude);
subWriteReg(&(AP_AON->PMCTL2_1),7,7,(1-amplitude));
break;
case ADC_P15_CH7:
subWriteReg(0x4000f048,8,8,0);
subWriteReg(0x4000f048,11,11,semode);
hal_gpio_cfg_analog_io(P15,Bit_ENABLE);
subWriteReg(&(AP_AON->PMCTL2_1),12,12,amplitude);
subWriteReg(&(AP_AON->PMCTL2_1),4,4,(1-amplitude));
break;
default:
break;
}
POWER_UP_ADC_R; //enable power up
subWriteReg(0x4000f048,0,0,1); //AP_PCRM->ANA_CTL //Power up analog LDO
}
void adc_stop_r(void)
{
write_reg(0x4000f020, 0);
}

View File

@ -0,0 +1,243 @@
/**************************************************************************************************
*******
**************************************************************************************************/
/*******************************************************************************
@file adc.h
@brief Contains all functions support for adc driver
@version 0.0
@date 18. Oct. 2017
@author qing.han
*******************************************************************************/
#ifndef __ADC__H__
#define __ADC__H__
#ifdef __cplusplus
extern "C" {
#endif
#include "types.h"
#include "bus_dev.h"
#include "gpio.h"
#define MAX_ADC_SAMPLE_SIZE 32
#define ADC_CH_BASE (0x40050400UL)
#define ENABLE_ADC_INT AP_ADCC->intr_mask |= 0x000001ff
#define MASK_ADC_INT AP_ADCC->intr_mask &= 0xfffffe00
#define CLEAR_ADC_INT(n) AP_ADC->intr_clear |= BIT(n)
#define IS_CLAER_ADC_INT_VOICE (AP_ADC->intr_clear & BIT(8))
#define IS_CLAER_ADC_INT(n) (AP_ADC->intr_clear & BIT(n))
#define GET_IRQ_STATUS (AP_ADCC->intr_status & 0x3ff)
#define ENABLE_ADC (AP_PCRM->ANA_CTL |= BIT(3))
#define DISABLE_ADC (AP_PCRM->ANA_CTL &= ~BIT(3))
#define ADC_CLOCK_ENABLE (AP_PCRM->CLKHF_CTL1 |= BIT(13))
#define ADC_CLOCK_DISABLE (AP_PCRM->CLKHF_CTL1 &= ~BIT(13))
#define ADC_USE_TIMEOUT 0
#define ADC_OP_TIMEOUT 100
#if(ADC_USE_TIMEOUT == 1)
#define ADC_INIT_TOUT(to) int to = hal_systick()
#define ADC_CHECK_TOUT(to, timeout, loginfo) {if(hal_ms_intv(to) > timeout){LOG(loginfo);return PPlus_ERR_TIMEOUT;}}
#else
#define ADC_INIT_TOUT(to)
#define ADC_CHECK_TOUT(to, timeout, loginfo)
#endif
/**************************************************************************************
@fn hal_get_adc_int_source
@brief This function process for get adc interrupt source,such as adc channel NO
input parameters
@param None.
output parameters
@param None.
@return adc interrupt source bit loaction(uint8_t)
**************************************************************************************/
/*
ADC note:
There are ten pins which can config as analogy,there are some differences between them.
hardware analogy index:
gpio<11>/aio<0>
gpio<23>/aio<1>/micphone bias reference voltage
gpio<24>/aio<2>
gpio<14>/aio<3>
gpio<15>/aio<4>/micphone bias
gpio<16>/aio<5>/32K XTAL input
gpio<17>/aio<6>/32K XTAL output
gpio<18>/aio<7>/pga in+
gpio<25>/aio<8>
gpio<20>/aio<9>/pga in-
There are six pins which can work in adc single mode.Such as:
ADC_CH0 = 2,ADC_CH1N_P11 = 2,
ADC_CH1 = 3,ADC_CH1P_P23 = 3,
ADC_CH2 = 4,ADC_CH2N_P24 = 4,
ADC_CH3 = 5,ADC_CH2P_P14 = 5,
ADC_CH4 = 6,ADC_CH3N_P15 = 6,
ADC_CH9 = 7,ADC_CH3P_P20 = 7,
There are four pair pins which can work in adc diff mode.Such as:
ADC_CH0DIFF = 1,p18(p) and P25(n)
ADC_CH1DIFF = 3,P23(p) and P11(n)
ADC_CH2DIFF = 5,P14(p) and P24(n)
ADC_CH3DIFF = 7,P20(p) and P15(n)
There are two pins which uses with 32.768K crystal oscillator.
gpio<16>/aio<5>/32K XTAL input
gpio<17>/aio<6>/32K XTAL output
There are four pins which uses as pga,voice and so on.
gpio<23>/aio<1>/micphone bias reference voltage,this pin is selected
gpio<15>/aio<4>/micphone bias
gpio<18>/aio<7>/pga in+
gpio<20>/aio<9>/pga in-
*/
typedef enum
{
ADC_CH0DIFF = 1,/*p18(positive),p25(negative),only works in diff*/
ADC_CH0 = 2,ADC_CH1N_P11 = 2,
ADC_CH1 = 3,ADC_CH1P_P23 = 3,ADC_CH1DIFF = 3,/*P23 and P11*/
ADC_CH2 = 4,ADC_CH2N_P24 = 4,
ADC_CH3 = 5,ADC_CH2P_P14 = 5,ADC_CH2DIFF = 5,/*P14 and P24*/
ADC_CH4 = 6,ADC_CH3N_P15 = 6,
ADC_CH9 = 7,ADC_CH3P_P20 = 7,ADC_CH3DIFF = 7,/*P20 and P15*/
ADC_CH_VOICE = 8,
ADC_CH_NUM =9,
} adc_CH_t;
#define ADC_BIT(ch) (1<<ch)
enum
{
HAL_ADC_EVT_DATA = 1,
HAL_ADC_EVT_FAIL = 0xff
};
typedef enum
{
HAL_ADC_CLOCK_80K = 0,
HAL_ADC_CLOCK_160K = 1,
HAL_ADC_CLOCK_320K = 2,
} adc_CLOCK_SEL_t;
typedef struct _adc_Cfg_t
{
uint8_t channel;
bool is_continue_mode;
uint8_t is_differential_mode;
uint8_t is_high_resolution;
} adc_Cfg_t;
typedef struct _adc_Evt_t
{
int type;
adc_CH_t ch;
uint16_t* data;
uint8_t size; //word size
} adc_Evt_t;
typedef void (*adc_Hdl_t)(adc_Evt_t* pev);
typedef struct _adc_Contex_t
{
bool enable;
uint8_t all_channel;
bool continue_mode;
adc_Hdl_t evt_handler[ADC_CH_NUM];
} adc_Ctx_t;
extern gpio_pin_e s_pinmap[ADC_CH_NUM];
/**************************************************************************************
@fn hal_adc_init
@brief This function process for adc initial
input parameters
@param ADC_CH_e adc_pin: adc pin select;ADC_CH0~ADC_CH7 and ADC_CH_VOICE
ADC_SEMODE_e semode: single-end mode and diff mode select; 1:SINGLE_END(single-end mode) 0:DIFF(Diff mode)
IO_CONTROL_e amplitude: input signal amplitude, 0:BELOW_1V,1:UP_1V
output parameters
@param None.
@return None.
**************************************************************************************/
void hal_adc_init(void);
int hal_adc_config_channel(adc_Cfg_t cfg, adc_Hdl_t evt_handler);
int hal_adc_clock_config(adc_CLOCK_SEL_t clk);
int hal_adc_start(void);
int hal_adc_stop(void);
void __attribute__((weak)) hal_ADC_IRQHandler(void);
float hal_adc_value_cal(adc_CH_t ch,uint16_t* buf, uint32_t size, uint8_t high_resol, uint8_t diff_mode);
#define POWER_UP_ADC_R *(volatile unsigned int *)0x4000f048 |= BIT(3)
#define ADC_CLOCK_ENABLE_R *(volatile unsigned int *)0x4000f044 |= BIT(13)
#define ADC_DBLE_CLOCK_DISABLE_R *(volatile unsigned int *)0x4000f044 &= ~BIT(21)
#define POWER_UP_TEMPSENSOR_R *(volatile unsigned int *)0x4000f048 |= BIT(29)
#define ENABLE_XTAL_OUTPUT_R *(volatile unsigned int *)0x4000f040 |= BIT(18)
#define ENABLE_DLL_R *(volatile unsigned int *)0x4000f044 |= BIT(7)
typedef enum {
//ADC_R_CH0 =0,
//ADC_R_CH1 =1,
ADC_P23_CH2 =2,
ADC_P11_CH3 =3,
ADC_P14_CH4 =4,
ADC_P24_CH5 =5,
ADC_P20_CH6 =6,
ADC_P15_CH7 =7,
ADC_R_CH_VOICE =8,
}ADC_CH_R_e;
typedef enum {
//SAM_AUTO = 0,
SAM_MANNUAL = 1,
}ADC_MODE_R_e;
typedef enum{
//DIFF = 0,
SINGLE_END = 1,
}ADC_SEMODE_R_e;
typedef enum{
BELOW_8000MV = 0,
//UP_8000MV = 1,
}IO_CONTROL_R_e;
void adc_init_r(ADC_CH_R_e adc_pin,ADC_SEMODE_R_e semode,IO_CONTROL_R_e amplitude);
void adc_stop_r(void);
#ifdef __cplusplus
}
#endif
#endif

View File

@ -0,0 +1,69 @@
/**************************************************************************************************
THIS IS EMPTY HEADER
**************************************************************************************************/
/**************************************************************************************************
Filename: SimpleBLEPeripheral_Main.c
Revised:
Revision:
Description: This file contains the main and callback functions for
the Simple BLE Peripheral sample application.
**************************************************************************************************/
/**************************************************************************************************
Includes
**************************************************************************************************/
/* Hal Drivers */
/* OSAL */
#include "OSAL.h"
#include "OSAL_Tasks.h"
#include "OSAL_PwrMgr.h"
#include "OSAL_Timers.h"
#include "osal_snv.h"
#include "ll_sleep.h"
#include "uart.h"
/**************************************************************************************************
FUNCTIONS
**************************************************************************************************/
#include "comdef.h"
//#include "OnBoard.h"
//#include "hal_mcu.h"
/*********************************************************************
EXTERNAL VARIABLES
*/
/**************************************************************************************************
@fn main
@brief Start of application.
@param none
@return none
**************************************************************************************************
*/
int app_main(void)
{
/* Initialize the operating system */
osal_init_system();
osal_pwrmgr_device( PWRMGR_BATTERY );
/* Start OSAL */
osal_start_system(); // No Return from here
return 0;
}
/**************************************************************************************************
CALL-BACKS
**************************************************************************************************/
/*************************************************************************************************
**************************************************************************************************/

View File

@ -0,0 +1,240 @@
/**************************************************************************************************
THIS IS EMPTY HEADER
**************************************************************************************************/
/**************************************************************************************************
Filename: adc_demo.c
Revised: $Date $
Revision: $Revision $
**************************************************************************************************/
/*********************************************************************
INCLUDES
*/
#include "OSAL.h"
#include "gpio.h"
#include "clock.h"
#include "adc.h"
#include "adc_demo.h"
#include "log.h"
#include "timer.h"
#include "pwm.h"
/*********************************************************************
TYPEDEFS
*/
/*********************************************************************
GLOBAL VARIABLES
*/
#define MAX_SAMPLE_POINT 64
uint16_t adc_debug[6][MAX_SAMPLE_POINT];
//static uint8_t channel_done_flag = 0;
/*********************************************************************
EXTERNAL VARIABLES
*/
/*********************************************************************
EXTERNAL FUNCTIONS
*/
/*********************************************************************
LOCAL VARIABLES
*/
static uint8 adcDemo_TaskID; // Task ID for internal task/event processing
/*********************************************************************
LOCAL FUNCTIONS
*/
static void adc_ProcessOSALMsg( osal_event_hdr_t* pMsg );
static void adcMeasureTask( void );
/*********************************************************************
PROFILE CALLBACKS
*/
/*********************************************************************
PUBLIC FUNCTIONS
*/
void time_cb()
{
static uint32 time_cnt;
time_cnt++;
if(time_cnt%500 == 1){
hal_gpio_write(GPIO_P20,(time_cnt/500)&0x01);
}
}
#define PWM_IO_DA GPIO_P03
#define PWM_FREQ 2750
#define PWM_DUTY 20/// 0~100
void adc_Init( uint8 task_id )
{
adcDemo_TaskID = task_id;
hal_gpio_pin_init(GPIO_P02,IE); /// p02 设置输入
hal_gpio_pull_set(GPIO_P02,GPIO_PULL_UP_S);/// 强上拉, 150k 弱上拉1M
hal_gpio_pin_init(GPIO_P20,OEN);
hal_gpio_write(GPIO_P20,0);
hal_pwm_init(PWM_CH0, PWM_CLK_DIV_4, PWM_CNT_UP, PWM_POLARITY_FALLING);
hal_pwm_open_channel(PWM_CH0, PWM_IO_DA);
hal_pwm_set_count_val(PWM_CH0, (((16000000/(1<<PWM_CLK_DIV_4))/PWM_FREQ)*PWM_DUTY/100), ((16000000/(1<<PWM_CLK_DIV_4))/PWM_FREQ));
hal_pwm_start(); /// pwm start
WaitMs(500);
hal_pwm_stop(); /// pwm stop
// WaitMs(500);
// hal_pwm_init(PWM_CH0, PWM_CLK_DIV_4, PWM_CNT_UP, PWM_POLARITY_FALLING);
// hal_pwm_open_channel(PWM_CH0, PWM_IO_DA);
// hal_pwm_set_count_val(PWM_CH0, (((16000000/(1<<PWM_CLK_DIV_4))/PWM_FREQ)*PWM_DUTY/100), ((16000000/(1<<PWM_CLK_DIV_4))/PWM_FREQ));
// hal_pwm_start(); /// pwm start
// WaitMs(500);
// hal_pwm_stop(); /// pwm stop
hal_timer_init(time_cb); /// 设置中断回调函数
hal_timer_set(AP_TIMER_ID_5, 1000); /// 1ms 中断
adcMeasureTask();
}
uint16 adc_ProcessEvent( uint8 task_id, uint16 events )
{
VOID task_id; // OSAL required parameter that isn't used in this function
//LOG("adc_ProcessEvent: 0x%x\n",events);
if ( events & SYS_EVENT_MSG )
{
uint8* pMsg;
if ( (pMsg = osal_msg_receive( adcDemo_TaskID )) != NULL )
{
adc_ProcessOSALMsg( (osal_event_hdr_t*)pMsg );
// Release the OSAL message
VOID osal_msg_deallocate( pMsg );
}
// return unprocessed events
return (events ^ SYS_EVENT_MSG);
}
if ( events & 0x20 )
{
// Perform periodic heart rate task
//LOG("20\n");
//osal_start_timerEx( adcDemo_TaskID, 0x20, 2000);
return (events ^ 0x20);
}
if ( events & adcMeasureTask_EVT )
{
// Perform periodic heart rate task
//LOG("adcMeasureTask_EVT\n");
adcMeasureTask();
return (events ^ adcMeasureTask_EVT);
}
// Discard unknown events
return 0;
}
static void adc_ProcessOSALMsg( osal_event_hdr_t* pMsg )
{
}
const uint32_t adc_base_addr[6] =
{
0x40050500,
0x40050580,
0x40050600,
0x40050680,
0x40050700,
0x40050780
};
void InsertSort(uint16_t *a, int n)
{
for(int i= 1; i<n; i++){
if(a[i] < a[i-1]){ //若第i个元素大于i-1元素直接插入。小于的话移动有序表后插入
int j= i-1;
int x = a[i]; //复制为哨兵,即存储待排序元素
a[i] = a[i-1]; //先后移一个元素
while(x < a[j]){ //查找在有序表的插入位置
a[j+1] = a[j];
j--; //元素后移
}
a[j+1] = x; //插入到正确位置
}
}
}
float my_hal_adc_value_cal(adc_CH_t ch,uint16_t buf,uint8_t high_resol, uint8_t diff_mode)
{
uint32_t i;
int adc_sum = 0;
volatile float result = 0.0;
result = buf;
result = (diff_mode) ? (float)(result / 2048 -1) : (float)(result /4096);
if(high_resol == TRUE)
{
result *= 0.8;
}
return result;
}
uint16_t adc_buf[64];
uint16_t adc_sample_buf[58];
uint16 adcMeasureCh(ADC_CH_R_e adc_ch)
{
uint32_t adc_sample_data[32];
adc_init_r(adc_ch, SINGLE_END, BELOW_8000MV); //adc init
subWriteReg(0x4000f07c, 2, 1, 2); //080K 1:160K 2:320k rate sample
WaitUs(300);/// 320K 64dot wait
// for (uint8_t i = 0; i < 32; i++)
for (uint8_t i = 0; i < 29; i++)
{
adc_sample_data[i] = read_reg(adc_base_addr[adc_ch-2] + (i << 2)); // 0x0700~0x077F offset=0x4
adc_buf[i*2] = adc_sample_data[i]&0x0fff;
adc_buf[i*2+1] = (adc_sample_data[i]>>16)&0x0fff;
}
adc_stop_r();
InsertSort(adc_buf, 58); /// 排序
// InsertSort(adc_buf, sizeof(adc_buf)/sizeof(uint16_t)); /// 排序
uint32 sum_adc = 0;
for(uint8 i=24;i<40;i++) { ///取中间16个数据的均值
sum_adc+=adc_buf[i];
}
sum_adc = (sum_adc>>4);
return sum_adc;
}
void adcMeasureTask( void )
{
uint32_t adc_sample_data[32];
uint32_t adc_word_p = 0;
uint16_t adc_buf[1];
ADC_CH_R_e adc_ch = ADC_P14_CH4;//ADC_P24_CH5; /// set channel
adc_CH_t ch;
float value = 0;
int adc_gpio_ch;
uint16 adc_val;
while(1)
{
adc_val = adcMeasureCh(ADC_P14_CH4);
value = my_hal_adc_value_cal(ch,adc_val,TRUE,FALSE);
LOG("ch%d %d mv \n",adc_ch,(int)(value*1000));
WaitMs(400);
}
}

View File

@ -0,0 +1,49 @@
/**************************************************************************************************
THIS IS EMPTY HEADER
**************************************************************************************************/
/**************************************************************************************************
Filename: adc_demo.h
Revised: $Date $
Revision: $Revision $
**************************************************************************************************/
#ifndef __ADC_DEMO_H__
#define __ADC_DEMO_H__
#ifdef __cplusplus
extern "C"
{
#endif
#include "adc.h"
/*********************************************************************
INCLUDES
*/
/*********************************************************************
CONSTANTS
*/
/*********************************************************************
MACROS
*/
#define adcMeasureTask_EVT 0x0080
/*********************************************************************
FUNCTIONS
*/
extern void adc_Init( uint8 task_id );
extern uint16 adc_ProcessEvent( uint8 task_id, uint16 events );
/*********************************************************************
*********************************************************************/
#ifdef __cplusplus
}
#endif
#endif

View File

@ -0,0 +1,221 @@
/**************************************************************************************************
THIS IS EMPTY HEADER
**************************************************************************************************/
#include "bus_dev.h"
#include "gpio.h"
#include "clock.h"
#include "timer.h"
#include "jump_function.h"
#include "pwrmgr.h"
#include "mcu.h"
#include "gpio.h"
#include "log.h"
#include "rf_phy_driver.h"
#include "flash.h"
#include "version.h"
#include "adc.h"
#define DEFAULT_UART_BAUD 115200
/*********************************************************************
LOCAL FUNCTION PROTOTYPES
*/
/*********************************************************************
EXTERNAL FUNCTIONS
*/
extern void init_config(void);
extern int app_main(void);
extern void hal_rom_boot_init(void);
/*********************************************************************
CONNECTION CONTEXT RELATE DEFINITION
*/
#define BLE_MAX_ALLOW_CONNECTION 1
#define BLE_MAX_ALLOW_PKT_PER_EVENT_TX 4
#define BLE_MAX_ALLOW_PKT_PER_EVENT_RX 4
#define BLE_PKT_VERSION BLE_PKT_VERSION_5_1 //BLE_PKT_VERSION_5_1 //BLE_PKT_VERSION_5_1
/* BLE_MAX_ALLOW_PER_CONNECTION
{
...
struct ll_pkt_desc *tx_conn_desc[MAX_LL_BUF_LEN]; // new Tx data buffer
struct ll_pkt_desc *rx_conn_desc[MAX_LL_BUF_LEN];
struct ll_pkt_desc *tx_not_ack_pkt;
struct ll_pkt_desc *tx_ntrm_pkts[MAX_LL_BUF_LEN];
...
}
tx_conn_desc[] + tx_ntrm_pkts[] --> BLE_MAX_ALLOW_PKT_PER_EVENT_TX * BLE_PKT_BUF_SIZE*2
rx_conn_desc[] --> BLE_MAX_ALLOW_PKT_PER_EVENT_RX * BLE_PKT_BUF_SIZE
tx_not_ack_pkt --> 1*BLE_PKT_BUF_SIZE
*/
#define BLE_PKT_BUF_SIZE (((BLE_PKT_VERSION == BLE_PKT_VERSION_5_1) ? 1 : 0) * BLE_PKT51_LEN \
+ ((BLE_PKT_VERSION == BLE_PKT_VERSION_4_0) ? 1 : 0) * BLE_PKT40_LEN \
+ (sizeof(struct ll_pkt_desc) - 2))
#define BLE_MAX_ALLOW_PER_CONNECTION ( (BLE_MAX_ALLOW_PKT_PER_EVENT_TX * BLE_PKT_BUF_SIZE*2) \
+(BLE_MAX_ALLOW_PKT_PER_EVENT_RX * BLE_PKT_BUF_SIZE) \
+ BLE_PKT_BUF_SIZE )
#define BLE_CONN_BUF_SIZE (BLE_MAX_ALLOW_CONNECTION * BLE_MAX_ALLOW_PER_CONNECTION)
ALIGN4_U8 g_pConnectionBuffer[BLE_CONN_BUF_SIZE];
llConnState_t pConnContext[BLE_MAX_ALLOW_CONNECTION];
/*********************************************************************
CTE IQ SAMPLE BUF config
*/
//#define BLE_SUPPORT_CTE_IQ_SAMPLE TRUE
#ifdef BLE_SUPPORT_CTE_IQ_SAMPLE
uint16 g_llCteSampleI[LL_CTE_MAX_SUPP_LEN * LL_CTE_SUPP_LEN_UNIT];
uint16 g_llCteSampleQ[LL_CTE_MAX_SUPP_LEN * LL_CTE_SUPP_LEN_UNIT];
#endif
/*********************************************************************
OSAL LARGE HEAP CONFIG
*/
#define LARGE_HEAP_SIZE (4*1024)
ALIGN4_U8 g_largeHeap[LARGE_HEAP_SIZE];
/*********************************************************************
GLOBAL VARIABLES
*/
volatile uint8 g_clk32K_config;
volatile sysclk_t g_spif_clk_config;
/*********************************************************************
EXTERNAL VARIABLES
*/
extern uint32_t __initial_sp;
static void hal_low_power_io_init(void)
{
//========= pull all io to gnd by default
ioinit_cfg_t ioInit[]=
{
{GPIO_P02, GPIO_FLOATING },/*SWD*/
{GPIO_P03, GPIO_FLOATING },/*SWD*/
{GPIO_P09, GPIO_PULL_UP },/*UART TX*/
{GPIO_P10, GPIO_PULL_UP },/*UART RX*/
{GPIO_P11, GPIO_PULL_DOWN },
{GPIO_P14, GPIO_PULL_DOWN },
{GPIO_P15, GPIO_PULL_DOWN },
{GPIO_P16, GPIO_FLOATING },
{GPIO_P18, GPIO_PULL_DOWN },
{GPIO_P20, GPIO_PULL_DOWN },
#if(SDK_VER_CHIP==__DEF_CHIP_QFN32__)
{GPIO_P00, GPIO_PULL_DOWN },
{GPIO_P01, GPIO_PULL_DOWN },
{GPIO_P07, GPIO_PULL_DOWN },
{GPIO_P17, GPIO_FLOATING },/*32k xtal*/
{GPIO_P23, GPIO_PULL_DOWN },
{GPIO_P24, GPIO_PULL_DOWN },
{GPIO_P25, GPIO_PULL_DOWN },
{GPIO_P26, GPIO_PULL_DOWN },
{GPIO_P27, GPIO_PULL_DOWN },
{GPIO_P31, GPIO_PULL_DOWN },
{GPIO_P32, GPIO_PULL_DOWN },
{GPIO_P33, GPIO_PULL_DOWN },
{GPIO_P34, GPIO_PULL_DOWN },
#endif
};
for(uint8_t i=0; i<sizeof(ioInit)/sizeof(ioinit_cfg_t); i++)
hal_gpio_pull_set(ioInit[i].pin,ioInit[i].type);
DCDC_CONFIG_SETTING(0x0a);
DCDC_REF_CLK_SETTING(1);
DIG_LDO_CURRENT_SETTING(0x01);
hal_pwrmgr_RAM_retention(RET_SRAM0|RET_SRAM1|RET_SRAM2);
// hal_pwrmgr_RAM_retention(RET_SRAM0);
hal_pwrmgr_RAM_retention_set();
hal_pwrmgr_LowCurrentLdo_enable();
}
static void ble_mem_init_config(void)
{
osal_mem_set_heap((osalMemHdr_t*)g_largeHeap, LARGE_HEAP_SIZE);
LL_InitConnectContext(pConnContext,
g_pConnectionBuffer,
BLE_MAX_ALLOW_CONNECTION,
BLE_MAX_ALLOW_PKT_PER_EVENT_TX,
BLE_MAX_ALLOW_PKT_PER_EVENT_RX,
BLE_PKT_VERSION);
#ifdef BLE_SUPPORT_CTE_IQ_SAMPLE
LL_EXT_Init_IQ_pBuff(g_llCteSampleI,g_llCteSampleQ);
#endif
}
static void hal_rfphy_init(void)
{
//============config the txPower
g_rfPhyTxPower = RF_PHY_TX_POWER_0DBM ;
//============config BLE_PHY TYPE
g_rfPhyPktFmt = PKT_FMT_BLE1M;
//============config RF Frequency Offset
g_rfPhyFreqOffSet =RF_PHY_FREQ_FOFF_00KHZ;
//============config xtal 16M cap
XTAL16M_CAP_SETTING(0x09);
XTAL16M_CURRENT_SETTING(0x01);
hal_rom_boot_init();
NVIC_SetPriority((IRQn_Type)BB_IRQn, IRQ_PRIO_REALTIME);
NVIC_SetPriority((IRQn_Type)TIM1_IRQn, IRQ_PRIO_HIGH); //ll_EVT
NVIC_SetPriority((IRQn_Type)TIM2_IRQn, IRQ_PRIO_HIGH); //OSAL_TICK
NVIC_SetPriority((IRQn_Type)TIM4_IRQn, IRQ_PRIO_HIGH); //LL_EXA_ADV
//ble memory init and config
ble_mem_init_config();
}
static void hal_init(void)
{
hal_low_power_io_init();
clk_init(g_system_clk); //system init
hal_rtc_clock_config((CLK32K_e)g_clk32K_config);
hal_pwrmgr_init();
xflash_Ctx_t cfg =
{
.spif_ref_clk = SYS_CLK_DLL_64M,
.rd_instr = XFRD_FCMD_READ_DUAL
};
hal_spif_cache_init(cfg);
LOG_INIT();
hal_gpio_init();
hal_adc_init();
}
#define _BUILD_FOR_DTM_IN_APP_ 0
/////////////////////////////////////////////////////////////////////////////////////////////////////////
int main(void)
{
g_system_clk = SYS_CLK_DLL_64M;//SYS_CLK_DLL_48M;//SYS_CLK_DLL_64M;//SYS_CLK_XTAL_16M;
g_clk32K_config = CLK_32K_RCOSC;//CLK_32K_XTAL;//CLK_32K_XTAL,CLK_32K_RCOSC
drv_irq_init();
init_config();
hal_rfphy_init();
hal_init();
#if(_BUILD_FOR_DTM_IN_APP_==1)
rf_phy_direct_test();
#endif
LOG("SDK Version ID %08x \n",SDK_VER_RELEASE_ID);
LOG("rfClk %d rcClk %d sysClk %d tpCap[%02x %02x]\n",g_rfPhyClkSel,g_clk32K_config,g_system_clk,g_rfPhyTpCal0,g_rfPhyTpCal1);
LOG("sizeof(struct ll_pkt_desc) = %d, buf size = %d\n", sizeof(struct ll_pkt_desc), BLE_CONN_BUF_SIZE);
LOG("sizeof(g_pConnectionBuffer) = %d, sizeof(pConnContext) = %d, sizeof(largeHeap)=%d \n",\
sizeof(g_pConnectionBuffer), sizeof(pConnContext),sizeof(g_largeHeap));
app_main();
}
///////////////////////////////////// end ///////////////////////////////////////

View File

@ -0,0 +1,297 @@
/**************************************************************************************************
*******
**************************************************************************************************/
/*******************************************************************************
@file pwm.c
@brief Contains all functions support for pwm driver
@version 0.0
@date 30. Oct. 2017
@author Ding
*******************************************************************************/
#include "rom_sym_def.h"
#include "gpio.h"
#include "clock.h"
#include "pwm.h"
#include "pwrmgr.h"
/**************************************************************************************
@fn hal_pwm_init
@brief This function process for pwm initial
input parameters
@param PWMN_e pwmN : pwm channel
PWM_CLK_DIV_e pwmDiv : clock prescaler of PWM channel
PWM_CNT_MODE_e pwmMode : count mode of PWM channel
PWM_POLARITY_e pwmPolarity : output polarity setting of PWM channel
unsigned short cmpVal : the compare value of PWM channel
unsigned short cntTopVal : the counter top value of PWM channel
output parameters
@param None.
@return None.
**************************************************************************************/
void hal_pwm_init(
PWMN_e pwmN,
PWM_CLK_DIV_e pwmDiv,
PWM_CNT_MODE_e pwmMode,
PWM_POLARITY_e pwmPolarity)
{
hal_clk_gate_enable(MOD_PWM);
PWM_DISABLE_CH(pwmN);
PWM_SET_DIV(pwmN, pwmDiv);
PWM_SET_MODE(pwmN, pwmMode);
PWM_SET_POL(pwmN, pwmPolarity);
PWM_INSTANT_LOAD_CH(pwmN);
hal_pwrmgr_register(MOD_PWM, NULL, NULL);
}
static gpio_pin_e pwm_gpio_map[]=
{
GPIO_DUMMY,
GPIO_DUMMY,
GPIO_DUMMY,
GPIO_DUMMY,
GPIO_DUMMY,
GPIO_DUMMY,
};
/**************************************************************************************
@fn hal_pwm_open_channel
@brief This function process for pwm start working
input parameters
@param PWMN_e pwmN : pwm channel
gpio_pin_e pwmPin : pwm pin number
output parameters
@param None.
@return None.
**************************************************************************************/
void hal_pwm_open_channel(PWMN_e pwmN,gpio_pin_e pwmPin)
{
hal_gpio_fmux_set(pwmPin, (gpio_fmux_e)(FMUX_PWM0 + pwmN));
PWM_ENABLE_CH(pwmN);
pwm_gpio_map[pwmN] = pwmPin;
}
/**************************************************************************************
@fn hal_pwm_close_channel
@brief This function process for pwm stop working
input parameters
@param PWMN_e pwmN : pwm channel
output parameters
@param None.
@return None.
**************************************************************************************/
void hal_pwm_close_channel(PWMN_e pwmN)
{
if(pwm_gpio_map[pwmN] != GPIO_DUMMY)
{
hal_gpio_fmux(pwm_gpio_map[pwmN],Bit_DISABLE);
pwm_gpio_map[pwmN] = GPIO_DUMMY;
}
PWM_DISABLE_CH(pwmN);
}
/**************************************************************************************
@fn hal_pwm_destroy
@brief This function process for pwm clear and disable
input parameters
@param PWMN_e pwmN : pwm channel
output parameters
@param None.
@return None.
**************************************************************************************/
void hal_pwm_destroy(PWMN_e pwmN)
{
PWM_DISABLE_CH(pwmN);
PWM_NO_LOAD_CH(pwmN);
PWM_NO_INSTANT_LOAD_CH(pwmN);
PWM_SET_DIV(pwmN, 0);
PWM_SET_MODE(pwmN, 0);
PWM_SET_POL(pwmN, 0);
PWM_SET_TOP_VAL(pwmN, 0);
PWM_SET_CMP_VAL(pwmN, 0);
}
/**************************************************************************************
@fn hal_pwm_set_count_val
@brief This function process for change pwm count value
input parameters
@param PWMN_e pwmN : pwm channel
uint16_t cmpVal : the compare value of PWM channel
uint16_t cntTopVal : the counter top value of PWM channel
output parameters
@param None.
@return None.
**************************************************************************************/
void hal_pwm_set_count_val(PWMN_e pwmN, uint16_t cmpVal, uint16_t cntTopVal)
{
if(cmpVal > cntTopVal)
return;
PWM_NO_LOAD_CH(pwmN);
PWM_SET_CMP_VAL(pwmN, cmpVal);
PWM_SET_TOP_VAL(pwmN, cntTopVal);
PWM_LOAD_CH(pwmN);
}
static unsigned int pwm_en = 0;
void hal_pwm_start(void)
{
if(pwm_en == 0)
{
hal_pwrmgr_lock(MOD_PWM);
PWM_ENABLE_ALL;
pwm_en = 1;
}
}
void hal_pwm_stop(void)
{
if(pwm_en == 1)
{
hal_pwrmgr_unlock(MOD_PWM);
PWM_DISABLE_ALL;
pwm_en = 0;
hal_clk_gate_disable(MOD_PWM);
}
}
//------------------------------------------------------------
//new api,make use easily
typedef struct
{
bool enable;
bool ch_en[6];
pwm_ch_t ch[6];
} pwm_Ctx_t;
static pwm_Ctx_t pwmCtx =
{
.enable = FALSE,
.ch_en = {FALSE,FALSE,FALSE,FALSE,FALSE,FALSE},
};
void hal_pwm_module_init(void)
{
int i = 0;
if(pwmCtx.enable == TRUE)
return;
pwmCtx.enable = TRUE;
for(i = 0; i < 6; i++)
{
pwmCtx.ch_en[i] = FALSE;
pwmCtx.ch[i].pwmN = (PWMN_e)i;
pwmCtx.ch[i].pwmPin = GPIO_DUMMY;
pwmCtx.ch[i].pwmDiv = PWM_CLK_NO_DIV;
pwmCtx.ch[i].pwmMode = PWM_CNT_UP;
pwmCtx.ch[i].pwmPolarity = PWM_POLARITY_RISING;
pwmCtx.ch[i].cmpVal = 0;
pwmCtx.ch[i].cntTopVal = 0;
hal_pwm_destroy((PWMN_e)i);
}
hal_pwm_stop();
}
void hal_pwm_module_deinit(void)
{
int i = 0;
if(pwmCtx.enable == FALSE)
return;
pwmCtx.enable = FALSE;
for(i = 0; i < 6; i++)
{
pwmCtx.ch_en[i] = FALSE;
pwmCtx.ch[i].pwmN = (PWMN_e)i;
pwmCtx.ch[i].pwmPin = GPIO_DUMMY;
pwmCtx.ch[i].pwmDiv = PWM_CLK_NO_DIV;
pwmCtx.ch[i].pwmMode = PWM_CNT_UP;
pwmCtx.ch[i].pwmPolarity = PWM_POLARITY_RISING;
pwmCtx.ch[i].cmpVal = 0;
pwmCtx.ch[i].cntTopVal = 0;
hal_pwm_close_channel((PWMN_e)i);
hal_pwm_destroy((PWMN_e)i);
}
hal_pwm_stop();
}
void hal_pwm_ch_start(pwm_ch_t ch)
{
if(pwmCtx.enable == FALSE)
return;
if(pwmCtx.ch_en[ch.pwmN] == TRUE)
{
hal_pwm_set_count_val(ch.pwmN,ch.cmpVal,ch.cntTopVal);
PWM_SET_DIV(ch.pwmN, ch.pwmDiv);
}
else
{
hal_pwm_init(ch.pwmN,ch.pwmDiv,ch.pwmMode,ch.pwmPolarity);
hal_pwm_set_count_val(ch.pwmN,ch.cmpVal,ch.cntTopVal);
hal_pwm_open_channel(ch.pwmN,ch.pwmPin);
pwmCtx.ch_en[ch.pwmN] = TRUE;
hal_pwm_start();
}
}
void hal_pwm_ch_stop(pwm_ch_t ch)
{
if(pwmCtx.ch_en[ch.pwmN] == FALSE)
return;
else
{
pwmCtx.ch_en[ch.pwmN] = FALSE;
hal_pwm_destroy(ch.pwmN);
hal_pwm_close_channel(ch.pwmN);
}
}
bool hal_pwm_ch_enable(PWMN_e pwmN)
{
return pwmCtx.ch_en[pwmN];
}
pwm_ch_t hal_pwm_ch_reg(PWMN_e pwmN)
{
return pwmCtx.ch[pwmN];
}

View File

@ -0,0 +1,355 @@
/**************************************************************************************************
*******
**************************************************************************************************/
/*******************************************************************************
@file pwm.h
@brief Contains all functions support for pwm driver
@version 0.0
@date 30. Oct. 2017
@author Ding
*******************************************************************************/
#ifndef __PWM__H__
#define __PWM__H__
#ifdef __cplusplus
extern "C" {
#endif
#include "types.h"
#include "gpio.h"
#define PWM_ENABLE_ALL do{\
AP_PWM->pwmen |= BIT(0);\
AP_PWM->pwmen |= BIT(4);\
}while(0)
#define PWM_DISABLE_ALL do{\
AP_PWM->pwmen &= ~BIT(0);\
AP_PWM->pwmen &= ~BIT(4);\
}while(0)
#define PWM_ENABLE_CH_012 do{\
AP_PWM->pwmen |= BIT(8);\
AP_PWM->pwmen |= BIT(9);\
}while(0)
#define PWM_DISABLE_CH_012 do{\
AP_PWM->pwmen &= ~BIT(8);\
AP_PWM->pwmen &= ~BIT(9);\
}while(0)
#define PWM_ENABLE_CH_345 do{\
AP_PWM->pwmen |= BIT(10);\
AP_PWM->pwmen |= BIT(11);\
}while(0)
#define PWM_DISABLE_CH_345 do{\
AP_PWM->pwmen &= ~BIT(10);\
AP_PWM->pwmen &= ~BIT(11);\
}while(0)
#define PWM_ENABLE_CH_01 do{\
AP_PWM->pwmen |= BIT(12);\
AP_PWM->pwmen |= BIT(13);\
}while(0)
#define PWM_DISABLE_CH_01 do{\
AP_PWM->pwmen &= ~BIT(12);\
AP_PWM->pwmen &= ~BIT(13);\
}while(0)
#define PWM_ENABLE_CH_23 do{\
AP_PWM->pwmen |= BIT(14);\
AP_PWM->pwmen |= BIT(15);\
}while(0)
#define PWM_DISABLE_CH_23 do{\
AP_PWM->pwmen &= ~BIT(14);\
AP_PWM->pwmen &= ~BIT(15);\
}while(0)
#define PWM_ENABLE_CH_45 do{\
AP_PWM->pwmen |= BIT(16);\
AP_PWM->pwmen |= BIT(17);\
}while(0)
#define PWM_DISABLE_CH_45 do{\
AP_PWM->pwmen &= ~BIT(16);\
AP_PWM->pwmen &= ~BIT(17);\
}while(0)
#define PWM_INSTANT_LOAD_CH(n) subWriteReg(&(AP_PWM_CTRL(n)->ctrl0),31,31,1)
#define PWM_NO_INSTANT_LOAD_CH(n) subWriteReg(&(AP_PWM_CTRL(n)->ctrl0),31,31,0)
#define PWM_LOAD_CH(n) subWriteReg(&(AP_PWM_CTRL(n)->ctrl0),16,16,1)
#define PWM_NO_LOAD_CH(n) subWriteReg(&(AP_PWM_CTRL(n)->ctrl0),16,16,0)
#define PWM_SET_DIV(n,v) subWriteReg(&(AP_PWM_CTRL(n)->ctrl0),14,12,v)
#define PWM_SET_MODE(n,v) subWriteReg(&(AP_PWM_CTRL(n)->ctrl0),8,8,v)
#define PWM_SET_POL(n,v) subWriteReg(&(AP_PWM_CTRL(n)->ctrl0),4,4,v)
#define PWM_ENABLE_CH(n) subWriteReg(&(AP_PWM_CTRL(n)->ctrl0),0,0,1)
#define PWM_DISABLE_CH(n) subWriteReg(&(AP_PWM_CTRL(n)->ctrl0),0,0,0)
#define PWM_SET_CMP_VAL(n,v) subWriteReg(&(AP_PWM_CTRL(n)->ctrl1),31,16,v)
#define PWM_SET_TOP_VAL(n,v) subWriteReg(&(AP_PWM_CTRL(n)->ctrl1),15,0,v)
#define PWM_GET_CMP_VAL(n) ((AP_PWM_CTRL(n)->ctrl1 & 0xFFFF0000) >> 8)
#define PWM_GET_TOP_VAL(n) AP_PWM_CTRL(n)->ctrl1 & 0x0000FFFF
/*************************************************************
@brief enum variable, the number of PWM channels supported
*/
typedef enum
{
PWM_CH0 = 0,
PWM_CH1 = 1,
PWM_CH2 = 2,
PWM_CH3 = 3,
PWM_CH4 = 4,
PWM_CH5 = 5
} PWMN_e;
/*************************************************************
@brief enum variable used for PWM clock prescaler
*/
typedef enum
{
PWM_CLK_NO_DIV = 0,
PWM_CLK_DIV_2 = 1,
PWM_CLK_DIV_4 = 2,
PWM_CLK_DIV_8 = 3,
PWM_CLK_DIV_16 = 4,
PWM_CLK_DIV_32 = 5,
PWM_CLK_DIV_64 = 6,
PWM_CLK_DIV_128 = 7
} PWM_CLK_DIV_e;
/*************************************************************
@brief enum variable used for PWM work mode setting
*/
typedef enum
{
PWM_CNT_UP = 0,
PWM_CNT_UP_AND_DOWN = 1
} PWM_CNT_MODE_e;
/*************************************************************
@brief enum variable used for PWM output polarity setting
*/
typedef enum
{
PWM_POLARITY_RISING = 0,
PWM_POLARITY_FALLING = 1
} PWM_POLARITY_e;
/**************************************************************************************
@fn hal_pwm_init
@brief This function process for pwm initial
input parameters
@param PWMN_e pwmN : pwm channel
PWM_CLK_DIV_e pwmDiv : clock prescaler of PWM channel
PWM_CNT_MODE_e pwmMode : count mode of PWM channel
PWM_POLARITY_e pwmPolarity : output polarity setting of PWM channel
unsigned short cmpVal : the compare value of PWM channel
unsigned short cntTopVal : the counter top value of PWM channel
output parameters
@param None.
@return None.
**************************************************************************************/
void hal_pwm_init(PWMN_e pwmN, PWM_CLK_DIV_e pwmDiv,
PWM_CNT_MODE_e pwmMode, PWM_POLARITY_e pwmPolarity);
/**************************************************************************************
@fn hal_pwm_open_channel
@brief This function process for pwm start working
input parameters
@param PWMN_e pwmN : pwm channel
gpio_pin_e pwmPin : pwm pin number
output parameters
@param None.
@return None.
**************************************************************************************/
void hal_pwm_open_channel(PWMN_e pwmN,gpio_pin_e pwmPin);
/**************************************************************************************
@fn hal_pwm_close_channel
@brief This function process for pwm stop working
input parameters
@param PWMN_e pwmN : pwm channel
output parameters
@param None.
@return None.
**************************************************************************************/
void hal_pwm_close_channel(PWMN_e pwmN);
/**************************************************************************************
@fn hal_pwm_destroy
@brief This function process for pwm clear and disable
input parameters
@param PWMN_e pwmN : pwm channel
output parameters
@param None.
@return None.
**************************************************************************************/
void hal_pwm_destroy(PWMN_e pwmN);
/**************************************************************************************
@fn hal_pwm_set_count_val
@brief This function process for change pwm count value
input parameters
@param PWMN_e pwmN : pwm channel
uint16_t cmpVal : the compare value of PWM channel
uint16_t cntTopVal : the counter top value of PWM channel
output parameters
@param None.
@return None.
**************************************************************************************/
void hal_pwm_set_count_val(PWMN_e pwmN, uint16_t cmpVal, uint16_t cntTopVal);
/**************************************************************************************
@fn hal_pwm_start
@brief pwm start
input parameters
@param None.
output parameters
@param None.
@return None.
**************************************************************************************/
void hal_pwm_start(void);
/**************************************************************************************
@fn hal_pwm_stop
@brief pwm stop
input parameters
@param None.
output parameters
@param None.
@return None.
**************************************************************************************/
void hal_pwm_stop(void);
//new api,make use easily
typedef struct
{
PWMN_e pwmN;
gpio_pin_e pwmPin;
PWM_CLK_DIV_e pwmDiv;
PWM_CNT_MODE_e pwmMode;
PWM_POLARITY_e pwmPolarity;
uint16_t cmpVal;
uint16_t cntTopVal;
} pwm_ch_t;
/**************************************************************************************
@fn hal_pwm_module_init
@brief init pwm global variables
input parameters
@param None.
output parameters
@param None.
@return None.
**************************************************************************************/
void hal_pwm_module_init(void);
/**************************************************************************************
@fn hal_pwm_module_deinit
@brief deinit pwm global variables
input parameters
@param None.
output parameters
@param None.
@return None.
**************************************************************************************/
void hal_pwm_module_deinit(void);
/**************************************************************************************
@fn hal_pwm_ch_start
@brief config and make a pwm start to work
input parameters
@param pwm_ch_t ch: pwm channel
output parameters
@param None.
@return None.
**************************************************************************************/
void hal_pwm_ch_start(pwm_ch_t ch);
/**************************************************************************************
@fn hal_pwm_ch_stop
@brief make a pwm stop form working
input parameters
@param pwm_ch_t ch: pwm channel
output parameters
@param None.
@return None.
**************************************************************************************/
void hal_pwm_ch_stop(pwm_ch_t ch);
#ifdef __cplusplus
}
#endif
#endif

View File

@ -0,0 +1,4 @@
1》 替换 adc.c adc.h
2》 初始化通道
3》 设置clk subWriteReg(0x4000f07c, 2, 1, 2); //2 320k rate sample 1160K 0:80K
4》 等待 300us 获取数据

View File

@ -0,0 +1,159 @@
/**************************************************************************************************
*******
**************************************************************************************************/
#include "rom_sym_def.h"
#include "timer.h"
#include "error.h"
#include "clock.h"
#include "pwrmgr.h"
#include "jump_function.h"
AP_TIM_TypeDef* const TimerIndex[FREE_TIMER_NUMBER]= {AP_TIM5,AP_TIM6};
static ap_tm_hdl_t s_ap_callback = NULL;
static int hal_timer_clear_int(AP_TIM_TypeDef* TIMx)
{
return TIMx->EOI;
}
static void hal_timer_stop_counter(AP_TIM_TypeDef* TIMx)
{
TIMx->ControlReg = 0;
TIMx->LoadCount = 0; //0x0
TIMx->CurrentCount = 0;//0x4
}
static void hal_timer_set_loadtimer(AP_TIM_TypeDef* TIMx, int time)
{
if(time>0)
{
TIMx->ControlReg = 0x0;
TIMx->ControlReg = 0x2;
TIMx->LoadCount = 4*time;// 4MHz system timer, * 4 to convert to 1MHz timer
TIMx->ControlReg = 0x3;
}
else
{
TIMx->ControlReg = 0x0;
}
}
void __attribute__((used)) hal_TIMER5_IRQHandler(void)
{
if(AP_TIM5->status & 0x1)
{
hal_timer_clear_int(AP_TIM5);
if(s_ap_callback)
s_ap_callback(HAL_EVT_TIMER_5);
}
}
void __attribute__((used)) hal_TIMER6_IRQHandler(void)
{
if(AP_TIM6->status & 0x1)
{
hal_timer_clear_int(AP_TIM6);
if(s_ap_callback)
s_ap_callback(HAL_EVT_TIMER_6);
}
}
static void hal_timer_wakeup_handler(void)
{
if(s_ap_callback)
s_ap_callback(HAL_EVT_WAKEUP);
}
void hal_timer_sleep_handler(void)
{
if(s_ap_callback)
s_ap_callback(HAL_EVT_SLEEP);
}
int hal_timer_mask_int(User_Timer_e timeId, bool en)
{
volatile AP_TIM_TypeDef* TIMx;
TIMx = TimerIndex[timeId-AP_TIMER_ID_5];
if(en)
TIMx->ControlReg |= (1 << 2);
else
TIMx->ControlReg &= ~(1 << 2);
return PPlus_SUCCESS;
}
int hal_timer_set(User_Timer_e timeId, uint32_t us)
{
uint32_t time = us;
switch(timeId)
{
case AP_TIMER_ID_5:
JUMP_FUNCTION(TIM5_IRQ_HANDLER) = (uint32_t)&hal_TIMER5_IRQHandler;
NVIC_EnableIRQ((IRQn_Type)TIM5_IRQn);
// NVIC_SetPriority((IRQn_Type)TIM5_IRQn, IRQ_PRIO_HAL);
NVIC_SetPriority((IRQn_Type)TIM5_IRQn, IRQ_PRIO_REALTIME);
hal_timer_set_loadtimer(AP_TIM5, time);
hal_clk_gate_enable(MOD_TIMER5);
break;
case AP_TIMER_ID_6:
JUMP_FUNCTION(TIM6_IRQ_HANDLER) = (uint32_t)&hal_TIMER6_IRQHandler;
NVIC_EnableIRQ((IRQn_Type)TIM6_IRQn);
// NVIC_SetPriority((IRQn_Type)TIM6_IRQn, IRQ_PRIO_HAL);
NVIC_SetPriority((IRQn_Type)TIM6_IRQn, IRQ_PRIO_REALTIME);
hal_timer_set_loadtimer(AP_TIM6, time);
hal_clk_gate_enable(MOD_TIMER6);
break;
default:
return PPlus_ERR_INVALID_PARAM;
}
return PPlus_SUCCESS;
}
int hal_timer_stop(User_Timer_e timeId)
{
switch(timeId)
{
case AP_TIMER_ID_5:
JUMP_FUNCTION(TIM5_IRQ_HANDLER) = 0;
hal_timer_stop_counter(AP_TIM5);
NVIC_DisableIRQ((IRQn_Type)TIM5_IRQn);
hal_clk_gate_disable(MOD_TIMER5);
break;
case AP_TIMER_ID_6:
JUMP_FUNCTION(TIM6_IRQ_HANDLER) = 0;
hal_timer_stop_counter(AP_TIM6);
NVIC_DisableIRQ((IRQn_Type)TIM6_IRQn);
hal_clk_gate_disable(MOD_TIMER6);
break;
default:
return PPlus_ERR_INVALID_PARAM;
}
return PPlus_SUCCESS;
}
int hal_timer_init(ap_tm_hdl_t callback)
{
s_ap_callback = callback;
hal_timer_stop(AP_TIMER_ID_5);
hal_timer_stop(AP_TIMER_ID_6);
return hal_pwrmgr_register(MOD_TIMER, hal_timer_sleep_handler, hal_timer_wakeup_handler);
}
int hal_timer_deinit(void)
{
s_ap_callback = NULL;
return hal_pwrmgr_unregister(MOD_TIMER);
}

View File

@ -0,0 +1,60 @@
/**************************************************************************************************
*******
**************************************************************************************************/
#ifndef __TIMER_H__
#define __TIMER_H__
#ifdef __cplusplus
extern "C" {
#endif
#include "types.h"
#include "bus_dev.h"
#define FREE_TIMER_NUMBER 2
typedef enum
{
AP_TIMER_ID_5 = 5,
AP_TIMER_ID_6 = 6,
} User_Timer_e;
enum
{
HAL_EVT_TIMER_5 = AP_TIMER_ID_5,
HAL_EVT_TIMER_6 = AP_TIMER_ID_6,
HAL_EVT_WAKEUP = 0x10,
HAL_EVT_SLEEP
};
typedef void(*ap_tm_hdl_t)(uint8_t evt);
int hal_timer_init(ap_tm_hdl_t callback);
int hal_timer_deinit(void);
int hal_timer_set(User_Timer_e timeId, uint32_t us);
int hal_timer_mask_int(User_Timer_e timeId, bool en);
int hal_timer_stop(User_Timer_e timeId);
void __attribute__((used)) hal_TIMER5_IRQHandler(void);
void __attribute__((used)) hal_TIMER6_IRQHandler(void);
extern void set_timer(AP_TIM_TypeDef* TIMx, int time);
extern uint32_t read_current_fine_time(void);
extern uint32 read_LL_remainder_time(void);
#ifndef BASE_TIME_UINTS
#define BASE_TIME_UNITS (0x3fffff)
#endif
#ifdef __cplusplus
}
#endif
#endif

Binary file not shown.