Update CEC1302 peripheral library version.

This commit is contained in:
Richard Barry 2016-04-18 15:52:19 +00:00
parent 057b38ad23
commit da6c95edae
27 changed files with 4035 additions and 7221 deletions

File diff suppressed because one or more lines are too long

View File

@ -89,7 +89,7 @@
<sRfunc>1</sRfunc>
<sRbox>1</sRbox>
<tLdApp>1</tLdApp>
<tGomain>1</tGomain>
<tGomain>0</tGomain>
<tRbreak>1</tRbreak>
<tRwatch>1</tRwatch>
<tRmem>1</tRmem>
@ -179,7 +179,7 @@
<DebugFlag>
<trace>0</trace>
<periodic>1</periodic>
<aLwin>0</aLwin>
<aLwin>1</aLwin>
<aCover>0</aCover>
<aSer1>0</aSer1>
<aSer2>0</aSer2>
@ -245,7 +245,7 @@
<Group>
<GroupName>main_and_config</GroupName>
<tvExp>1</tvExp>
<tvExp>0</tvExp>
<tvExpOptDlg>0</tvExpOptDlg>
<cbSel>0</cbSel>
<RteFlg>0</RteFlg>
@ -369,7 +369,7 @@
<Group>
<GroupName>main_low_power</GroupName>
<tvExp>1</tvExp>
<tvExp>0</tvExp>
<tvExpOptDlg>0</tvExpOptDlg>
<cbSel>0</cbSel>
<RteFlg>0</RteFlg>
@ -401,7 +401,7 @@
<Group>
<GroupName>main_full</GroupName>
<tvExp>1</tvExp>
<tvExp>0</tvExp>
<tvExpOptDlg>0</tvExpOptDlg>
<cbSel>0</cbSel>
<RteFlg>0</RteFlg>

View File

@ -1,9 +1,10 @@
/*
* Default linker script for GCC MEC1322
* Default linker script for GCC CEC1302
* Based upon linker scripts from GNU ARM Eclipse plug-in
*/
INCLUDE mem.ld
__SRAM_segment_end__ = ORIGIN( RAM ) + LENGTH( RAM );
/*
* The '__stack' definition is required by crt0, do not remove it.
@ -58,7 +59,7 @@ SECTIONS
* For Cortex-M devices, the beginning of the startup code is stored in
* the .isr_vector section, which goes to ROM
*/
.isr_vector :
{
. = ALIGN(4);
@ -66,8 +67,8 @@ SECTIONS
KEEP(*(.isr_vector))
. = ALIGN(4);
} >ROM
.text :
{
. = ALIGN(4);

View File

@ -33,43 +33,16 @@
.syntax unified
.arch armv7e-m
.section .stack
.align 3
.equ ulMainStackSize, 200 * 4
.equ Stack_Size, 0x004
.globl __StackTop
.globl __StackLimit
.extern ulMainStack
__StackLimit:
.space Stack_Size
.size __StackLimit, . - __StackLimit
__StackTop:
.size __StackTop, . - __StackTop
.section .heap
.align 3
#ifdef __HEAP_SIZE
.equ Heap_Size, __HEAP_SIZE
#else
.equ Heap_Size, 0
#endif
.globl __HeapBase
.globl __HeapLimit
__HeapBase:
.if Heap_Size
.space Heap_Size
.endif
.size __HeapBase, . - __HeapBase
__HeapLimit:
.size __HeapLimit, . - __HeapLimit
.extern __SRAM_segment_end__
.section .isr_vector,"a",%progbits
.align 4
.globl __isr_vector
.global __Vectors
.type __Vectors, %object
.size __Vectors, .-__Vectors
__Vectors:
.long ulMainStack + ulMainStackSize /* Top of Stack */
__isr_vector:
.long __SRAM_segment_end__ - 4 /* Top of Stack at top of RAM*/
.long Reset_Handler /* Reset Handler */
.long NMI_Handler /* NMI Handler */
.long HardFault_Handler /* Hard Fault Handler */
@ -207,9 +180,6 @@ Reset_Handler:
*
* All addresses must be aligned to 4 bytes boundary.
*/
ldr sp, =ulMainStack + ulMainStackSize
sub sp, sp, #4
ldr r1, =__etext
ldr r2, =__data_start__
ldr r3, =__data_end__
@ -280,10 +250,10 @@ Default_Handler:
def_irq_handler MemManage_Handler
def_irq_handler BusFault_Handler
def_irq_handler UsageFault_Handler
/* def_irq_handler SVC_Handler */
def_irq_handler SVC_Handler
def_irq_handler DebugMon_Handler
/* def_irq_handler PendSV_Handler */
/* def_irq_handler SysTick_Handler */
def_irq_handler PendSV_Handler
def_irq_handler SysTick_Handler
def_irq_handler DEF_IRQHandler
def_irq_handler NVIC_Handler_I2C0

View File

@ -22,12 +22,12 @@
* @{
*/
/** @file pwm_c_wrapper.cpp
\brief the pwm component C wrapper
\brief the pwm component C wrapper
This program is designed to allow the other C programs to be able to use this component
There are entry points for all C wrapper API implementation
<b>Platform:</b> This is ARC-based component
<b>Platform:</b> This is ARC-based component
<b>Toolset:</b> Metaware IDE(8.5.1)
<b>Reference:</b> smsc_reusable_fw_requirement.doc */
@ -41,7 +41,7 @@
* AUTHOR: $Author: akrishnan $
*
* Revision history (latest first):
* #3 2011/05/09 martin_y update to Metaware IDE(8.5.1)
* #3 2011/05/09 martin_y update to Metaware IDE(8.5.1)
* #2 2011/03/25 martin_y support FPGA build 058 apps
* #1 2011/03/23 martin_y branch from MEC1618 sample code: MEC1618_evb_sample_code_build_0200
***********************************************************************************
@ -55,12 +55,6 @@
#define MMCR_PCR_PROCESSOR_CLOCK_CONTROL (*(uint32_t *)(ADDR_PCR_PROCESSOR_CLOCK_CONTROL))
#define CPU_CLOCK_DIVIDER 1
/* The start up code is configured to use the following array as the stack used
by main(), which will then also get used by FreeRTOS interrupt handlers after
the scheduler has been started. */
#warning If the array size is modified here then ulMainStackSize must also be modified in startup_ARMCM4.S.
volatile uint32_t ulMainStack[ 200 ];
/******************************************************************************/
/** system_set_ec_clock
* Set CPU speed

View File

@ -397,7 +397,7 @@
<GroupNumber>5</GroupNumber>
<FileNumber>14</FileNumber>
<FileType>1</FileType>
<tvExp>1</tvExp>
<tvExp>0</tvExp>
<tvExpOptDlg>0</tvExpOptDlg>
<bDave2>0</bDave2>
<PathWithFileName>..\main_full\main_full.c</PathWithFileName>
@ -573,7 +573,7 @@
<GroupNumber>6</GroupNumber>
<FileNumber>28</FileNumber>
<FileType>1</FileType>
<tvExp>0</tvExp>
<tvExp>1</tvExp>
<tvExpOptDlg>0</tvExpOptDlg>
<bDave2>0</bDave2>
<PathWithFileName>..\peripheral_library\basic_timer\btimer_api.c</PathWithFileName>

View File

@ -19,10 +19,10 @@
;* OF THESE TERMS.
;******************************************************************************
; */
;/** @file startup_MEC1322.s
; *MEC1322 API Test: startup and vector table
;/** @file startup_CEC1302.s
; *CEC1302 API Test: startup and vector table
; */
;/** @defgroup startup_MEC1322
;/** @defgroup startup_CEC1302
; * @{
; */
@ -55,7 +55,7 @@ __initial_sp
; <o> Heap Size (in Bytes) <0x0-0xFFFFFFFF:8>
; </h>
Heap_Size EQU 0x00000000
Heap_Size EQU 0x00000000
AREA HEAP, NOINIT, READWRITE, ALIGN=3
__heap_base
@ -88,7 +88,7 @@ __Vectors DCD __initial_sp ; Top of Stack
DCD PendSV_Handler ; PendSV Handler
DCD SysTick_Handler ; SysTick Handler
; MEC1322 External Interrupts
; CEC1302 External Interrupts
DCD NVIC_Handler_I2C0 ; 40h: 0, I2C/SMBus 0
DCD NVIC_Handler_I2C1 ; 44h: 1, I2C/SMBus 1
DCD NVIC_Handler_I2C2 ; 48h: 2, I2C/SMBus 2
@ -152,7 +152,7 @@ __Vectors DCD __initial_sp ; Top of Stack
DCD NVIC_Handler_GIRQ11 ; 130h: 60, GIRQ11
DCD NVIC_Handler_GIRQ12 ; 134h: 61, GIRQ12
DCD NVIC_Handler_GIRQ13 ; 138h: 62, GIRQ13
DCD NVIC_Handler_GIRQ14 ; 13Ch: 63, GIRQ14
DCD NVIC_Handler_GIRQ14 ; 13Ch: 63, GIRQ14
DCD NVIC_Handler_GIRQ15 ; 140h: 64, GIRQ15
DCD NVIC_Handler_GIRQ16 ; 144h: 65, GIRQ16
DCD NVIC_Handler_GIRQ17 ; 148h: 66, GIRQ17
@ -178,9 +178,9 @@ __Vectors DCD __initial_sp ; Top of Stack
DCD NVIC_Handler_PKE_ERR ; 198h: 86, PKE Error
DCD NVIC_Handler_PKE_END ; 19Ch: 87, PKE End
DCD NVIC_Handler_TRNG ; 1A0h: 88, TRandom Num Gen
DCD NVIC_Handler_AES ; 1A4h: 89, AES
DCD NVIC_Handler_AES ; 1A4h: 89, AES
DCD NVIC_Handler_HASH ; 1A8h: 90, HASH
AREA ROMTABLE, CODE, READONLY
THUMB
@ -198,16 +198,16 @@ Reset_Handler PROC
EXPORT Reset_Handler [WEAK]
CPSID i
; support code is loaded from ROM loader
LDR SP, =__initial_sp
; configure CPU speed
; support code is loaded from ROM loader
LDR SP, =__initial_sp
; configure CPU speed
LDR R0, =system_set_ec_clock
BLX R0
LDR SP, =__initial_sp
; support FPU
; support FPU
IF {CPU} = "Cortex-M4.fp"
LDR R0, =0xE000ED88 ; Enable CP10,CP11
LDR R1,[R0]
@ -275,7 +275,7 @@ SysTick_Handler PROC
Default_Handler PROC
; External MEC1322 NVIC Interrupt Inputs
; External CEC1302 NVIC Interrupt Inputs
EXPORT NVIC_Handler_I2C0 [WEAK]
EXPORT NVIC_Handler_I2C1 [WEAK]
EXPORT NVIC_Handler_I2C2 [WEAK]
@ -468,14 +468,14 @@ NVIC_Handler_HASH
; User Initial Stack & Heap
IF :DEF:__MICROLIB
EXPORT __initial_sp
EXPORT __heap_base
EXPORT __heap_limit
EXPORT __stack_bottom
ELSE
IMPORT __use_two_region_memory
EXPORT __user_initial_stackheap
__user_initial_stackheap

View File

@ -165,7 +165,7 @@ static void prvSetupHardware( void )
extern void system_set_ec_clock( void );
extern unsigned long __Vectors[];
/* Disable M4 write buffer: fix MEC1322 hardware bug. */
/* Disable M4 write buffer: fix CEC1302 hardware bug. */
mainNVIC_AUX_ACTLR |= 0x07;
/* Enable alternative NVIC vectors. */

View File

@ -117,8 +117,13 @@ timers must still be above the tick interrupt priority. */
#define tmrMEDIUM_PRIORITY ( configLIBRARY_MAX_SYSCALL_INTERRUPT_PRIORITY + 0 )
#define tmrHIGHER_PRIORITY ( configLIBRARY_MAX_SYSCALL_INTERRUPT_PRIORITY - 1 )
/* Hardware register locations. */
#define tmrGIRQ23_ENABLE_SET ( * ( volatile uint32_t * ) 0x4000C130 )
/* Hardware register locations and bit definitions to enable the btimer
interrupts. */
#define tmrGIRQ23_ENABLE_SET ( * ( volatile uint32_t * ) 0x4000C130 )
#define tmrGIRQ23_BIT_TIMER0 ( 1UL << 0UL )
#define tmrGIRQ23_BIT_TIMER1 ( 1UL << 1UL )
#define tmrGIRQ23_BIT_TIMER2 ( 1UL << 2UL )
#define tmrGIRQ23_TIMER_BITS ( tmrGIRQ23_BIT_TIMER0 | tmrGIRQ23_BIT_TIMER1 | tmrGIRQ23_BIT_TIMER2 )
#define tmrRECORD_NESTING_DEPTH() \
ulNestingDepth++; \
@ -138,13 +143,12 @@ const uint32_t ulTimer0Count = configCPU_CLOCK_HZ / tmrTIMER_0_FREQUENCY;
const uint32_t ulTimer1Count = configCPU_CLOCK_HZ / tmrTIMER_1_FREQUENCY;
const uint32_t ulTimer2Count = configCPU_CLOCK_HZ / tmrTIMER_2_FREQUENCY;
tmrGIRQ23_ENABLE_SET = 0x03;
tmrGIRQ23_ENABLE_SET = tmrGIRQ23_TIMER_BITS;
/* Initialise the three timers as described at the top of this file, and
enable their interrupts in the NVIC. */
btimer_init( tmrTIMER_CHANNEL_0, BTIMER_AUTO_RESTART | BTIMER_COUNT_DOWN | BTIMER_INT_EN, 0, ulTimer0Count, ulTimer0Count );
btimer_interrupt_status_get_clr( tmrTIMER_CHANNEL_0 );
enable_timer0_irq();
NVIC_SetPriority( TIMER0_IRQn, tmrLOWER_PRIORITY ); //0xc0 into 0xe000e431
NVIC_ClearPendingIRQ( TIMER0_IRQn );
NVIC_EnableIRQ( TIMER0_IRQn );
@ -152,7 +156,6 @@ const uint32_t ulTimer2Count = configCPU_CLOCK_HZ / tmrTIMER_2_FREQUENCY;
btimer_init( tmrTIMER_CHANNEL_1, BTIMER_AUTO_RESTART | BTIMER_COUNT_DOWN | BTIMER_INT_EN, 0, ulTimer1Count, ulTimer1Count );
btimer_interrupt_status_get_clr( tmrTIMER_CHANNEL_1 );
enable_timer1_irq();
NVIC_SetPriority( TIMER1_IRQn, tmrMEDIUM_PRIORITY ); //0xa0 into 0xe000e432
NVIC_ClearPendingIRQ( TIMER1_IRQn );
NVIC_EnableIRQ( TIMER1_IRQn );
@ -160,7 +163,6 @@ const uint32_t ulTimer2Count = configCPU_CLOCK_HZ / tmrTIMER_2_FREQUENCY;
btimer_init( tmrTIMER_CHANNEL_2, BTIMER_AUTO_RESTART | BTIMER_COUNT_DOWN | BTIMER_INT_EN, 0, ulTimer2Count, ulTimer2Count );
btimer_interrupt_status_get_clr( tmrTIMER_CHANNEL_2 );
enable_timer2_irq();
NVIC_SetPriority( TIMER2_IRQn, tmrHIGHER_PRIORITY );
NVIC_ClearPendingIRQ( TIMER2_IRQn );
NVIC_EnableIRQ( TIMER2_IRQn );

View File

@ -76,6 +76,8 @@
/* Library includes. */
#include "common_lib.h"
#include "peripheral_library/interrupt/interrupt.h"
#include "peripheral_library/basic_timer/btimer.h"
/* This file contains functions that will override the default implementations
in the RTOS port layer. Therefore only build this file if the low power demo
@ -170,13 +172,14 @@ void NVIC_Handler_HIB_TMR( void )
#if( lpINCLUDE_TEST_TIMER == 1 )
#define lpGIRQ23_ENABLE_SET ( * ( uint32_t * ) 0x4000C130 )
#define tmrGIRQ23_BIT_TIMER0 ( 1UL << 0UL )
static void prvSetupBasicTimer( void )
{
const uint8_t ucTimerChannel = 0;
const uint32_t ulTimer0Count = configCPU_CLOCK_HZ / 10;
lpGIRQ23_ENABLE_SET = 0x03;
lpGIRQ23_ENABLE_SET = tmrGIRQ23_BIT_TIMER0;
/* To fully test the low power tick processing it is necessary to sometimes
bring the MCU out of its sleep state by a method other than the tick
@ -184,7 +187,6 @@ void NVIC_Handler_HIB_TMR( void )
purpose. */
btimer_init( ucTimerChannel, BTIMER_AUTO_RESTART | BTIMER_COUNT_DOWN | BTIMER_INT_EN, 0, ulTimer0Count, ulTimer0Count );
btimer_interrupt_status_get_clr( ucTimerChannel );
enable_timer0_irq();
NVIC_SetPriority( TIMER0_IRQn, ucTimerChannel );
NVIC_ClearPendingIRQ( TIMER0_IRQn );
NVIC_EnableIRQ( TIMER0_IRQn );

View File

@ -1,194 +1,194 @@
/*
**********************************************************************************
* © 2013 Microchip Technology Inc. and its subsidiaries.
* You may use this software and any derivatives exclusively with
* Microchip products.
* THIS SOFTWARE IS SUPPLIED BY MICROCHIP "AS IS".
* NO WARRANTIES, WHETHER EXPRESS, IMPLIED OR STATUTORY, APPLY TO THIS SOFTWARE,
* INCLUDING ANY IMPLIED WARRANTIES OF NON-INFRINGEMENT, MERCHANTABILITY,
* AND FITNESS FOR A PARTICULAR PURPOSE, OR ITS INTERACTION WITH MICROCHIP
* PRODUCTS, COMBINATION WITH ANY OTHER PRODUCTS, OR USE IN ANY APPLICATION.
* IN NO EVENT WILL MICROCHIP BE LIABLE FOR ANY INDIRECT, SPECIAL, PUNITIVE,
* INCIDENTAL OR CONSEQUENTIAL LOSS, DAMAGE, COST OR EXPENSE OF ANY KIND
* WHATSOEVER RELATED TO THE SOFTWARE, HOWEVER CAUSED, EVEN IF MICROCHIP HAS
* BEEN ADVISED OF THE POSSIBILITY OR THE DAMAGES ARE FORESEEABLE.
* TO THE FULLEST EXTENT ALLOWED BY LAW, MICROCHIP'S TOTAL LIABILITY ON ALL
* CLAIMS IN ANY WAY RELATED TO THIS SOFTWARE WILL NOT EXCEED THE AMOUNT OF
* FEES, IF ANY, THAT YOU HAVE PAID DIRECTLY TO MICROCHIP FOR THIS SOFTWARE.
* MICROCHIP PROVIDES THIS SOFTWARE CONDITIONALLY UPON YOUR ACCEPTANCE
* OF THESE TERMS.
**********************************************************************************
* ARM_REG.h
* This is the header to define Cortex-M3 system control & status registers
**********************************************************************************
* SMSC version control information (Perforce):
*
* FILE: $File: //depot_pcs/FWEng/Release/projects/CEC1302_CLIB/release2/Source/hw_blks/common/include/ARM_REG.h $
* REVISION: $Revision: #1 $
* DATETIME: $DateTime: 2015/12/23 15:37:58 $
* AUTHOR: $Author: akrishnan $
*
* Revision history (latest first):
* #xx
***********************************************************************************
*/
/******************************************************************************/
/** @defgroup ARM_REG ARM_REG
* @{
*/
/** @file ARM_REG.h
* \brief ARM Cortex-M3 registers header file
* \author KBCEC Team
*
* This file contains ARM Cortex-M3 system control & status registers.
******************************************************************************/
#ifndef ARM_REG_H_
#define ARM_REG_H_
#define REG8(x) (*((volatile unsigned char *)(x)))
#define REG16(x) (*((volatile unsigned short *)(x)))
#define REG32(x) (*((volatile unsigned long *)(x)))
/* NVIC Registers */
#define NVIC_INT_TYPE REG32(0xE000E004)
#define NVIC_AUX_ACTLR REG32(0xE000E008)
#define WR_BUF_DISABLE (1 << 1)
#define NVIC_ST_CTRL REG32(0xE000E010)
#define ST_ENABLE (1 << 0)
#define ST_TICKINT (1 << 1)
#define ST_CLKSOURCE (1 << 2)
#define ST_COUNTFLAG (1 << 3)
#define NVIC_ST_RELOAD REG32(0xE000E014)
#define NVIC_ST_CURRENT REG32(0xE000E018)
#define NVIC_ST_CALIB REG32(0xE000E01C)
#define NVIC_ENABLE0 REG32(0xE000E100)
#define NVIC_ENABLE1 REG32(0xE000E104)
#define NVIC_ENABLE2 REG32(0xE000E108)
#define NVIC_ENABLE3 REG32(0xE000E10C)
#define NVIC_ENABLE4 REG32(0xE000E110)
#define NVIC_ENABLE5 REG32(0xE000E114)
#define NVIC_ENABLE6 REG32(0xE000E118)
#define NVIC_ENABLE7 REG32(0xE000E11C)
#define NVIC_DISABLE0 REG32(0xE000E180)
#define NVIC_DISABLE1 REG32(0xE000E184)
#define NVIC_DISABLE2 REG32(0xE000E188)
#define NVIC_DISABLE3 REG32(0xE000E18C)
#define NVIC_DISABLE4 REG32(0xE000E190)
#define NVIC_DISABLE5 REG32(0xE000E194)
#define NVIC_DISABLE6 REG32(0xE000E198)
#define NVIC_DISABLE7 REG32(0xE000E19C)
#define NVIC_PEND0 REG32(0xE000E200)
#define NVIC_PEND1 REG32(0xE000E204)
#define NVIC_PEND2 REG32(0xE000E208)
#define NVIC_PEND3 REG32(0xE000E20C)
#define NVIC_PEND4 REG32(0xE000E210)
#define NVIC_PEND5 REG32(0xE000E214)
#define NVIC_PEND6 REG32(0xE000E218)
#define NVIC_PEND7 REG32(0xE000E21C)
#define NVIC_UNPEND0 REG32(0xE000E280)
#define NVIC_UNPEND1 REG32(0xE000E284)
#define NVIC_UNPEND2 REG32(0xE000E288)
#define NVIC_UNPEND3 REG32(0xE000E28C)
#define NVIC_UNPEND4 REG32(0xE000E290)
#define NVIC_UNPEND5 REG32(0xE000E294)
#define NVIC_UNPEND6 REG32(0xE000E298)
#define NVIC_UNPEND7 REG32(0xE000E29C)
#define NVIC_ACTIVE0 REG32(0xE000E300)
#define NVIC_ACTIVE1 REG32(0xE000E304)
#define NVIC_ACTIVE2 REG32(0xE000E308)
#define NVIC_ACTIVE3 REG32(0xE000E30C)
#define NVIC_ACTIVE4 REG32(0xE000E310)
#define NVIC_ACTIVE5 REG32(0xE000E314)
#define NVIC_ACTIVE6 REG32(0xE000E318)
#define NVIC_ACTIVE7 REG32(0xE000E31C)
#define NVIC_PRI0 REG32(0xE000E400)
#define NVIC_PRI1 REG32(0xE000E404)
#define NVIC_PRI2 REG32(0xE000E408)
#define NVIC_PRI3 REG32(0xE000E40C)
#define NVIC_PRI4 REG32(0xE000E410)
#define NVIC_PRI5 REG32(0xE000E414)
#define NVIC_PRI6 REG32(0xE000E418)
#define NVIC_PRI7 REG32(0xE000E41C)
#define NVIC_PRI8 REG32(0xE000E420)
#define NVIC_PRI9 REG32(0xE000E424)
#define NVIC_PRI10 REG32(0xE000E428)
#define NVIC_PRI11 REG32(0xE000E42C)
#define NVIC_PRI12 REG32(0xE000E430)
#define NVIC_PRI13 REG32(0xE000E434)
#define NVIC_PRI14 REG32(0xE000E438)
#define NVIC_PRI15 REG32(0xE000E43C)
#define NVIC_PRI16 REG32(0xE000E440)
#define NVIC_PRI17 REG32(0xE000E444)
#define NVIC_PRI18 REG32(0xE000E448)
#define NVIC_PRI19 REG32(0xE000E44C)
#define NVIC_PRI20 REG32(0xE000E450)
#define NVIC_PRI21 REG32(0xE000E454)
#define NVIC_PRI22 REG32(0xE000E458)
#define NVIC_PRI23 REG32(0xE000E45C)
#define NVIC_PRI24 REG32(0xE000E460)
#define NVIC_PRI25 REG32(0xE000E464)
#define NVIC_PRI26 REG32(0xE000E468)
#define NVIC_PRI27 REG32(0xE000E46C)
#define NVIC_PRI28 REG32(0xE000E470)
#define NVIC_PRI29 REG32(0xE000E474)
#define NVIC_PRI30 REG32(0xE000E478)
#define NVIC_PRI31 REG32(0xE000E47C)
#define NVIC_PRI32 REG32(0xE000E480)
#define NVIC_PRI33 REG32(0xE000E484)
#define NVIC_PRI34 REG32(0xE000E488)
#define NVIC_PRI35 REG32(0xE000E48C)
#define NVIC_PRI36 REG32(0xE000E490)
#define NVIC_PRI37 REG32(0xE000E494)
#define NVIC_PRI38 REG32(0xE000E498)
#define NVIC_PRI39 REG32(0xE000E49C)
#define NVIC_PRI40 REG32(0xE000E4A0)
#define NVIC_PRI41 REG32(0xE000E4A4)
#define NVIC_PRI42 REG32(0xE000E4A8)
#define NVIC_PRI43 REG32(0xE000E4AC)
#define NVIC_PRI44 REG32(0xE000E4B0)
#define NVIC_PRI45 REG32(0xE000E4B4)
#define NVIC_PRI46 REG32(0xE000E4B8)
#define NVIC_PRI47 REG32(0xE000E4BC)
#define NVIC_PRI48 REG32(0xE000E4C0)
#define NVIC_PRI49 REG32(0xE000E4C4)
#define NVIC_PRI50 REG32(0xE000E4C8)
#define NVIC_PRI51 REG32(0xE000E4CC)
#define NVIC_PRI52 REG32(0xE000E4D0)
#define NVIC_PRI53 REG32(0xE000E4D4)
#define NVIC_PRI54 REG32(0xE000E4D8)
#define NVIC_PRI55 REG32(0xE000E4DC)
#define NVIC_PRI56 REG32(0xE000E4E0)
#define NVIC_PRI57 REG32(0xE000E4E4)
#define NVIC_PRI58 REG32(0xE000E4E8)
#define NVIC_PRI59 REG32(0xE000E4EC)
#define NVIC_CPUID REG32(0xE000ED00)
#define NVIC_INT_CTRL REG32(0xE000ED04)
#define NVIC_VECT_TABLE REG32(0xE000ED08)
#define NVIC_AP_INT_RST REG32(0xE000ED0C)
#define NVIC_SYS_CTRL REG32(0xE000ED10)
#define NVIC_CFG_CTRL REG32(0xE000ED14)
#define NVIC_SYS_H_PRI1 REG32(0xE000ED18)
#define NVIC_SYS_H_PRI2 REG32(0xE000ED1C)
#define NVIC_SYS_H_PRI3 REG32(0xE000ED20)
#define NVIC_SYS_H_CTRL REG32(0xE000ED24)
#define NVIC_FAULT_STA REG32(0xE000ED28)
#define NVIC_HARD_F_STA REG32(0xE000ED2C)
#define NVIC_DBG_F_STA REG32(0xE000ED30)
#define NVIC_MM_F_ADR REG32(0xE000ED34)
#define NVIC_BUS_F_ADR REG32(0xE000ED38)
#define NVIC_SW_TRIG REG32(0xE000EF00)
/* MPU Registers */
#define MPU_TYPE REG32(0xE000ED90)
#define MPU_CTRL REG32(0xE000ED94)
#define MPU_RG_NUM REG32(0xE000ED98)
#define MPU_RG_ADDR REG32(0xE000ED9C)
#define MPU_RG_AT_SZ REG32(0xE000EDA0)
#endif /* #ifndef ARM_REG_H_ */
/** @}
*/
/*
**********************************************************************************
* © 2013 Microchip Technology Inc. and its subsidiaries.
* You may use this software and any derivatives exclusively with
* Microchip products.
* THIS SOFTWARE IS SUPPLIED BY MICROCHIP "AS IS".
* NO WARRANTIES, WHETHER EXPRESS, IMPLIED OR STATUTORY, APPLY TO THIS SOFTWARE,
* INCLUDING ANY IMPLIED WARRANTIES OF NON-INFRINGEMENT, MERCHANTABILITY,
* AND FITNESS FOR A PARTICULAR PURPOSE, OR ITS INTERACTION WITH MICROCHIP
* PRODUCTS, COMBINATION WITH ANY OTHER PRODUCTS, OR USE IN ANY APPLICATION.
* IN NO EVENT WILL MICROCHIP BE LIABLE FOR ANY INDIRECT, SPECIAL, PUNITIVE,
* INCIDENTAL OR CONSEQUENTIAL LOSS, DAMAGE, COST OR EXPENSE OF ANY KIND
* WHATSOEVER RELATED TO THE SOFTWARE, HOWEVER CAUSED, EVEN IF MICROCHIP HAS
* BEEN ADVISED OF THE POSSIBILITY OR THE DAMAGES ARE FORESEEABLE.
* TO THE FULLEST EXTENT ALLOWED BY LAW, MICROCHIP'S TOTAL LIABILITY ON ALL
* CLAIMS IN ANY WAY RELATED TO THIS SOFTWARE WILL NOT EXCEED THE AMOUNT OF
* FEES, IF ANY, THAT YOU HAVE PAID DIRECTLY TO MICROCHIP FOR THIS SOFTWARE.
* MICROCHIP PROVIDES THIS SOFTWARE CONDITIONALLY UPON YOUR ACCEPTANCE
* OF THESE TERMS.
**********************************************************************************
* ARM_REG.h
* This is the header to define Cortex-M3 system control & status registers
**********************************************************************************
* SMSC version control information (Perforce):
*
* FILE: $File: //depot_pcs/FWEng/Release/projects/CEC1302_PLIB_CLIB/release5/Source/hw_blks/common/include/ARM_REG.h $
* REVISION: $Revision: #1 $
* DATETIME: $DateTime: 2016/04/08 10:18:28 $
* AUTHOR: $Author: pramans $
*
* Revision history (latest first):
* #xx
***********************************************************************************
*/
/******************************************************************************/
/** @defgroup ARM_REG ARM_REG
* @{
*/
/** @file ARM_REG.h
* \brief ARM Cortex-M3 registers header file
* \author KBCEC Team
*
* This file contains ARM Cortex-M3 system control & status registers.
******************************************************************************/
#ifndef ARM_REG_H_
#define ARM_REG_H_
#define REG8(x) (*((volatile unsigned char *)(x)))
#define REG16(x) (*((volatile unsigned short *)(x)))
#define REG32(x) (*((volatile unsigned long *)(x)))
/* NVIC Registers */
#define NVIC_INT_TYPE REG32(0xE000E004)
#define NVIC_AUX_ACTLR REG32(0xE000E008)
#define WR_BUF_DISABLE (1 << 1)
#define NVIC_ST_CTRL REG32(0xE000E010)
#define ST_ENABLE (1 << 0)
#define ST_TICKINT (1 << 1)
#define ST_CLKSOURCE (1 << 2)
#define ST_COUNTFLAG (1 << 3)
#define NVIC_ST_RELOAD REG32(0xE000E014)
#define NVIC_ST_CURRENT REG32(0xE000E018)
#define NVIC_ST_CALIB REG32(0xE000E01C)
#define NVIC_ENABLE0 REG32(0xE000E100)
#define NVIC_ENABLE1 REG32(0xE000E104)
#define NVIC_ENABLE2 REG32(0xE000E108)
#define NVIC_ENABLE3 REG32(0xE000E10C)
#define NVIC_ENABLE4 REG32(0xE000E110)
#define NVIC_ENABLE5 REG32(0xE000E114)
#define NVIC_ENABLE6 REG32(0xE000E118)
#define NVIC_ENABLE7 REG32(0xE000E11C)
#define NVIC_DISABLE0 REG32(0xE000E180)
#define NVIC_DISABLE1 REG32(0xE000E184)
#define NVIC_DISABLE2 REG32(0xE000E188)
#define NVIC_DISABLE3 REG32(0xE000E18C)
#define NVIC_DISABLE4 REG32(0xE000E190)
#define NVIC_DISABLE5 REG32(0xE000E194)
#define NVIC_DISABLE6 REG32(0xE000E198)
#define NVIC_DISABLE7 REG32(0xE000E19C)
#define NVIC_PEND0 REG32(0xE000E200)
#define NVIC_PEND1 REG32(0xE000E204)
#define NVIC_PEND2 REG32(0xE000E208)
#define NVIC_PEND3 REG32(0xE000E20C)
#define NVIC_PEND4 REG32(0xE000E210)
#define NVIC_PEND5 REG32(0xE000E214)
#define NVIC_PEND6 REG32(0xE000E218)
#define NVIC_PEND7 REG32(0xE000E21C)
#define NVIC_UNPEND0 REG32(0xE000E280)
#define NVIC_UNPEND1 REG32(0xE000E284)
#define NVIC_UNPEND2 REG32(0xE000E288)
#define NVIC_UNPEND3 REG32(0xE000E28C)
#define NVIC_UNPEND4 REG32(0xE000E290)
#define NVIC_UNPEND5 REG32(0xE000E294)
#define NVIC_UNPEND6 REG32(0xE000E298)
#define NVIC_UNPEND7 REG32(0xE000E29C)
#define NVIC_ACTIVE0 REG32(0xE000E300)
#define NVIC_ACTIVE1 REG32(0xE000E304)
#define NVIC_ACTIVE2 REG32(0xE000E308)
#define NVIC_ACTIVE3 REG32(0xE000E30C)
#define NVIC_ACTIVE4 REG32(0xE000E310)
#define NVIC_ACTIVE5 REG32(0xE000E314)
#define NVIC_ACTIVE6 REG32(0xE000E318)
#define NVIC_ACTIVE7 REG32(0xE000E31C)
#define NVIC_PRI0 REG32(0xE000E400)
#define NVIC_PRI1 REG32(0xE000E404)
#define NVIC_PRI2 REG32(0xE000E408)
#define NVIC_PRI3 REG32(0xE000E40C)
#define NVIC_PRI4 REG32(0xE000E410)
#define NVIC_PRI5 REG32(0xE000E414)
#define NVIC_PRI6 REG32(0xE000E418)
#define NVIC_PRI7 REG32(0xE000E41C)
#define NVIC_PRI8 REG32(0xE000E420)
#define NVIC_PRI9 REG32(0xE000E424)
#define NVIC_PRI10 REG32(0xE000E428)
#define NVIC_PRI11 REG32(0xE000E42C)
#define NVIC_PRI12 REG32(0xE000E430)
#define NVIC_PRI13 REG32(0xE000E434)
#define NVIC_PRI14 REG32(0xE000E438)
#define NVIC_PRI15 REG32(0xE000E43C)
#define NVIC_PRI16 REG32(0xE000E440)
#define NVIC_PRI17 REG32(0xE000E444)
#define NVIC_PRI18 REG32(0xE000E448)
#define NVIC_PRI19 REG32(0xE000E44C)
#define NVIC_PRI20 REG32(0xE000E450)
#define NVIC_PRI21 REG32(0xE000E454)
#define NVIC_PRI22 REG32(0xE000E458)
#define NVIC_PRI23 REG32(0xE000E45C)
#define NVIC_PRI24 REG32(0xE000E460)
#define NVIC_PRI25 REG32(0xE000E464)
#define NVIC_PRI26 REG32(0xE000E468)
#define NVIC_PRI27 REG32(0xE000E46C)
#define NVIC_PRI28 REG32(0xE000E470)
#define NVIC_PRI29 REG32(0xE000E474)
#define NVIC_PRI30 REG32(0xE000E478)
#define NVIC_PRI31 REG32(0xE000E47C)
#define NVIC_PRI32 REG32(0xE000E480)
#define NVIC_PRI33 REG32(0xE000E484)
#define NVIC_PRI34 REG32(0xE000E488)
#define NVIC_PRI35 REG32(0xE000E48C)
#define NVIC_PRI36 REG32(0xE000E490)
#define NVIC_PRI37 REG32(0xE000E494)
#define NVIC_PRI38 REG32(0xE000E498)
#define NVIC_PRI39 REG32(0xE000E49C)
#define NVIC_PRI40 REG32(0xE000E4A0)
#define NVIC_PRI41 REG32(0xE000E4A4)
#define NVIC_PRI42 REG32(0xE000E4A8)
#define NVIC_PRI43 REG32(0xE000E4AC)
#define NVIC_PRI44 REG32(0xE000E4B0)
#define NVIC_PRI45 REG32(0xE000E4B4)
#define NVIC_PRI46 REG32(0xE000E4B8)
#define NVIC_PRI47 REG32(0xE000E4BC)
#define NVIC_PRI48 REG32(0xE000E4C0)
#define NVIC_PRI49 REG32(0xE000E4C4)
#define NVIC_PRI50 REG32(0xE000E4C8)
#define NVIC_PRI51 REG32(0xE000E4CC)
#define NVIC_PRI52 REG32(0xE000E4D0)
#define NVIC_PRI53 REG32(0xE000E4D4)
#define NVIC_PRI54 REG32(0xE000E4D8)
#define NVIC_PRI55 REG32(0xE000E4DC)
#define NVIC_PRI56 REG32(0xE000E4E0)
#define NVIC_PRI57 REG32(0xE000E4E4)
#define NVIC_PRI58 REG32(0xE000E4E8)
#define NVIC_PRI59 REG32(0xE000E4EC)
#define NVIC_CPUID REG32(0xE000ED00)
#define NVIC_INT_CTRL REG32(0xE000ED04)
#define NVIC_VECT_TABLE REG32(0xE000ED08)
#define NVIC_AP_INT_RST REG32(0xE000ED0C)
#define NVIC_SYS_CTRL REG32(0xE000ED10)
#define NVIC_CFG_CTRL REG32(0xE000ED14)
#define NVIC_SYS_H_PRI1 REG32(0xE000ED18)
#define NVIC_SYS_H_PRI2 REG32(0xE000ED1C)
#define NVIC_SYS_H_PRI3 REG32(0xE000ED20)
#define NVIC_SYS_H_CTRL REG32(0xE000ED24)
#define NVIC_FAULT_STA REG32(0xE000ED28)
#define NVIC_HARD_F_STA REG32(0xE000ED2C)
#define NVIC_DBG_F_STA REG32(0xE000ED30)
#define NVIC_MM_F_ADR REG32(0xE000ED34)
#define NVIC_BUS_F_ADR REG32(0xE000ED38)
#define NVIC_SW_TRIG REG32(0xE000EF00)
/* MPU Registers */
#define MPU_TYPE REG32(0xE000ED90)
#define MPU_CTRL REG32(0xE000ED94)
#define MPU_RG_NUM REG32(0xE000ED98)
#define MPU_RG_ADDR REG32(0xE000ED9C)
#define MPU_RG_AT_SZ REG32(0xE000EDA0)
#endif /* #ifndef ARM_REG_H_ */
/** @}
*/

View File

@ -963,7 +963,7 @@ typedef struct { /*!< ACPI_EC0 Structure
struct {
__I uint8_t OBF : 1; /*!< Output Buffer Full bit */
__I uint8_t IBF : 1; /*!< Input Buffer Full bit */
__I uint8_t UD1A : 1; /*!< User Defined */
__IO uint8_t UD1A : 1; /*!< User Defined */
__I uint8_t CMD : 1; /*!< OS2EC Data contains a command byte */
__IO uint8_t BURST : 1; /*!< set when the ACPI_EC is in Burst Mode */
__IO uint8_t SCI_EVT : 1; /*!< set when an SCI event is pending */
@ -975,8 +975,8 @@ typedef struct { /*!< ACPI_EC0 Structure
__I uint16_t RESERVED1;
union {
__IO uint32_t OS2EC_DATA; /*!< OS2EC Data EC-Register */
__IO uint8_t OS2EC_DATA_BYTE[4]; /*!< OS2EC Data Bytes */
__I uint32_t OS2EC_DATA; /*!< OS2EC Data EC-Register */
__I uint8_t OS2EC_DATA_BYTE[4]; /*!< OS2EC Data Bytes */
};
} ACPI_EC0_Type;
@ -1034,7 +1034,7 @@ typedef struct { /*!< KBC Structure
__IO uint8_t UD0 : 1; /*!< User-defined data. */
__I uint8_t CMDnDATA : 1; /*!< data register contains data(0) or command(1) */
__IO uint8_t UD1 : 1; /*!< User-defined data. */
__IO uint8_t AUXOBF : 1; /*!< Auxiliary Output Buffer Full. */
__I uint8_t AUXOBF : 1; /*!< Auxiliary Output Buffer Full. */
__IO uint8_t UD2 : 2; /*!< User-defined data. */
} STATUS_b; /*!< BitSize */
};
@ -1087,7 +1087,7 @@ typedef struct { /*!< PORT92 Structure
__I uint8_t RESERVED1[7];
__O uint8_t SETGA20L; /*!< write to set GATEA20 in GATEA20 Control Reg */
__I uint8_t RESERVED2[3];
__IO uint8_t RSTGA20L; /*!< write to set GATEA20 in GATEA20 Control Reg */
__O uint8_t RSTGA20L; /*!< write to set GATEA20 in GATEA20 Control Reg */
__I uint8_t RESERVED3[547];
__IO uint8_t PORT92_ENABLE; /*!< [0:0] 1= Port92h Register is enabled. */
} PORT92_Type;
@ -2110,8 +2110,7 @@ typedef struct { /*!< RPM_FAN Structure
__IO uint8_t VALID_TACH_COUNT; /*!< max value to indicate fan spin properly */
__IO uint16_t DRIVE_FAIL_BAND; /*!< [15:3]counts for Drive Fail circuitry */
__IO uint16_t TACH_TARGET; /*!< [12:0] The target tachometer value. */
__IO uint8_t TACH_READING; /*!< [15:3]current tachometer reading value. */
__I uint8_t RESERVED1;
__IO uint16_t TACH_READING; /*!< [15:3]current tachometer reading value. */
__IO uint8_t DRIVER_BASE_FREQUENCY; /*!< [1:0]frequency range of the PWM fan driver */
union {
@ -2513,7 +2512,7 @@ typedef struct { /*!< JTAG Structure
/*------------- Public Key Encryption Subsystem (PKE) -----------------------------*/
/** @addtogroup MEC1322_PKE Public Key Encryption (PKE)
/** @addtogroup CEC1302_PKE Public Key Encryption (PKE)
@{
*/
typedef struct
@ -2525,10 +2524,10 @@ typedef struct
__I uint32_t VERSION; /*!< Offset: 0x0010 Version */
__IO uint32_t LOAD_MICRO_CODE; /*!< Offset: 0x0014 Load Micro Code */
} PKE_TypeDef;
/*@}*/ /* end of group MEC1322_PKE */
/*@}*/ /* end of group CEC1302_PKE */
/*------------- Random Number Generator Subsystem (TRNG) -----------------------------*/
/** @addtogroup MEC1322_TRNG Random Number Generator (TRNG)
/** @addtogroup CEC1302_TRNG Random Number Generator (TRNG)
@{
*/
typedef struct
@ -2537,10 +2536,10 @@ typedef struct
__I uint32_t FIFO_LEVEL; /*!< Offset: 0x0004 FIFO Level */
__I uint32_t VERSION; /*!< Offset: 0x0008 Version */
} TRNG_TypeDef;
/*@}*/ /* end of group MEC1322_TRNG */
/*@}*/ /* end of group CEC1302_TRNG */
/*------------- Hash Subsystem (HASH) -----------------------------*/
/** @addtogroup MEC1322_HASH Hash Security (HASH)
/** @addtogroup CEC1302_HASH Hash Security (HASH)
@{
*/
typedef struct
@ -2555,12 +2554,12 @@ typedef struct
__IO uint32_t DATA_SOURCE_ADDR; /*!< Offset: 0x001C Data to hash Address */
__IO uint32_t HASH_RESULT_ADDR; /*!< Offset: 0x0020 Hash result address */
} HASH_TypeDef;
/*@}*/ /* end of group MEC1322_HASH */
/*@}*/ /* end of group CEC1302_HASH */
/*------------- Advanced Encryption Subsystem (AES) -----------------------------*/
/** @addtogroup MEC1322_AES Advanced Encryption Subsys (AES)
/** @addtogroup CEC1302_AES Advanced Encryption Subsys (AES)
@{
*/
@ -2603,7 +2602,7 @@ typedef struct
!< Offset: 0x0158 KeyIn1[95:64]
!< Offset: 0x015C KeyIn1[127:96] */
} AES_TypeDef;
/*@}*/ /* end of group MEC1322_AES */
/*@}*/ /* end of group CEC1302_AES */
/* -------------------- End of section using anonymous unions ------------------- */
#if defined(__CC_ARM)
@ -3280,114 +3279,6 @@ typedef struct
#define ACPI_EC0_EC_STATUS_UD0A_Msk (0x80UL) /*!< ACPI_EC0 EC_STATUS: UD0A (Bitfield-Mask: 0x01) */
/* ================================================================================ */
/* ================ struct 'ACPI_EC1' Position & Mask ================ */
/* ================================================================================ */
/* ----------------------------- ACPI_EC1_OS_STATUS ----------------------------- */
#define ACPI_EC1_OS_STATUS_OBF_Pos (0UL) /*!< ACPI_EC1 OS_STATUS: OBF (Bit 0) */
#define ACPI_EC1_OS_STATUS_OBF_Msk (0x1UL) /*!< ACPI_EC1 OS_STATUS: OBF (Bitfield-Mask: 0x01) */
#define ACPI_EC1_OS_STATUS_IBF_Pos (1UL) /*!< ACPI_EC1 OS_STATUS: IBF (Bit 1) */
#define ACPI_EC1_OS_STATUS_IBF_Msk (0x2UL) /*!< ACPI_EC1 OS_STATUS: IBF (Bitfield-Mask: 0x01) */
#define ACPI_EC1_OS_STATUS_UD1B_Pos (2UL) /*!< ACPI_EC1 OS_STATUS: UD1B (Bit 2) */
#define ACPI_EC1_OS_STATUS_UD1B_Msk (0x4UL) /*!< ACPI_EC1 OS_STATUS: UD1B (Bitfield-Mask: 0x01) */
#define ACPI_EC1_OS_STATUS_CMD_Pos (3UL) /*!< ACPI_EC1 OS_STATUS: CMD (Bit 3) */
#define ACPI_EC1_OS_STATUS_CMD_Msk (0x8UL) /*!< ACPI_EC1 OS_STATUS: CMD (Bitfield-Mask: 0x01) */
#define ACPI_EC1_OS_STATUS_BURST_Pos (4UL) /*!< ACPI_EC1 OS_STATUS: BURST (Bit 4) */
#define ACPI_EC1_OS_STATUS_BURST_Msk (0x10UL) /*!< ACPI_EC1 OS_STATUS: BURST (Bitfield-Mask: 0x01) */
#define ACPI_EC1_OS_STATUS_SCI_EVT_Pos (5UL) /*!< ACPI_EC1 OS_STATUS: SCI_EVT (Bit 5) */
#define ACPI_EC1_OS_STATUS_SCI_EVT_Msk (0x20UL) /*!< ACPI_EC1 OS_STATUS: SCI_EVT (Bitfield-Mask: 0x01) */
#define ACPI_EC1_OS_STATUS_SMI_EVT_Pos (6UL) /*!< ACPI_EC1 OS_STATUS: SMI_EVT (Bit 6) */
#define ACPI_EC1_OS_STATUS_SMI_EVT_Msk (0x40UL) /*!< ACPI_EC1 OS_STATUS: SMI_EVT (Bitfield-Mask: 0x01) */
#define ACPI_EC1_OS_STATUS_UD0B_Pos (7UL) /*!< ACPI_EC1 OS_STATUS: UD0B (Bit 7) */
#define ACPI_EC1_OS_STATUS_UD0B_Msk (0x80UL) /*!< ACPI_EC1 OS_STATUS: UD0B (Bitfield-Mask: 0x01) */
/* ----------------------------- ACPI_EC1_EC_STATUS ----------------------------- */
#define ACPI_EC1_EC_STATUS_OBF_Pos (0UL) /*!< ACPI_EC1 EC_STATUS: OBF (Bit 0) */
#define ACPI_EC1_EC_STATUS_OBF_Msk (0x1UL) /*!< ACPI_EC1 EC_STATUS: OBF (Bitfield-Mask: 0x01) */
#define ACPI_EC1_EC_STATUS_IBF_Pos (1UL) /*!< ACPI_EC1 EC_STATUS: IBF (Bit 1) */
#define ACPI_EC1_EC_STATUS_IBF_Msk (0x2UL) /*!< ACPI_EC1 EC_STATUS: IBF (Bitfield-Mask: 0x01) */
#define ACPI_EC1_EC_STATUS_UD1A_Pos (2UL) /*!< ACPI_EC1 EC_STATUS: UD1A (Bit 2) */
#define ACPI_EC1_EC_STATUS_UD1A_Msk (0x4UL) /*!< ACPI_EC1 EC_STATUS: UD1A (Bitfield-Mask: 0x01) */
#define ACPI_EC1_EC_STATUS_CMD_Pos (3UL) /*!< ACPI_EC1 EC_STATUS: CMD (Bit 3) */
#define ACPI_EC1_EC_STATUS_CMD_Msk (0x8UL) /*!< ACPI_EC1 EC_STATUS: CMD (Bitfield-Mask: 0x01) */
#define ACPI_EC1_EC_STATUS_BURST_Pos (4UL) /*!< ACPI_EC1 EC_STATUS: BURST (Bit 4) */
#define ACPI_EC1_EC_STATUS_BURST_Msk (0x10UL) /*!< ACPI_EC1 EC_STATUS: BURST (Bitfield-Mask: 0x01) */
#define ACPI_EC1_EC_STATUS_SCI_EVT_Pos (5UL) /*!< ACPI_EC1 EC_STATUS: SCI_EVT (Bit 5) */
#define ACPI_EC1_EC_STATUS_SCI_EVT_Msk (0x20UL) /*!< ACPI_EC1 EC_STATUS: SCI_EVT (Bitfield-Mask: 0x01) */
#define ACPI_EC1_EC_STATUS_SMI_EVT_Pos (6UL) /*!< ACPI_EC1 EC_STATUS: SMI_EVT (Bit 6) */
#define ACPI_EC1_EC_STATUS_SMI_EVT_Msk (0x40UL) /*!< ACPI_EC1 EC_STATUS: SMI_EVT (Bitfield-Mask: 0x01) */
#define ACPI_EC1_EC_STATUS_UD0A_Pos (7UL) /*!< ACPI_EC1 EC_STATUS: UD0A (Bit 7) */
#define ACPI_EC1_EC_STATUS_UD0A_Msk (0x80UL) /*!< ACPI_EC1 EC_STATUS: UD0A (Bitfield-Mask: 0x01) */
/* ================================================================================ */
/* ================ struct 'KBC' Position & Mask ================ */
/* ================================================================================ */
/* ---------------------------- KBC_RD_PORT64_STATUS ---------------------------- */
#define KBC_RD_PORT64_STATUS_OBF_Pos (0UL) /*!< KBC RD_PORT64_STATUS: OBF (Bit 0) */
#define KBC_RD_PORT64_STATUS_OBF_Msk (0x1UL) /*!< KBC RD_PORT64_STATUS: OBF (Bitfield-Mask: 0x01) */
#define KBC_RD_PORT64_STATUS_IBF_Pos (1UL) /*!< KBC RD_PORT64_STATUS: IBF (Bit 1) */
#define KBC_RD_PORT64_STATUS_IBF_Msk (0x2UL) /*!< KBC RD_PORT64_STATUS: IBF (Bitfield-Mask: 0x01) */
#define KBC_RD_PORT64_STATUS_UD0_Pos (2UL) /*!< KBC RD_PORT64_STATUS: UD0 (Bit 2) */
#define KBC_RD_PORT64_STATUS_UD0_Msk (0x4UL) /*!< KBC RD_PORT64_STATUS: UD0 (Bitfield-Mask: 0x01) */
#define KBC_RD_PORT64_STATUS_CMDnDATA_Pos (3UL) /*!< KBC RD_PORT64_STATUS: CMDnDATA (Bit 3) */
#define KBC_RD_PORT64_STATUS_CMDnDATA_Msk (0x8UL) /*!< KBC RD_PORT64_STATUS: CMDnDATA (Bitfield-Mask: 0x01) */
#define KBC_RD_PORT64_STATUS_UD1_Pos (4UL) /*!< KBC RD_PORT64_STATUS: UD1 (Bit 4) */
#define KBC_RD_PORT64_STATUS_UD1_Msk (0x10UL) /*!< KBC RD_PORT64_STATUS: UD1 (Bitfield-Mask: 0x01) */
#define KBC_RD_PORT64_STATUS_AUXOBF_Pos (5UL) /*!< KBC RD_PORT64_STATUS: AUXOBF (Bit 5) */
#define KBC_RD_PORT64_STATUS_AUXOBF_Msk (0x20UL) /*!< KBC RD_PORT64_STATUS: AUXOBF (Bitfield-Mask: 0x01) */
#define KBC_RD_PORT64_STATUS_UD2_Pos (6UL) /*!< KBC RD_PORT64_STATUS: UD2 (Bit 6) */
#define KBC_RD_PORT64_STATUS_UD2_Msk (0xc0UL) /*!< KBC RD_PORT64_STATUS: UD2 (Bitfield-Mask: 0x03) */
/* --------------------------------- KBC_STATUS --------------------------------- */
#define KBC_STATUS_OBF_Pos (0UL) /*!< KBC STATUS: OBF (Bit 0) */
#define KBC_STATUS_OBF_Msk (0x1UL) /*!< KBC STATUS: OBF (Bitfield-Mask: 0x01) */
#define KBC_STATUS_IBF_Pos (1UL) /*!< KBC STATUS: IBF (Bit 1) */
#define KBC_STATUS_IBF_Msk (0x2UL) /*!< KBC STATUS: IBF (Bitfield-Mask: 0x01) */
#define KBC_STATUS_UD0_Pos (2UL) /*!< KBC STATUS: UD0 (Bit 2) */
#define KBC_STATUS_UD0_Msk (0x4UL) /*!< KBC STATUS: UD0 (Bitfield-Mask: 0x01) */
#define KBC_STATUS_CMDnDATA_Pos (3UL) /*!< KBC STATUS: CMDnDATA (Bit 3) */
#define KBC_STATUS_CMDnDATA_Msk (0x8UL) /*!< KBC STATUS: CMDnDATA (Bitfield-Mask: 0x01) */
#define KBC_STATUS_UD1_Pos (4UL) /*!< KBC STATUS: UD1 (Bit 4) */
#define KBC_STATUS_UD1_Msk (0x10UL) /*!< KBC STATUS: UD1 (Bitfield-Mask: 0x01) */
#define KBC_STATUS_AUXOBF_Pos (5UL) /*!< KBC STATUS: AUXOBF (Bit 5) */
#define KBC_STATUS_AUXOBF_Msk (0x20UL) /*!< KBC STATUS: AUXOBF (Bitfield-Mask: 0x01) */
#define KBC_STATUS_UD2_Pos (6UL) /*!< KBC STATUS: UD2 (Bit 6) */
#define KBC_STATUS_UD2_Msk (0xc0UL) /*!< KBC STATUS: UD2 (Bitfield-Mask: 0x03) */
/* --------------------------------- KBC_CONTROL -------------------------------- */
#define KBC_CONTROL_UD3_Pos (0UL) /*!< KBC CONTROL: UD3 (Bit 0) */
#define KBC_CONTROL_UD3_Msk (0x1UL) /*!< KBC CONTROL: UD3 (Bitfield-Mask: 0x01) */
#define KBC_CONTROL_SAEN_Pos (1UL) /*!< KBC CONTROL: SAEN (Bit 1) */
#define KBC_CONTROL_SAEN_Msk (0x2UL) /*!< KBC CONTROL: SAEN (Bitfield-Mask: 0x01) */
#define KBC_CONTROL_PCOBFEN_Pos (2UL) /*!< KBC CONTROL: PCOBFEN (Bit 2) */
#define KBC_CONTROL_PCOBFEN_Msk (0x4UL) /*!< KBC CONTROL: PCOBFEN (Bitfield-Mask: 0x01) */
#define KBC_CONTROL_UD4_Pos (3UL) /*!< KBC CONTROL: UD4 (Bit 3) */
#define KBC_CONTROL_UD4_Msk (0x18UL) /*!< KBC CONTROL: UD4 (Bitfield-Mask: 0x03) */
#define KBC_CONTROL_OBFEN_Pos (5UL) /*!< KBC CONTROL: OBFEN (Bit 5) */
#define KBC_CONTROL_OBFEN_Msk (0x20UL) /*!< KBC CONTROL: OBFEN (Bitfield-Mask: 0x01) */
#define KBC_CONTROL_UD5_Pos (6UL) /*!< KBC CONTROL: UD5 (Bit 6) */
#define KBC_CONTROL_UD5_Msk (0x40UL) /*!< KBC CONTROL: UD5 (Bitfield-Mask: 0x01) */
#define KBC_CONTROL_AUXH_Pos (7UL) /*!< KBC CONTROL: AUXH (Bit 7) */
#define KBC_CONTROL_AUXH_Msk (0x80UL) /*!< KBC CONTROL: AUXH (Bitfield-Mask: 0x01) */
/* ================================================================================ */
/* ================ struct 'PORT92' Position & Mask ================ */
/* ================================================================================ */
/* -------------------------------- PORT92_PORT92 ------------------------------- */
#define PORT92_PORT92_ALT_CPU_RESET_Pos (0UL) /*!< PORT92 PORT92: ALT_CPU_RESET (Bit 0) */
#define PORT92_PORT92_ALT_CPU_RESET_Msk (0x1UL) /*!< PORT92 PORT92: ALT_CPU_RESET (Bitfield-Mask: 0x01) */
#define PORT92_PORT92_ALT_GATE_A20_Pos (1UL) /*!< PORT92 PORT92: ALT_GATE_A20 (Bit 1) */
#define PORT92_PORT92_ALT_GATE_A20_Msk (0x2UL) /*!< PORT92 PORT92: ALT_GATE_A20 (Bitfield-Mask: 0x01) */
/* ================================================================================ */
/* ================ struct 'MBX' Position & Mask ================ */
/* ================================================================================ */

View File

@ -1,409 +1,409 @@
/*****************************************************************************
* © 2015 Microchip Technology Inc. and its subsidiaries.
* You may use this software and any derivatives exclusively with
* Microchip products.
* THIS SOFTWARE IS SUPPLIED BY MICROCHIP "AS IS".
* NO WARRANTIES, WHETHER EXPRESS, IMPLIED OR STATUTORY, APPLY TO THIS SOFTWARE,
* INCLUDING ANY IMPLIED WARRANTIES OF NON-INFRINGEMENT, MERCHANTABILITY,
* AND FITNESS FOR A PARTICULAR PURPOSE, OR ITS INTERACTION WITH MICROCHIP
* PRODUCTS, COMBINATION WITH ANY OTHER PRODUCTS, OR USE IN ANY APPLICATION.
* IN NO EVENT WILL MICROCHIP BE LIABLE FOR ANY INDIRECT, SPECIAL, PUNITIVE,
* INCIDENTAL OR CONSEQUENTIAL LOSS, DAMAGE, COST OR EXPENSE OF ANY KIND
* WHATSOEVER RELATED TO THE SOFTWARE, HOWEVER CAUSED, EVEN IF MICROCHIP HAS
* BEEN ADVISED OF THE POSSIBILITY OR THE DAMAGES ARE FORESEEABLE.
* TO THE FULLEST EXTENT ALLOWED BY LAW, MICROCHIP'S TOTAL LIABILITY ON ALL
* CLAIMS IN ANY WAY RELATED TO THIS SOFTWARE WILL NOT EXCEED THE AMOUNT OF
* FEES, IF ANY, THAT YOU HAVE PAID DIRECTLY TO MICROCHIP FOR THIS SOFTWARE.
* MICROCHIP PROVIDES THIS SOFTWARE CONDITIONALLY UPON YOUR ACCEPTANCE
* OF THESE TERMS.
******************************************************************************
Version Control Information (Perforce)
******************************************************************************
$Revision: #1 $
$DateTime: 2015/11/22 06:01:28 $
$Author: amohandas $
Last Change: Updated with unit testing feedbacks
******************************************************************************/
/** @file btimer.h
* \brief Basic Timer Peripheral Header file
* \author jvasanth
*
* This file is the header file for Basic Timer Peripheral
******************************************************************************/
/** @defgroup Basic_Timer
* @{
*/
#ifndef _BTIMER_H
#define _BTIMER_H
/******************************************************************************/
/** Logical Timer ID for APIs.
* This is the timer IDs passed to Basic Timer API function calls
*******************************************************************************/
enum _PID_BTIMER_
{
PID_BTIMER_0,
PID_BTIMER_1,
PID_BTIMER_2,
PID_BTIMER_3,
PID_BTIMER_4,
PID_BTIMER_5,
PID_BTIMER_MAX
};
/* ---------------------------------------------------------------------- */
/* Logical flags for Timer Control */
/* ---------------------------------------------------------------------- */
//This is for tmr_cntl parameter in btimer_init function
#define BTIMER_AUTO_RESTART (0x08u)
#define BTIMER_ONE_SHOT (0u)
#define BTIMER_COUNT_UP (0x04u)
#define BTIMER_COUNT_DOWN (0u)
#define BTIMER_INT_EN (0x01u)
#define BTIMER_NO_INT (0u)
/* ---------------------------------------------------------------------- */
//Timer Block Hardware Bits and Masks
#define BTIMER_CNTL_HALT (0x80UL)
#define BTIMER_CNTL_RELOAD (0x40UL)
#define BTIMER_CNTL_START (0x20UL)
#define BTIMER_CNTL_SOFT_RESET (0x10UL)
#define BTIMER_CNTL_AUTO_RESTART (0x08UL)
#define BTIMER_CNTL_COUNT_UP (0x04UL)
#define BTIMER_CNTL_ENABLE (0x01UL)
#define BTIMER_CNTL_HALT_BIT (7U)
#define BTIMER_CNTL_RELOAD_BIT (6U)
#define BTIMER_CNTL_START_BIT (5U)
#define BTIMER_CNTRL_SOFT_RESET_BIT (4U)
#define BTIMER_CNTL_AUTO_RESTART_BIT (3U)
#define BTIMER_CNTL_COUNT_DIR_BIT (2U)
#define BTIMER_CNTL_ENABLE_BIT (0U)
#define BTIMER_GIRQ MEC_GIRQ23_ID
#define BTIMER_MAX_INSTANCE PID_BTIMER_MAX
/* ---------------------------------------------------------------------- */
/* API - Basic Timer Intitialization function */
/* ---------------------------------------------------------------------- */
/** Initialize specified timer
* @param btimer_id Basic Timer ID
* @param tmr_cntl Logical flags for Timer Control
* @param initial_count Initial Count
* @param preload_count Preload Count
* @note Performs a soft reset of the timer before configuration
*/
void btimer_init(uint8_t btimer_id,
uint16_t tmr_cntl,
uint16_t prescaler,
uint32_t initial_count,
uint32_t preload_count);
/* ---------------------------------------------------------------------- */
/* API - Functions to program and read the Basic Timer Counter */
/* ---------------------------------------------------------------------- */
/** Program timer's counter register.
* @param btimer_id Basic Timer ID
* @param count new counter value
* @note Timer hardware may implement a 16-bit or 32-bit
* hardware counter. If the timer is 16-bit only the lower
* 16-bits of the count paramter are used.
*/
void btimer_count_set(uint8_t btimer_id, uint32_t count);
/** Return current value of timer's count register.
* @param btimer_id Basic Timer ID.
* @return uint32_t timer count may be 32 or 16 bits depending
* upon the hardware. Timers 0-3 are 16-bit
* and Timers 4-5 are 32-bit.
*/
uint32_t btimer_count_get(uint8_t btimer_id);
/* ---------------------------------------------------------------------- */
/* API - Function to reload counter from Preload Register */
/* ---------------------------------------------------------------------- */
/** Force timer to reload counter from preload
* register.
* @param btimer_id Basic Timer ID.
* @note Hardware will only reload counter if timer is running.
*/
void btimer_reload(uint8_t btimer_id);
/* ---------------------------------------------------------------------- */
/* API - Functions for stopping and starting the basic Timer */
/* ---------------------------------------------------------------------- */
/** Start timer counting.
* @param btimer_id Basic Timer ID.
*/
void btimer_start(uint8_t btimer_id);
/** Stop timer.
* @param btimer_id Basic Timer ID.
* @note When a stopped timer is started again it will reload
* the count register from preload value.
*/
void btimer_stop(uint8_t btimer_id);
/** Return state of timer's START bit.
* @param btimer_id Basic Timer ID.
* @return uint8_t 0(timer not started), 1 (timer started)
*/
uint8_t btimer_is_started(uint8_t btimer_id);
/* ---------------------------------------------------------------------- */
/* API - Function to perform basic timer soft reset */
/* ---------------------------------------------------------------------- */
/** Peform soft reset of specified timer.
* @param btimer_id Basic Timer ID
* @note Soft reset set all registers to POR values.
* Spins 256 times waiting on hardware to clear reset bit.
*/
void btimer_reset(uint8_t btimer_id);
/* ---------------------------------------------------------------------- */
/* API - Functions to halt/unhalt the timer counting */
/* ---------------------------------------------------------------------- */
/** Halt timer counting with no reload on unhalt.
* @param btimer_id Basic Timer ID.
* @note A halted timer will not reload the count register when
* unhalted, it will continue counting from the current
* count value.
*/
void btimer_halt(uint8_t btimer_id);
/** Unhalt timer counting.
* @param btimer_id Basic Timer ID.
*/
void btimer_unhalt(uint8_t btimer_id);
/* ---------------------------------------------------------------------- */
/* API - Functions for Basic Timer interrupt */
/* ---------------------------------------------------------------------- */
/** Enable specified timer's interrupt from the block.
* @param btimer_id Basic Timer ID.
* @param ien Non-zero enable interrupt in timer block, 0
* disable.
*/
void btimer_interrupt_enable(uint8_t btimer_id, uint8_t ien);
/** Read Timer interrupt status and clear if set
* @param btimer_id Basic Timer ID.
* @return uint8_t 1 (Timer interrupt status set) else 0.
* @note If timer interrupt status is set then clear it before
* returning.
*/
uint8_t btimer_interrupt_status_get_clr(uint8_t btimer_id);
/* ---------------------------------------------------------------------- */
/* API - Functions for Basic Timer GIRQ */
/* ---------------------------------------------------------------------- */
/** Enables GIRQ enable bit for the timer
* @param btimer_id Basic Timer ID.
*/
void btimer_girq_enable_set(uint8_t btimer_id);
/** Clears GIRQ enable bit for the timer
* @param btimer_id Basic Timer ID.
*/
void btimer_girq_enable_clr(uint8_t btimer_id);
/** Returns GIRQ source bit for the timer
* @param btimer_id Basic Timer ID.
* @return uint8_t 0(src bit not set), Non-zero (src bit set)
*/
uint8_t btimer_girq_src_get(uint8_t btimer_id);
/** Clears GIRQ source bit for the timer
* @param btimer_id Basic Timer ID.
*/
void btimer_girq_src_clr(uint8_t btimer_id);
/** Returns GIRQ result bit for the timer
* @param btimer_id Basic Timer ID.
* @return uint8_t 0(result bit not set), Non-zero (result bit set)
*/
uint8_t btimer_girq_result_get(uint8_t btimer_id);
/* ---------------------------------------------------------------------- */
/* API - Functions for Basic Timer Sleep */
/* ---------------------------------------------------------------------- */
/** Enable/Disable clock gating on idle of a timer
* @param btimer_id Basic Timer ID.
* @param sleep_en 1 = Sleep enable, 0 = Sleep disable
*/
void btimer_sleep(uint8_t btimer_id, uint8_t sleep_en);
/** Returns clk required status for the timer block
* @param btimer_id Basic Timer ID.
* @return Non-zero if clk required, else 0
*/
uint32_t btimer_clk_reqd_sts_get(uint8_t btimer_id);
/** Enable/Disable reset on sleep for the timer block
* @param btimer_id Basic Timer ID.
* @param reset_en 1 to enable, 0 to disable
*/
void btimer_reset_on_sleep(uint8_t btimer_id, uint8_t reset_en);
/* ---------------------------------------------------------------------- */
/* Peripheral Function - Functions to set and read Timer Counter Register */
/* ---------------------------------------------------------------------- */
/** Sets timer counter
* @param btimer_id Basic Timer ID
* @param count - 32-bit counter
*/
void p_btimer_count_set(uint8_t btimer_id, uint32_t count);
/** Read the timer counter
* @param btimer_id Basic Timer ID
* @return count - 32-bit counter
*/
uint32_t p_btimer_count_get(uint8_t btimer_id);
/* ---------------------------------------------------------------------- */
/* Peripheral Function - Function to program the Preload */
/* ---------------------------------------------------------------------- */
/** Sets preload for the counter
* @param btimer_id Basic Timer ID
* @param preload_count - 32-bit pre-load value
*/
void p_btimer_preload_set(uint8_t btimer_id, uint32_t preload_count);
/* ---------------------------------------------------------------------- */
/* Peripheral Functions - Functions for basic timer interrupts */
/* ---------------------------------------------------------------------- */
/** Reads the interrupt status bit in the timer block
* @param btimer_id Basic Timer ID
* @return status - 1 if interrupt status set, else 0
*/
uint8_t p_btimer_int_status_get(uint8_t btimer_id);
/** Clears interrupt status bit in the timer block
* @param btimer_id Basic Timer ID
*/
void p_btimer_int_status_clr(uint8_t btimer_id);
/** Sets interrupt enable bit in the timer block
* @param btimer_id Basic Timer ID
*/
void p_btimer_int_enable_set(uint8_t btimer_id);
/** Clears interrupt enable bit for the timer block
* @param btimer_id Basic Timer ID
*/
void p_btimer_int_enable_clr(uint8_t btimer_id);
/* ---------------------------------------------------------------------- */
/* Peripheral Functions - Functions for Control Register */
/* ---------------------------------------------------------------------- */
/** Writes the control register 32-bits
* @param btimer_id Basic Timer ID
* @param value - 32-bit value to program
*/
void p_btimer_ctrl_write(uint8_t btimer_id, uint32_t value);
/** Reads the control register
* @param btimer_id Basic Timer ID
* @return uint32_t - 32-bit value
*/
uint32_t p_btimer_ctrl_read(uint8_t btimer_id);
/** Clears enable bit in the control register
* @param btimer_id Basic Timer ID
*/
void p_btimer_ctrl_enable_set(uint8_t btimer_id);
/** Clears enable bit in the control register
* @param btimer_id Basic Timer ID
*/
void p_btimer_ctrl_enable_clr(uint8_t btimer_id);
/** Sets counter direction bit in the control register
* @param btimer_id Basic Timer ID
*/
void p_btimer_ctrl_counter_dir_set(uint8_t btimer_id);
/** Clears counter direction bit in the control register
* @param btimer_id Basic Timer ID
*/
void p_btimer_ctrl_counter_dir_clr(uint8_t btimer_id);
/** Sets auto restart bit in the control register
* @param btimer_id Basic Timer ID
*/
void p_btimer_ctrl_auto_restart_set(uint8_t btimer_id);
/** Clears auto resetart bit in the control register
* @param btimer_id Basic Timer ID
*/
void p_btimer_ctrl_auto_restart_clr(uint8_t btimer_id);
/** Sets soft reset bit in the control register
* @param btimer_id Basic Timer ID
*/
void p_btimer_ctrl_soft_reset_set(uint8_t btimer_id);
/** Read Soft Reset bit
* @param btimer_id Basic Timer ID
* @return 0 if soft reset status bit cleared; else non-zero value
*/
uint8_t p_btimer_ctrl_soft_reset_sts_get(uint8_t btimer_id);
/** Sets start bit in the control register
* @param btimer_id Basic Timer ID
*/
void p_btimer_ctrl_start_set(uint8_t btimer_id);
/** Read start bit in the control register
* @param btimer_id Basic Timer ID
* @return 0 if start bit not set; else non-zero value
*/
uint8_t p_btimer_ctrl_start_get(uint8_t btimer_id);
/** Clears start bit in the control register
* @param btimer_id Basic Timer ID
*/
void p_btimer_ctrl_start_clr(uint8_t btimer_id);
/** Sets reload bit in the control register
* @param btimer_id Basic Timer ID
*/
void p_btimer_ctrl_reload_set(uint8_t btimer_id);
/** Clears reload bit in the control register
* @param btimer_id Basic Timer ID
*/
void p_btimer_ctrl_reload_clr(uint8_t btimer_id);
/** Sets halt bit in the control register
* @param btimer_id Basic Timer ID
*/
void p_btimer_ctrl_halt_set(uint8_t btimer_id);
/** Clears halt bit in the control register
* @param btimer_id Basic Timer ID
*/
void p_btimer_ctrl_halt_clr(uint8_t btimer_id);
/** Sets prescale value
* @param btimer_id Basic Timer ID
* @param prescaler - 16-bit pre-scale value
*/
void p_btimer_ctrl_prescale_set(uint8_t btimer_id, uint16_t prescaler);
#endif // #ifndef _BTIMER_H
/* end btimer_perphl.c */
/** @} //Peripherals Basic_Timer
*/
/*****************************************************************************
* © 2015 Microchip Technology Inc. and its subsidiaries.
* You may use this software and any derivatives exclusively with
* Microchip products.
* THIS SOFTWARE IS SUPPLIED BY MICROCHIP "AS IS".
* NO WARRANTIES, WHETHER EXPRESS, IMPLIED OR STATUTORY, APPLY TO THIS SOFTWARE,
* INCLUDING ANY IMPLIED WARRANTIES OF NON-INFRINGEMENT, MERCHANTABILITY,
* AND FITNESS FOR A PARTICULAR PURPOSE, OR ITS INTERACTION WITH MICROCHIP
* PRODUCTS, COMBINATION WITH ANY OTHER PRODUCTS, OR USE IN ANY APPLICATION.
* IN NO EVENT WILL MICROCHIP BE LIABLE FOR ANY INDIRECT, SPECIAL, PUNITIVE,
* INCIDENTAL OR CONSEQUENTIAL LOSS, DAMAGE, COST OR EXPENSE OF ANY KIND
* WHATSOEVER RELATED TO THE SOFTWARE, HOWEVER CAUSED, EVEN IF MICROCHIP HAS
* BEEN ADVISED OF THE POSSIBILITY OR THE DAMAGES ARE FORESEEABLE.
* TO THE FULLEST EXTENT ALLOWED BY LAW, MICROCHIP'S TOTAL LIABILITY ON ALL
* CLAIMS IN ANY WAY RELATED TO THIS SOFTWARE WILL NOT EXCEED THE AMOUNT OF
* FEES, IF ANY, THAT YOU HAVE PAID DIRECTLY TO MICROCHIP FOR THIS SOFTWARE.
* MICROCHIP PROVIDES THIS SOFTWARE CONDITIONALLY UPON YOUR ACCEPTANCE
* OF THESE TERMS.
******************************************************************************
Version Control Information (Perforce)
******************************************************************************
$Revision: #1 $
$DateTime: 2016/04/08 10:18:28 $
$Author: pramans $
Last Change: Updated with unit testing feedbacks
******************************************************************************/
/** @file btimer.h
* \brief Basic Timer Peripheral Header file
* \author jvasanth
*
* This file is the header file for Basic Timer Peripheral
******************************************************************************/
/** @defgroup Basic_Timer
* @{
*/
#ifndef _BTIMER_H
#define _BTIMER_H
/******************************************************************************/
/** Logical Timer ID for APIs.
* This is the timer IDs passed to Basic Timer API function calls
*******************************************************************************/
enum _PID_BTIMER_
{
PID_BTIMER_0,
PID_BTIMER_1,
PID_BTIMER_2,
PID_BTIMER_3,
PID_BTIMER_4,
PID_BTIMER_5,
PID_BTIMER_MAX
};
/* ---------------------------------------------------------------------- */
/* Logical flags for Timer Control */
/* ---------------------------------------------------------------------- */
//This is for tmr_cntl parameter in btimer_init function
#define BTIMER_AUTO_RESTART (0x08u)
#define BTIMER_ONE_SHOT (0u)
#define BTIMER_COUNT_UP (0x04u)
#define BTIMER_COUNT_DOWN (0u)
#define BTIMER_INT_EN (0x01u)
#define BTIMER_NO_INT (0u)
/* ---------------------------------------------------------------------- */
//Timer Block Hardware Bits and Masks
#define BTIMER_CNTL_HALT (0x80UL)
#define BTIMER_CNTL_RELOAD (0x40UL)
#define BTIMER_CNTL_START (0x20UL)
#define BTIMER_CNTL_SOFT_RESET (0x10UL)
#define BTIMER_CNTL_AUTO_RESTART (0x08UL)
#define BTIMER_CNTL_COUNT_UP (0x04UL)
#define BTIMER_CNTL_ENABLE (0x01UL)
#define BTIMER_CNTL_HALT_BIT (7U)
#define BTIMER_CNTL_RELOAD_BIT (6U)
#define BTIMER_CNTL_START_BIT (5U)
#define BTIMER_CNTRL_SOFT_RESET_BIT (4U)
#define BTIMER_CNTL_AUTO_RESTART_BIT (3U)
#define BTIMER_CNTL_COUNT_DIR_BIT (2U)
#define BTIMER_CNTL_ENABLE_BIT (0U)
#define BTIMER_GIRQ MEC_GIRQ23_ID
#define BTIMER_MAX_INSTANCE PID_BTIMER_MAX
/* ---------------------------------------------------------------------- */
/* API - Basic Timer Intitialization function */
/* ---------------------------------------------------------------------- */
/** Initialize specified timer
* @param btimer_id Basic Timer ID
* @param tmr_cntl Logical flags for Timer Control
* @param initial_count Initial Count
* @param preload_count Preload Count
* @note Performs a soft reset of the timer before configuration
*/
void btimer_init(uint8_t btimer_id,
uint16_t tmr_cntl,
uint16_t prescaler,
uint32_t initial_count,
uint32_t preload_count);
/* ---------------------------------------------------------------------- */
/* API - Functions to program and read the Basic Timer Counter */
/* ---------------------------------------------------------------------- */
/** Program timer's counter register.
* @param btimer_id Basic Timer ID
* @param count new counter value
* @note Timer hardware may implement a 16-bit or 32-bit
* hardware counter. If the timer is 16-bit only the lower
* 16-bits of the count paramter are used.
*/
void btimer_count_set(uint8_t btimer_id, uint32_t count);
/** Return current value of timer's count register.
* @param btimer_id Basic Timer ID.
* @return uint32_t timer count may be 32 or 16 bits depending
* upon the hardware. Timers 0-3 are 16-bit
* and Timers 4-5 are 32-bit.
*/
uint32_t btimer_count_get(uint8_t btimer_id);
/* ---------------------------------------------------------------------- */
/* API - Function to reload counter from Preload Register */
/* ---------------------------------------------------------------------- */
/** Force timer to reload counter from preload
* register.
* @param btimer_id Basic Timer ID.
* @note Hardware will only reload counter if timer is running.
*/
void btimer_reload(uint8_t btimer_id);
/* ---------------------------------------------------------------------- */
/* API - Functions for stopping and starting the basic Timer */
/* ---------------------------------------------------------------------- */
/** Start timer counting.
* @param btimer_id Basic Timer ID.
*/
void btimer_start(uint8_t btimer_id);
/** Stop timer.
* @param btimer_id Basic Timer ID.
* @note When a stopped timer is started again it will reload
* the count register from preload value.
*/
void btimer_stop(uint8_t btimer_id);
/** Return state of timer's START bit.
* @param btimer_id Basic Timer ID.
* @return uint8_t 0(timer not started), 1 (timer started)
*/
uint8_t btimer_is_started(uint8_t btimer_id);
/* ---------------------------------------------------------------------- */
/* API - Function to perform basic timer soft reset */
/* ---------------------------------------------------------------------- */
/** Peform soft reset of specified timer.
* @param btimer_id Basic Timer ID
* @note Soft reset set all registers to POR values.
* Spins 256 times waiting on hardware to clear reset bit.
*/
void btimer_reset(uint8_t btimer_id);
/* ---------------------------------------------------------------------- */
/* API - Functions to halt/unhalt the timer counting */
/* ---------------------------------------------------------------------- */
/** Halt timer counting with no reload on unhalt.
* @param btimer_id Basic Timer ID.
* @note A halted timer will not reload the count register when
* unhalted, it will continue counting from the current
* count value.
*/
void btimer_halt(uint8_t btimer_id);
/** Unhalt timer counting.
* @param btimer_id Basic Timer ID.
*/
void btimer_unhalt(uint8_t btimer_id);
/* ---------------------------------------------------------------------- */
/* API - Functions for Basic Timer interrupt */
/* ---------------------------------------------------------------------- */
/** Enable specified timer's interrupt from the block.
* @param btimer_id Basic Timer ID.
* @param ien Non-zero enable interrupt in timer block, 0
* disable.
*/
void btimer_interrupt_enable(uint8_t btimer_id, uint8_t ien);
/** Read Timer interrupt status and clear if set
* @param btimer_id Basic Timer ID.
* @return uint8_t 1 (Timer interrupt status set) else 0.
* @note If timer interrupt status is set then clear it before
* returning.
*/
uint8_t btimer_interrupt_status_get_clr(uint8_t btimer_id);
/* ---------------------------------------------------------------------- */
/* API - Functions for Basic Timer GIRQ */
/* ---------------------------------------------------------------------- */
/** Enables GIRQ enable bit for the timer
* @param btimer_id Basic Timer ID.
*/
void btimer_girq_enable_set(uint8_t btimer_id);
/** Clears GIRQ enable bit for the timer
* @param btimer_id Basic Timer ID.
*/
void btimer_girq_enable_clr(uint8_t btimer_id);
/** Returns GIRQ source bit for the timer
* @param btimer_id Basic Timer ID.
* @return uint8_t 0(src bit not set), Non-zero (src bit set)
*/
uint8_t btimer_girq_src_get(uint8_t btimer_id);
/** Clears GIRQ source bit for the timer
* @param btimer_id Basic Timer ID.
*/
void btimer_girq_src_clr(uint8_t btimer_id);
/** Returns GIRQ result bit for the timer
* @param btimer_id Basic Timer ID.
* @return uint8_t 0(result bit not set), Non-zero (result bit set)
*/
uint8_t btimer_girq_result_get(uint8_t btimer_id);
/* ---------------------------------------------------------------------- */
/* API - Functions for Basic Timer Sleep */
/* ---------------------------------------------------------------------- */
/** Enable/Disable clock gating on idle of a timer
* @param btimer_id Basic Timer ID.
* @param sleep_en 1 = Sleep enable, 0 = Sleep disable
*/
void btimer_sleep(uint8_t btimer_id, uint8_t sleep_en);
/** Returns clk required status for the timer block
* @param btimer_id Basic Timer ID.
* @return Non-zero if clk required, else 0
*/
uint32_t btimer_clk_reqd_sts_get(uint8_t btimer_id);
/** Enable/Disable reset on sleep for the timer block
* @param btimer_id Basic Timer ID.
* @param reset_en 1 to enable, 0 to disable
*/
void btimer_reset_on_sleep(uint8_t btimer_id, uint8_t reset_en);
/* ---------------------------------------------------------------------- */
/* Peripheral Function - Functions to set and read Timer Counter Register */
/* ---------------------------------------------------------------------- */
/** Sets timer counter
* @param btimer_id Basic Timer ID
* @param count - 32-bit counter
*/
void p_btimer_count_set(uint8_t btimer_id, uint32_t count);
/** Read the timer counter
* @param btimer_id Basic Timer ID
* @return count - 32-bit counter
*/
uint32_t p_btimer_count_get(uint8_t btimer_id);
/* ---------------------------------------------------------------------- */
/* Peripheral Function - Function to program the Preload */
/* ---------------------------------------------------------------------- */
/** Sets preload for the counter
* @param btimer_id Basic Timer ID
* @param preload_count - 32-bit pre-load value
*/
void p_btimer_preload_set(uint8_t btimer_id, uint32_t preload_count);
/* ---------------------------------------------------------------------- */
/* Peripheral Functions - Functions for basic timer interrupts */
/* ---------------------------------------------------------------------- */
/** Reads the interrupt status bit in the timer block
* @param btimer_id Basic Timer ID
* @return status - 1 if interrupt status set, else 0
*/
uint8_t p_btimer_int_status_get(uint8_t btimer_id);
/** Clears interrupt status bit in the timer block
* @param btimer_id Basic Timer ID
*/
void p_btimer_int_status_clr(uint8_t btimer_id);
/** Sets interrupt enable bit in the timer block
* @param btimer_id Basic Timer ID
*/
void p_btimer_int_enable_set(uint8_t btimer_id);
/** Clears interrupt enable bit for the timer block
* @param btimer_id Basic Timer ID
*/
void p_btimer_int_enable_clr(uint8_t btimer_id);
/* ---------------------------------------------------------------------- */
/* Peripheral Functions - Functions for Control Register */
/* ---------------------------------------------------------------------- */
/** Writes the control register 32-bits
* @param btimer_id Basic Timer ID
* @param value - 32-bit value to program
*/
void p_btimer_ctrl_write(uint8_t btimer_id, uint32_t value);
/** Reads the control register
* @param btimer_id Basic Timer ID
* @return uint32_t - 32-bit value
*/
uint32_t p_btimer_ctrl_read(uint8_t btimer_id);
/** Clears enable bit in the control register
* @param btimer_id Basic Timer ID
*/
void p_btimer_ctrl_enable_set(uint8_t btimer_id);
/** Clears enable bit in the control register
* @param btimer_id Basic Timer ID
*/
void p_btimer_ctrl_enable_clr(uint8_t btimer_id);
/** Sets counter direction bit in the control register
* @param btimer_id Basic Timer ID
*/
void p_btimer_ctrl_counter_dir_set(uint8_t btimer_id);
/** Clears counter direction bit in the control register
* @param btimer_id Basic Timer ID
*/
void p_btimer_ctrl_counter_dir_clr(uint8_t btimer_id);
/** Sets auto restart bit in the control register
* @param btimer_id Basic Timer ID
*/
void p_btimer_ctrl_auto_restart_set(uint8_t btimer_id);
/** Clears auto resetart bit in the control register
* @param btimer_id Basic Timer ID
*/
void p_btimer_ctrl_auto_restart_clr(uint8_t btimer_id);
/** Sets soft reset bit in the control register
* @param btimer_id Basic Timer ID
*/
void p_btimer_ctrl_soft_reset_set(uint8_t btimer_id);
/** Read Soft Reset bit
* @param btimer_id Basic Timer ID
* @return 0 if soft reset status bit cleared; else non-zero value
*/
uint8_t p_btimer_ctrl_soft_reset_sts_get(uint8_t btimer_id);
/** Sets start bit in the control register
* @param btimer_id Basic Timer ID
*/
void p_btimer_ctrl_start_set(uint8_t btimer_id);
/** Read start bit in the control register
* @param btimer_id Basic Timer ID
* @return 0 if start bit not set; else non-zero value
*/
uint8_t p_btimer_ctrl_start_get(uint8_t btimer_id);
/** Clears start bit in the control register
* @param btimer_id Basic Timer ID
*/
void p_btimer_ctrl_start_clr(uint8_t btimer_id);
/** Sets reload bit in the control register
* @param btimer_id Basic Timer ID
*/
void p_btimer_ctrl_reload_set(uint8_t btimer_id);
/** Clears reload bit in the control register
* @param btimer_id Basic Timer ID
*/
void p_btimer_ctrl_reload_clr(uint8_t btimer_id);
/** Sets halt bit in the control register
* @param btimer_id Basic Timer ID
*/
void p_btimer_ctrl_halt_set(uint8_t btimer_id);
/** Clears halt bit in the control register
* @param btimer_id Basic Timer ID
*/
void p_btimer_ctrl_halt_clr(uint8_t btimer_id);
/** Sets prescale value
* @param btimer_id Basic Timer ID
* @param prescaler - 16-bit pre-scale value
*/
void p_btimer_ctrl_prescale_set(uint8_t btimer_id, uint16_t prescaler);
#endif // #ifndef _BTIMER_H
/* end btimer_perphl.c */
/** @} //Peripherals Basic_Timer
*/

View File

@ -1,473 +1,474 @@
/*****************************************************************************
* © 2015 Microchip Technology Inc. and its subsidiaries.
* You may use this software and any derivatives exclusively with
* Microchip products.
* THIS SOFTWARE IS SUPPLIED BY MICROCHIP "AS IS".
* NO WARRANTIES, WHETHER EXPRESS, IMPLIED OR STATUTORY, APPLY TO THIS SOFTWARE,
* INCLUDING ANY IMPLIED WARRANTIES OF NON-INFRINGEMENT, MERCHANTABILITY,
* AND FITNESS FOR A PARTICULAR PURPOSE, OR ITS INTERACTION WITH MICROCHIP
* PRODUCTS, COMBINATION WITH ANY OTHER PRODUCTS, OR USE IN ANY APPLICATION.
* IN NO EVENT WILL MICROCHIP BE LIABLE FOR ANY INDIRECT, SPECIAL, PUNITIVE,
* INCIDENTAL OR CONSEQUENTIAL LOSS, DAMAGE, COST OR EXPENSE OF ANY KIND
* WHATSOEVER RELATED TO THE SOFTWARE, HOWEVER CAUSED, EVEN IF MICROCHIP HAS
* BEEN ADVISED OF THE POSSIBILITY OR THE DAMAGES ARE FORESEEABLE.
* TO THE FULLEST EXTENT ALLOWED BY LAW, MICROCHIP'S TOTAL LIABILITY ON ALL
* CLAIMS IN ANY WAY RELATED TO THIS SOFTWARE WILL NOT EXCEED THE AMOUNT OF
* FEES, IF ANY, THAT YOU HAVE PAID DIRECTLY TO MICROCHIP FOR THIS SOFTWARE.
* MICROCHIP PROVIDES THIS SOFTWARE CONDITIONALLY UPON YOUR ACCEPTANCE
* OF THESE TERMS.
******************************************************************************
Version Control Information (Perforce)
******************************************************************************
$Revision: #2 $
$DateTime: 2015/11/24 06:27:00 $
$Author: amohandas $
Last Change: Updated for tabs
******************************************************************************/
/** @file btimer_api.c
* \brief Basic Timer APIs Source file
* \author jvasanth
*
* This file implements the Basic Timer API functions
******************************************************************************/
/** @defgroup Basic_Timer
* @{
*/
#include "common_lib.h"
#include "btimer.h"
#include "..\pcr\pcr.h"
/** Basic Timer Sleep Registers & Bit Positions */
static const uint32_t btmr_pcr_id[BTIMER_MAX_INSTANCE] = {
PCR_BTIMER0,
PCR_BTIMER1,
PCR_BTIMER2,
PCR_BTIMER3,
PCR_BTIMER4,
PCR_BTIMER5
};
#ifdef PLIB_BTIMER_CHECK_ID
/** Local helper that checks if logical Timer ID is valid.
* @param btimer_id Basic Timer ID
* @return uint8_t Non-zero(VALID), 0(Invalid)
*/
static uint8_t btmr_valid(uint8_t btimer_id)
{
if ( btimer_id < (PID_BTIMER_MAX ) ) {
return true;
}
return false;
}
#else
/** This version of tmr_valid skips checking always returning 1.
* Compiler may optimize it out.
* @param btimer_id Basic Timer ID
* @return uint8_t 1(VALID)
*/
static uint8_t btmr_valid(uint8_t btimer_id) { return 1; }
#endif
/* ---------------------------------------------------------------------- */
/* Basic Timer Intitialization function */
/* ---------------------------------------------------------------------- */
/** Initialize specified timer
* @param btimer_id Basic Timer ID
* @param tmr_cntl Logical flags for Timer Control
* @param initial_count Initial Count
* @param preload_count Preload Count
* @note Performs a soft reset of the timer before configuration
*/
void btimer_init(uint8_t btimer_id,
uint16_t tmr_cntl,
uint16_t prescaler,
uint32_t initial_count,
uint32_t preload_count)
{
uint32_t value;
if (btmr_valid(btimer_id)) {
btimer_reset(btimer_id);
// Ungate timer clocks and program prescale
value = ((uint32_t)prescaler << 16) + (BTIMER_CNTL_ENABLE);
p_btimer_ctrl_write(btimer_id, value);
// Program Preload & initial counter value
p_btimer_preload_set(btimer_id, preload_count);
p_btimer_count_set(btimer_id, initial_count);
// Program control register, interrupt enable, and clear status
if (tmr_cntl & BTIMER_COUNT_UP) {
p_btimer_ctrl_counter_dir_set(btimer_id);
}
if (tmr_cntl & BTIMER_AUTO_RESTART) {
p_btimer_ctrl_auto_restart_set(btimer_id);
}
if (tmr_cntl & BTIMER_INT_EN) {
p_btimer_int_enable_set(btimer_id); // enable first
p_btimer_int_status_clr(btimer_id); // clear status
}
}
}
/* ---------------------------------------------------------------------- */
/* Functions to program and read the Basic Timer Counter */
/* ---------------------------------------------------------------------- */
/** Program timer's counter register.
* @param btimer_id Basic Timer ID
* @param count new counter value
* @note Timer hardware may implement a 16-bit or 32-bit
* hardware counter. If the timer is 16-bit only the lower
* 16-bits of the count paramter are used.
*/
void btimer_count_set(uint8_t btimer_id, uint32_t count)
{
if ( btmr_valid(btimer_id) ) {
p_btimer_count_set(btimer_id, count);
}
}
/** Return current value of timer's count register.
* @param btimer_id Basic Timer ID.
* @return uint32_t timer count may be 32 or 16 bits depending
* upon the hardware. Timers 0-3 are 16-bit
* and Timers 4-5 are 32-bit.
*/
uint32_t btimer_count_get(uint8_t btimer_id)
{
uint32_t cnt;
cnt = 0ul;
if ( btmr_valid(btimer_id) ) {
cnt = p_btimer_count_get(btimer_id);
}
return cnt;
}
/* ---------------------------------------------------------------------- */
/* Function to reload counter from Preload Register */
/* ---------------------------------------------------------------------- */
/** Force timer to reload counter from preload
* register.
* @param btimer_id Basic Timer ID.
* @note Hardware will only reload counter if timer is running.
*/
void btimer_reload(uint8_t btimer_id)
{
if ( btmr_valid(btimer_id) ) {
if (p_btimer_ctrl_start_get(btimer_id)) //Check if timer is running
{
p_btimer_ctrl_reload_set(btimer_id);
}
}
}
/* ---------------------------------------------------------------------- */
/* Functions for stopping and starting the basic Timer */
/* ---------------------------------------------------------------------- */
/** Start timer counting.
* @param btimer_id Basic Timer ID.
*/
void btimer_start(uint8_t btimer_id)
{
if ( btmr_valid(btimer_id) ) {
p_btimer_ctrl_start_set(btimer_id);
}
}
/** Stop timer.
* @param btimer_id Basic Timer ID.
* @note When a stopped timer is started again it will reload
* the count register from preload value.
*/
void btimer_stop(uint8_t btimer_id)
{
if ( btmr_valid(btimer_id) ) {
p_btimer_ctrl_start_clr(btimer_id);
}
}
/** Return state of timer's START bit.
* @param btimer_id Basic Timer ID.
* @return uint8_t 0(timer not started), 1 (timer started)
*/
uint8_t btimer_is_started(uint8_t btimer_id)
{
uint8_t sts;
sts = 0;
if ( btmr_valid(btimer_id) ) {
if (p_btimer_ctrl_start_get(btimer_id))
{
sts = 1;
}
}
return sts;
}
/* ---------------------------------------------------------------------- */
/* Function to perform basic timer soft reset */
/* ---------------------------------------------------------------------- */
/** Peform soft reset of specified timer.
* @param btimer_id Basic Timer ID
* @note Soft reset set all registers to POR values.
* Spins 256 times waiting on hardware to clear reset bit.
*/
void btimer_reset(uint8_t btimer_id)
{
uint32_t wait_cnt;
uint8_t soft_reset_sts;
if (btmr_valid(btimer_id)) {
p_btimer_ctrl_soft_reset_set(btimer_id);
wait_cnt = 256ul;
do {
soft_reset_sts = p_btimer_ctrl_soft_reset_sts_get(btimer_id);
if (0 == soft_reset_sts){
break;
}
}
while ( wait_cnt-- );
}
}
/* ---------------------------------------------------------------------- */
/* Functions to halt/unhalt the timer counting */
/* ---------------------------------------------------------------------- */
/** Halt timer counting with no reload on unhalt.
* @param btimer_id Basic Timer ID.
* @note A halted timer will not reload the count register when
* unhalted, it will continue counting from the current
* count value.
*/
void btimer_halt(uint8_t btimer_id)
{
if ( btmr_valid(btimer_id) ) {
p_btimer_ctrl_halt_set(btimer_id);
}
}
/** Unhalt timer counting.
* @param btimer_id Basic Timer ID.
*/
void btimer_unhalt(uint8_t btimer_id)
{
if ( btmr_valid(btimer_id) ) {
p_btimer_ctrl_halt_clr(btimer_id);
}
}
/* ---------------------------------------------------------------------- */
/* Functions for Basic Timer interrupt */
/* ---------------------------------------------------------------------- */
/** Enable specified timer's interrupt from the block.
* @param btimer_id Basic Timer ID.
* @param ien Non-zero enable interrupt in timer block, 0
* disable.
*/
void btimer_interrupt_enable(uint8_t btimer_id, uint8_t ien)
{
if (btmr_valid(btimer_id)) {
p_btimer_int_enable_set(btimer_id);
if (ien) {
p_btimer_int_enable_set(btimer_id);
} else {
p_btimer_int_enable_clr(btimer_id);
}
}
}
/** Read Timer interrupt status and clear if set
* @param btimer_id Basic Timer ID.
* @return uint8_t 1 (Timer interrupt status set) else 0.
* @note If timer interrupt status is set then clear it before
* returning.
*/
uint8_t btimer_interrupt_status_get_clr(uint8_t btimer_id)
{
uint8_t sts;
sts = 0;
if (btmr_valid(btimer_id)) {
sts = p_btimer_int_status_get(btimer_id);
if (sts) {
p_btimer_int_status_clr(btimer_id);
}
}
return sts;
}
#if 0 //Temporary disable until interrupt module
/* ---------------------------------------------------------------------- */
/* Functions for Basic Timer GIRQ */
/* ---------------------------------------------------------------------- */
/** Enables GIRQ enable bit for the timer
* @param btimer_id Basic Timer ID.
*/
void btimer_girq_enable_set(uint8_t btimer_id)
{
if (btmr_valid(btimer_id))
{
//Note: Bit Position is same as Timer ID
p_ecia_girq_enable_set(BTIMER_GIRQ, btimer_id);
}
}
/** Clears GIRQ enable bit for the timer
* @param btimer_id Basic Timer ID.
*/
void btimer_girq_enable_clr(uint8_t btimer_id)
{
if (btmr_valid(btimer_id))
{
//Note: Bit Position is same as Timer ID
p_ecia_girq_enable_clr(BTIMER_GIRQ, btimer_id);
}
}
/** Returns GIRQ source bit for the timer
* @param btimer_id Basic Timer ID.
* @return uint8_t 0(src bit not set), Non-zero (src bit set)
*/
uint8_t btimer_girq_src_get(uint8_t btimer_id)
{
uint8_t retVal;
retVal = 0;
if (btmr_valid(btimer_id))
{
//Note: Bit Position is same as Timer ID
retVal = p_ecia_girq_source_get(BTIMER_GIRQ, btimer_id);
}
return retVal;
}
/** Clears GIRQ source bit for the timer
* @param btimer_id Basic Timer ID.
*/
void btimer_girq_src_clr(uint8_t btimer_id)
{
if (btmr_valid(btimer_id))
{
//Note: Bit Position is same as Timer ID
p_ecia_girq_source_clr(BTIMER_GIRQ, btimer_id);
}
}
/** Returns GIRQ result bit for the timer
* @param btimer_id Basic Timer ID.
* @return uint8_t 0(result bit not set), Non-zero (result bit set)
*/
uint8_t btimer_girq_result_get(uint8_t btimer_id)
{
uint8_t retVal;
retVal = 0;
if (btmr_valid(btimer_id))
{
//Note: Bit Position is same as Timer ID
retVal = p_ecia_girq_result_get(BTIMER_GIRQ, btimer_id);
}
return retVal;
}
#endif
/* ---------------------------------------------------------------------- */
/* Functions for Basic Timer Sleep */
/* ---------------------------------------------------------------------- */
/** Enable/Disable clock gating on idle of a timer
* @param btimer_id Basic Timer ID.
* @param sleep_en 1 = Sleep enable, 0 = Sleep disable
*/
void btimer_sleep(uint8_t btimer_id, uint8_t sleep_en)
{
uint32_t pcr_blk_id;
if ( btmr_valid(btimer_id) )
{
pcr_blk_id = btmr_pcr_id[btimer_id];
pcr_sleep_enable(pcr_blk_id, sleep_en);
}
}
/** Returns clk required status for the timer block
* @param btimer_id Basic Timer ID.
* @return Non-zero if clk required, else 0
*/
uint32_t btimer_clk_reqd_sts_get(uint8_t btimer_id)
{
uint32_t retVal;
uint32_t pcr_blk_id;
retVal = 0ul;
if ( btmr_valid(btimer_id) )
{
pcr_blk_id = btmr_pcr_id[btimer_id];
retVal = pcr_clock_reqd_status_get(pcr_blk_id);
}
return retVal;
}
/** Enable/Disable reset on sleep for the timer block
* @param btimer_id Basic Timer ID.
* @param reset_en 1 to enable, 0 to disable
*/
void btimer_reset_on_sleep(uint8_t btimer_id, uint8_t reset_en)
{
uint32_t pcr_blk_id;
if ( btmr_valid(btimer_id) )
{
pcr_blk_id = btmr_pcr_id[btimer_id];
pcr_reset_enable(pcr_blk_id, reset_en);
}
}
/* end btimer_api.c */
/** @} //Peripheral Basic_Timer
*/
/*****************************************************************************
* © 2015 Microchip Technology Inc. and its subsidiaries.
* You may use this software and any derivatives exclusively with
* Microchip products.
* THIS SOFTWARE IS SUPPLIED BY MICROCHIP "AS IS".
* NO WARRANTIES, WHETHER EXPRESS, IMPLIED OR STATUTORY, APPLY TO THIS SOFTWARE,
* INCLUDING ANY IMPLIED WARRANTIES OF NON-INFRINGEMENT, MERCHANTABILITY,
* AND FITNESS FOR A PARTICULAR PURPOSE, OR ITS INTERACTION WITH MICROCHIP
* PRODUCTS, COMBINATION WITH ANY OTHER PRODUCTS, OR USE IN ANY APPLICATION.
* IN NO EVENT WILL MICROCHIP BE LIABLE FOR ANY INDIRECT, SPECIAL, PUNITIVE,
* INCIDENTAL OR CONSEQUENTIAL LOSS, DAMAGE, COST OR EXPENSE OF ANY KIND
* WHATSOEVER RELATED TO THE SOFTWARE, HOWEVER CAUSED, EVEN IF MICROCHIP HAS
* BEEN ADVISED OF THE POSSIBILITY OR THE DAMAGES ARE FORESEEABLE.
* TO THE FULLEST EXTENT ALLOWED BY LAW, MICROCHIP'S TOTAL LIABILITY ON ALL
* CLAIMS IN ANY WAY RELATED TO THIS SOFTWARE WILL NOT EXCEED THE AMOUNT OF
* FEES, IF ANY, THAT YOU HAVE PAID DIRECTLY TO MICROCHIP FOR THIS SOFTWARE.
* MICROCHIP PROVIDES THIS SOFTWARE CONDITIONALLY UPON YOUR ACCEPTANCE
* OF THESE TERMS.
******************************************************************************
Version Control Information (Perforce)
******************************************************************************
$Revision: #1 $
$DateTime: 2016/04/08 10:18:28 $
$Author: pramans $
Last Change: Updated for tabs
******************************************************************************/
/** @file btimer_api.c
* \brief Basic Timer APIs Source file
* \author jvasanth
*
* This file implements the Basic Timer API functions
******************************************************************************/
/** @defgroup Basic_Timer
* @{
*/
#include "common_lib.h"
#include "btimer.h"
#include "..\pcr\pcr.h"
//#include "..\interrupt\ecia.h"
/** Basic Timer Sleep Registers & Bit Positions */
static const uint32_t btmr_pcr_id[BTIMER_MAX_INSTANCE] = {
PCR_BTIMER0,
PCR_BTIMER1,
PCR_BTIMER2,
PCR_BTIMER3,
PCR_BTIMER4,
PCR_BTIMER5
};
#ifdef PLIB_BTIMER_CHECK_ID
/** Local helper that checks if logical Timer ID is valid.
* @param btimer_id Basic Timer ID
* @return uint8_t Non-zero(VALID), 0(Invalid)
*/
static uint8_t btmr_valid(uint8_t btimer_id)
{
if ( btimer_id < (PID_BTIMER_MAX ) ) {
return true;
}
return false;
}
#else
/** This version of tmr_valid skips checking always returning 1.
* Compiler may optimize it out.
* @param btimer_id Basic Timer ID
* @return uint8_t 1(VALID)
*/
static uint8_t btmr_valid(uint8_t btimer_id) { return 1; }
#endif
/* ---------------------------------------------------------------------- */
/* Basic Timer Intitialization function */
/* ---------------------------------------------------------------------- */
/** Initialize specified timer
* @param btimer_id Basic Timer ID
* @param tmr_cntl Logical flags for Timer Control
* @param initial_count Initial Count
* @param preload_count Preload Count
* @note Performs a soft reset of the timer before configuration
*/
void btimer_init(uint8_t btimer_id,
uint16_t tmr_cntl,
uint16_t prescaler,
uint32_t initial_count,
uint32_t preload_count)
{
uint32_t value;
if (btmr_valid(btimer_id)) {
btimer_reset(btimer_id);
// Ungate timer clocks and program prescale
value = ((uint32_t)prescaler << 16) + (BTIMER_CNTL_ENABLE);
p_btimer_ctrl_write(btimer_id, value);
// Program Preload & initial counter value
p_btimer_preload_set(btimer_id, preload_count);
p_btimer_count_set(btimer_id, initial_count);
// Program control register, interrupt enable, and clear status
if (tmr_cntl & BTIMER_COUNT_UP) {
p_btimer_ctrl_counter_dir_set(btimer_id);
}
if (tmr_cntl & BTIMER_AUTO_RESTART) {
p_btimer_ctrl_auto_restart_set(btimer_id);
}
if (tmr_cntl & BTIMER_INT_EN) {
p_btimer_int_enable_set(btimer_id); // enable first
p_btimer_int_status_clr(btimer_id); // clear status
}
}
}
/* ---------------------------------------------------------------------- */
/* Functions to program and read the Basic Timer Counter */
/* ---------------------------------------------------------------------- */
/** Program timer's counter register.
* @param btimer_id Basic Timer ID
* @param count new counter value
* @note Timer hardware may implement a 16-bit or 32-bit
* hardware counter. If the timer is 16-bit only the lower
* 16-bits of the count paramter are used.
*/
void btimer_count_set(uint8_t btimer_id, uint32_t count)
{
if ( btmr_valid(btimer_id) ) {
p_btimer_count_set(btimer_id, count);
}
}
/** Return current value of timer's count register.
* @param btimer_id Basic Timer ID.
* @return uint32_t timer count may be 32 or 16 bits depending
* upon the hardware. Timers 0-3 are 16-bit
* and Timers 4-5 are 32-bit.
*/
uint32_t btimer_count_get(uint8_t btimer_id)
{
uint32_t cnt;
cnt = 0ul;
if ( btmr_valid(btimer_id) ) {
cnt = p_btimer_count_get(btimer_id);
}
return cnt;
}
/* ---------------------------------------------------------------------- */
/* Function to reload counter from Preload Register */
/* ---------------------------------------------------------------------- */
/** Force timer to reload counter from preload
* register.
* @param btimer_id Basic Timer ID.
* @note Hardware will only reload counter if timer is running.
*/
void btimer_reload(uint8_t btimer_id)
{
if ( btmr_valid(btimer_id) ) {
if (p_btimer_ctrl_start_get(btimer_id)) //Check if timer is running
{
p_btimer_ctrl_reload_set(btimer_id);
}
}
}
/* ---------------------------------------------------------------------- */
/* Functions for stopping and starting the basic Timer */
/* ---------------------------------------------------------------------- */
/** Start timer counting.
* @param btimer_id Basic Timer ID.
*/
void btimer_start(uint8_t btimer_id)
{
if ( btmr_valid(btimer_id) ) {
p_btimer_ctrl_start_set(btimer_id);
}
}
/** Stop timer.
* @param btimer_id Basic Timer ID.
* @note When a stopped timer is started again it will reload
* the count register from preload value.
*/
void btimer_stop(uint8_t btimer_id)
{
if ( btmr_valid(btimer_id) ) {
p_btimer_ctrl_start_clr(btimer_id);
}
}
/** Return state of timer's START bit.
* @param btimer_id Basic Timer ID.
* @return uint8_t 0(timer not started), 1 (timer started)
*/
uint8_t btimer_is_started(uint8_t btimer_id)
{
uint8_t sts;
sts = 0;
if ( btmr_valid(btimer_id) ) {
if (p_btimer_ctrl_start_get(btimer_id))
{
sts = 1;
}
}
return sts;
}
/* ---------------------------------------------------------------------- */
/* Function to perform basic timer soft reset */
/* ---------------------------------------------------------------------- */
/** Peform soft reset of specified timer.
* @param btimer_id Basic Timer ID
* @note Soft reset set all registers to POR values.
* Spins 256 times waiting on hardware to clear reset bit.
*/
void btimer_reset(uint8_t btimer_id)
{
uint32_t wait_cnt;
uint8_t soft_reset_sts;
if (btmr_valid(btimer_id)) {
p_btimer_ctrl_soft_reset_set(btimer_id);
wait_cnt = 256ul;
do {
soft_reset_sts = p_btimer_ctrl_soft_reset_sts_get(btimer_id);
if (0 == soft_reset_sts){
break;
}
}
while ( wait_cnt-- );
}
}
/* ---------------------------------------------------------------------- */
/* Functions to halt/unhalt the timer counting */
/* ---------------------------------------------------------------------- */
/** Halt timer counting with no reload on unhalt.
* @param btimer_id Basic Timer ID.
* @note A halted timer will not reload the count register when
* unhalted, it will continue counting from the current
* count value.
*/
void btimer_halt(uint8_t btimer_id)
{
if ( btmr_valid(btimer_id) ) {
p_btimer_ctrl_halt_set(btimer_id);
}
}
/** Unhalt timer counting.
* @param btimer_id Basic Timer ID.
*/
void btimer_unhalt(uint8_t btimer_id)
{
if ( btmr_valid(btimer_id) ) {
p_btimer_ctrl_halt_clr(btimer_id);
}
}
/* ---------------------------------------------------------------------- */
/* Functions for Basic Timer interrupt */
/* ---------------------------------------------------------------------- */
/** Enable specified timer's interrupt from the block.
* @param btimer_id Basic Timer ID.
* @param ien Non-zero enable interrupt in timer block, 0
* disable.
*/
void btimer_interrupt_enable(uint8_t btimer_id, uint8_t ien)
{
if (btmr_valid(btimer_id)) {
p_btimer_int_enable_set(btimer_id);
if (ien) {
p_btimer_int_enable_set(btimer_id);
} else {
p_btimer_int_enable_clr(btimer_id);
}
}
}
/** Read Timer interrupt status and clear if set
* @param btimer_id Basic Timer ID.
* @return uint8_t 1 (Timer interrupt status set) else 0.
* @note If timer interrupt status is set then clear it before
* returning.
*/
uint8_t btimer_interrupt_status_get_clr(uint8_t btimer_id)
{
uint8_t sts;
sts = 0;
if (btmr_valid(btimer_id)) {
sts = p_btimer_int_status_get(btimer_id);
if (sts) {
p_btimer_int_status_clr(btimer_id);
}
}
return sts;
}
#if 0 //Temporary disable until interrupt module
/* ---------------------------------------------------------------------- */
/* Functions for Basic Timer GIRQ */
/* ---------------------------------------------------------------------- */
/** Enables GIRQ enable bit for the timer
* @param btimer_id Basic Timer ID.
*/
void btimer_girq_enable_set(uint8_t btimer_id)
{
if (btmr_valid(btimer_id))
{
//Note: Bit Position is same as Timer ID
p_ecia_girq_enable_set(BTIMER_GIRQ, btimer_id);
}
}
/** Clears GIRQ enable bit for the timer
* @param btimer_id Basic Timer ID.
*/
void btimer_girq_enable_clr(uint8_t btimer_id)
{
if (btmr_valid(btimer_id))
{
//Note: Bit Position is same as Timer ID
p_ecia_girq_enable_clr(BTIMER_GIRQ, btimer_id);
}
}
/** Returns GIRQ source bit for the timer
* @param btimer_id Basic Timer ID.
* @return uint8_t 0(src bit not set), Non-zero (src bit set)
*/
uint8_t btimer_girq_src_get(uint8_t btimer_id)
{
uint8_t retVal;
retVal = 0;
if (btmr_valid(btimer_id))
{
//Note: Bit Position is same as Timer ID
retVal = p_ecia_girq_source_get(BTIMER_GIRQ, btimer_id);
}
return retVal;
}
/** Clears GIRQ source bit for the timer
* @param btimer_id Basic Timer ID.
*/
void btimer_girq_src_clr(uint8_t btimer_id)
{
if (btmr_valid(btimer_id))
{
//Note: Bit Position is same as Timer ID
p_ecia_girq_source_clr(BTIMER_GIRQ, btimer_id);
}
}
/** Returns GIRQ result bit for the timer
* @param btimer_id Basic Timer ID.
* @return uint8_t 0(result bit not set), Non-zero (result bit set)
*/
uint8_t btimer_girq_result_get(uint8_t btimer_id)
{
uint8_t retVal;
retVal = 0;
if (btmr_valid(btimer_id))
{
//Note: Bit Position is same as Timer ID
retVal = p_ecia_girq_result_get(BTIMER_GIRQ, btimer_id);
}
return retVal;
}
#endif
/* ---------------------------------------------------------------------- */
/* Functions for Basic Timer Sleep */
/* ---------------------------------------------------------------------- */
/** Enable/Disable clock gating on idle of a timer
* @param btimer_id Basic Timer ID.
* @param sleep_en 1 = Sleep enable, 0 = Sleep disable
*/
void btimer_sleep(uint8_t btimer_id, uint8_t sleep_en)
{
uint32_t pcr_blk_id;
if ( btmr_valid(btimer_id) )
{
pcr_blk_id = btmr_pcr_id[btimer_id];
pcr_sleep_enable(pcr_blk_id, sleep_en);
}
}
/** Returns clk required status for the timer block
* @param btimer_id Basic Timer ID.
* @return Non-zero if clk required, else 0
*/
uint32_t btimer_clk_reqd_sts_get(uint8_t btimer_id)
{
uint32_t retVal;
uint32_t pcr_blk_id;
retVal = 0ul;
if ( btmr_valid(btimer_id) )
{
pcr_blk_id = btmr_pcr_id[btimer_id];
retVal = pcr_clock_reqd_status_get(pcr_blk_id);
}
return retVal;
}
/** Enable/Disable reset on sleep for the timer block
* @param btimer_id Basic Timer ID.
* @param reset_en 1 to enable, 0 to disable
*/
void btimer_reset_on_sleep(uint8_t btimer_id, uint8_t reset_en)
{
uint32_t pcr_blk_id;
if ( btmr_valid(btimer_id) )
{
pcr_blk_id = btmr_pcr_id[btimer_id];
pcr_reset_enable(pcr_blk_id, reset_en);
}
}
/* end btimer_api.c */
/** @} //Peripheral Basic_Timer
*/

View File

@ -1,287 +1,287 @@
/*****************************************************************************
* © 2015 Microchip Technology Inc. and its subsidiaries.
* You may use this software and any derivatives exclusively with
* Microchip products.
* THIS SOFTWARE IS SUPPLIED BY MICROCHIP "AS IS".
* NO WARRANTIES, WHETHER EXPRESS, IMPLIED OR STATUTORY, APPLY TO THIS SOFTWARE,
* INCLUDING ANY IMPLIED WARRANTIES OF NON-INFRINGEMENT, MERCHANTABILITY,
* AND FITNESS FOR A PARTICULAR PURPOSE, OR ITS INTERACTION WITH MICROCHIP
* PRODUCTS, COMBINATION WITH ANY OTHER PRODUCTS, OR USE IN ANY APPLICATION.
* IN NO EVENT WILL MICROCHIP BE LIABLE FOR ANY INDIRECT, SPECIAL, PUNITIVE,
* INCIDENTAL OR CONSEQUENTIAL LOSS, DAMAGE, COST OR EXPENSE OF ANY KIND
* WHATSOEVER RELATED TO THE SOFTWARE, HOWEVER CAUSED, EVEN IF MICROCHIP HAS
* BEEN ADVISED OF THE POSSIBILITY OR THE DAMAGES ARE FORESEEABLE.
* TO THE FULLEST EXTENT ALLOWED BY LAW, MICROCHIP'S TOTAL LIABILITY ON ALL
* CLAIMS IN ANY WAY RELATED TO THIS SOFTWARE WILL NOT EXCEED THE AMOUNT OF
* FEES, IF ANY, THAT YOU HAVE PAID DIRECTLY TO MICROCHIP FOR THIS SOFTWARE.
* MICROCHIP PROVIDES THIS SOFTWARE CONDITIONALLY UPON YOUR ACCEPTANCE
* OF THESE TERMS.
******************************************************************************
Version Control Information (Perforce)
******************************************************************************
$Revision: #2 $
$DateTime: 2015/11/24 06:27:00 $
$Author: amohandas $
Last Change: Updated for tabs
******************************************************************************/
/** @file btimer_perphl.c
* \brief Basic Timer Peripheral Source file
* \author jvasanth
*
* This file implements the Basic Timer Peripheral functions
******************************************************************************/
/** @defgroup Basic_Timer
* @{
*/
#include "common_lib.h"
#include "btimer.h"
/** Basic Timer Instance base addresses */
static TIMER_16_0_Type * const btmr_inst[BTIMER_MAX_INSTANCE] = {
CEC1302_TIMER_16_0,
CEC1302_TIMER_16_1,
CEC1302_TIMER_16_2,
CEC1302_TIMER_16_3,
CEC1302_TIMER_32_0,
CEC1302_TIMER_32_1
};
/* ---------------------------------------------------------------------- */
/* Functions to set and read Timer Counter Register */
/* ---------------------------------------------------------------------- */
/** Sets timer counter
* @param btimer_id Basic Timer ID
* @param count - 32-bit counter
*/
void p_btimer_count_set(uint8_t btimer_id, uint32_t count)
{
btmr_inst[btimer_id]->COUNT = count;
}
/** Read the timer counter
* @param btimer_id Basic Timer ID
* @return count - 32-bit counter
*/
uint32_t p_btimer_count_get(uint8_t btimer_id)
{
return btmr_inst[btimer_id]->COUNT;
}
/* ---------------------------------------------------------------------- */
/* Function to program the Preload */
/* ---------------------------------------------------------------------- */
/** Sets preload for the counter
* @param btimer_id Basic Timer ID
* @param preload_count - 32-bit pre-load value
*/
void p_btimer_preload_set(uint8_t btimer_id, uint32_t preload_count)
{
btmr_inst[btimer_id]->PRE_LOAD = preload_count;
}
/* ---------------------------------------------------------------------- */
/* Functions for basic timer interrupts */
/* ---------------------------------------------------------------------- */
/** Reads the interrupt status bit in the timer block
* @param btimer_id Basic Timer ID
* @return status - 1 if interrupt status set, else 0
*/
uint8_t p_btimer_int_status_get(uint8_t btimer_id)
{
return (uint8_t)(btmr_inst[btimer_id]->INTERRUPT_STATUS);
}
/** Clears interrupt status bit in the timer block
* @param btimer_id Basic Timer ID
*/
void p_btimer_int_status_clr(uint8_t btimer_id)
{
// Write 1 to clear
btmr_inst[btimer_id]->INTERRUPT_STATUS = 1;
}
/** Sets interrupt enable bit in the timer block
* @param btimer_id Basic Timer ID
*/
void p_btimer_int_enable_set(uint8_t btimer_id)
{
btmr_inst[btimer_id]->INTERRUPT_ENABLE = 1;
}
/** Clears interrupt enable bit for the timer block
* @param btimer_id Basic Timer ID
*/
void p_btimer_int_enable_clr(uint8_t btimer_id)
{
btmr_inst[btimer_id]->INTERRUPT_ENABLE = 0;
}
/* ---------------------------------------------------------------------- */
/* Functions for Control Register */
/* ---------------------------------------------------------------------- */
/** Writes the control register 32-bits
* @param btimer_id Basic Timer ID
* @param value - 32-bit value to program
*/
void p_btimer_ctrl_write(uint8_t btimer_id, uint32_t value)
{
btmr_inst[btimer_id]->CONTROL.w = value;
}
/** Reads the control register
* @param btimer_id Basic Timer ID
* @return uint32_t - 32-bit value
*/
uint32_t p_btimer_ctrl_read(uint8_t btimer_id)
{
uint32_t retVal;
retVal = btmr_inst[btimer_id]->CONTROL.w;
return retVal;
}
/** Sets enable bit in the control register
* @param btimer_id Basic Timer ID
*/
void p_btimer_ctrl_enable_set(uint8_t btimer_id)
{
btmr_inst[btimer_id]->CONTROL.b[0] |= BTIMER_CNTL_ENABLE;
}
/** Clears enable bit in the control register
* @param btimer_id Basic Timer ID
*/
void p_btimer_ctrl_enable_clr(uint8_t btimer_id)
{
btmr_inst[btimer_id]->CONTROL.b[0] &= ~BTIMER_CNTL_ENABLE;
}
/** Sets counter direction bit in the control register
* @param btimer_id Basic Timer ID
*/
void p_btimer_ctrl_counter_dir_set(uint8_t btimer_id)
{
btmr_inst[btimer_id]->CONTROL.b[0] |= BTIMER_CNTL_COUNT_UP;
}
/** Clears counter direction bit in the control register
* @param btimer_id Basic Timer ID
*/
void p_btimer_ctrl_counter_dir_clr(uint8_t btimer_id)
{
btmr_inst[btimer_id]->CONTROL.b[0] &= ~BTIMER_CNTL_COUNT_UP;
}
/** Sets auto restart bit in the control register
* @param btimer_id Basic Timer ID
*/
void p_btimer_ctrl_auto_restart_set(uint8_t btimer_id)
{
btmr_inst[btimer_id]->CONTROL.b[0] |= BTIMER_CNTL_AUTO_RESTART;
}
/** Clears auto resetart bit in the control register
* @param btimer_id Basic Timer ID
*/
void p_btimer_ctrl_auto_restart_clr(uint8_t btimer_id)
{
btmr_inst[btimer_id]->CONTROL.b[0] &= ~BTIMER_CNTL_AUTO_RESTART;
}
/** Sets soft reset bit in the control register
* @param btimer_id Basic Timer ID
*/
void p_btimer_ctrl_soft_reset_set(uint8_t btimer_id)
{
btmr_inst[btimer_id]->CONTROL.b[0] |= BTIMER_CNTL_SOFT_RESET;
}
/** Read Soft Reset bit
* @param btimer_id Basic Timer ID
* @return 0 if soft reset status bit cleared; else non-zero value
*/
uint8_t p_btimer_ctrl_soft_reset_sts_get(uint8_t btimer_id)
{
return (btmr_inst[btimer_id]->CONTROL.b[0] & BTIMER_CNTL_SOFT_RESET);
}
/** Sets start bit in the control register
* @param btimer_id Basic Timer ID
*/
void p_btimer_ctrl_start_set(uint8_t btimer_id)
{
btmr_inst[btimer_id]->CONTROL.b[0] |= BTIMER_CNTL_START;
}
/** Read start bit in the control register
* @param btimer_id Basic Timer ID
* @return 0 if start bit not set; else non-zero value
*/
uint8_t p_btimer_ctrl_start_get(uint8_t btimer_id)
{
return (btmr_inst[btimer_id]->CONTROL.b[0] & BTIMER_CNTL_START);
}
/** Clears start bit in the control register
* @param btimer_id Basic Timer ID
*/
void p_btimer_ctrl_start_clr(uint8_t btimer_id)
{
btmr_inst[btimer_id]->CONTROL.b[0] &= ~BTIMER_CNTL_START;
}
/** Sets reload bit in the control register
* @param btimer_id Basic Timer ID
*/
void p_btimer_ctrl_reload_set(uint8_t btimer_id)
{
btmr_inst[btimer_id]->CONTROL.b[0] |= BTIMER_CNTL_RELOAD;
}
/** Clears reload bit in the control register
* @param btimer_id Basic Timer ID
*/
void p_btimer_ctrl_reload_clr(uint8_t btimer_id)
{
btmr_inst[btimer_id]->CONTROL.b[0] &= ~BTIMER_CNTL_RELOAD;
}
/** Sets halt bit in the control register
* @param btimer_id Basic Timer ID
*/
void p_btimer_ctrl_halt_set(uint8_t btimer_id)
{
btmr_inst[btimer_id]->CONTROL.b[0] |= BTIMER_CNTL_HALT;
}
/** Clears halt bit in the control register
* @param btimer_id Basic Timer ID
*/
void p_btimer_ctrl_halt_clr(uint8_t btimer_id)
{
btmr_inst[btimer_id]->CONTROL.b[0] &= ~BTIMER_CNTL_HALT;
}
/** Sets prescale value
* @param btimer_id Basic Timer ID
* @param prescaler - 16-bit pre-scale value
*/
void p_btimer_ctrl_prescale_set(uint8_t btimer_id, uint16_t prescaler)
{
btmr_inst[btimer_id]->CONTROL.h[1] = prescaler;
}
/* end btimer_perphl.c */
/** @} //Peripheral Basic_Timer
*/
/*****************************************************************************
* © 2015 Microchip Technology Inc. and its subsidiaries.
* You may use this software and any derivatives exclusively with
* Microchip products.
* THIS SOFTWARE IS SUPPLIED BY MICROCHIP "AS IS".
* NO WARRANTIES, WHETHER EXPRESS, IMPLIED OR STATUTORY, APPLY TO THIS SOFTWARE,
* INCLUDING ANY IMPLIED WARRANTIES OF NON-INFRINGEMENT, MERCHANTABILITY,
* AND FITNESS FOR A PARTICULAR PURPOSE, OR ITS INTERACTION WITH MICROCHIP
* PRODUCTS, COMBINATION WITH ANY OTHER PRODUCTS, OR USE IN ANY APPLICATION.
* IN NO EVENT WILL MICROCHIP BE LIABLE FOR ANY INDIRECT, SPECIAL, PUNITIVE,
* INCIDENTAL OR CONSEQUENTIAL LOSS, DAMAGE, COST OR EXPENSE OF ANY KIND
* WHATSOEVER RELATED TO THE SOFTWARE, HOWEVER CAUSED, EVEN IF MICROCHIP HAS
* BEEN ADVISED OF THE POSSIBILITY OR THE DAMAGES ARE FORESEEABLE.
* TO THE FULLEST EXTENT ALLOWED BY LAW, MICROCHIP'S TOTAL LIABILITY ON ALL
* CLAIMS IN ANY WAY RELATED TO THIS SOFTWARE WILL NOT EXCEED THE AMOUNT OF
* FEES, IF ANY, THAT YOU HAVE PAID DIRECTLY TO MICROCHIP FOR THIS SOFTWARE.
* MICROCHIP PROVIDES THIS SOFTWARE CONDITIONALLY UPON YOUR ACCEPTANCE
* OF THESE TERMS.
******************************************************************************
Version Control Information (Perforce)
******************************************************************************
$Revision: #1 $
$DateTime: 2016/04/08 10:18:28 $
$Author: pramans $
Last Change: Updated for tabs
******************************************************************************/
/** @file btimer_perphl.c
* \brief Basic Timer Peripheral Source file
* \author jvasanth
*
* This file implements the Basic Timer Peripheral functions
******************************************************************************/
/** @defgroup Basic_Timer
* @{
*/
#include "common_lib.h"
#include "btimer.h"
/** Basic Timer Instance base addresses */
static TIMER_16_0_Type * const btmr_inst[BTIMER_MAX_INSTANCE] = {
CEC1302_TIMER_16_0,
CEC1302_TIMER_16_1,
CEC1302_TIMER_16_2,
CEC1302_TIMER_16_3,
CEC1302_TIMER_32_0,
CEC1302_TIMER_32_1
};
/* ---------------------------------------------------------------------- */
/* Functions to set and read Timer Counter Register */
/* ---------------------------------------------------------------------- */
/** Sets timer counter
* @param btimer_id Basic Timer ID
* @param count - 32-bit counter
*/
void p_btimer_count_set(uint8_t btimer_id, uint32_t count)
{
btmr_inst[btimer_id]->COUNT = count;
}
/** Read the timer counter
* @param btimer_id Basic Timer ID
* @return count - 32-bit counter
*/
uint32_t p_btimer_count_get(uint8_t btimer_id)
{
return btmr_inst[btimer_id]->COUNT;
}
/* ---------------------------------------------------------------------- */
/* Function to program the Preload */
/* ---------------------------------------------------------------------- */
/** Sets preload for the counter
* @param btimer_id Basic Timer ID
* @param preload_count - 32-bit pre-load value
*/
void p_btimer_preload_set(uint8_t btimer_id, uint32_t preload_count)
{
btmr_inst[btimer_id]->PRE_LOAD = preload_count;
}
/* ---------------------------------------------------------------------- */
/* Functions for basic timer interrupts */
/* ---------------------------------------------------------------------- */
/** Reads the interrupt status bit in the timer block
* @param btimer_id Basic Timer ID
* @return status - 1 if interrupt status set, else 0
*/
uint8_t p_btimer_int_status_get(uint8_t btimer_id)
{
return (uint8_t)(btmr_inst[btimer_id]->INTERRUPT_STATUS);
}
/** Clears interrupt status bit in the timer block
* @param btimer_id Basic Timer ID
*/
void p_btimer_int_status_clr(uint8_t btimer_id)
{
// Write 1 to clear
btmr_inst[btimer_id]->INTERRUPT_STATUS = 1;
}
/** Sets interrupt enable bit in the timer block
* @param btimer_id Basic Timer ID
*/
void p_btimer_int_enable_set(uint8_t btimer_id)
{
btmr_inst[btimer_id]->INTERRUPT_ENABLE = 1;
}
/** Clears interrupt enable bit for the timer block
* @param btimer_id Basic Timer ID
*/
void p_btimer_int_enable_clr(uint8_t btimer_id)
{
btmr_inst[btimer_id]->INTERRUPT_ENABLE = 0;
}
/* ---------------------------------------------------------------------- */
/* Functions for Control Register */
/* ---------------------------------------------------------------------- */
/** Writes the control register 32-bits
* @param btimer_id Basic Timer ID
* @param value - 32-bit value to program
*/
void p_btimer_ctrl_write(uint8_t btimer_id, uint32_t value)
{
btmr_inst[btimer_id]->CONTROL.w = value;
}
/** Reads the control register
* @param btimer_id Basic Timer ID
* @return uint32_t - 32-bit value
*/
uint32_t p_btimer_ctrl_read(uint8_t btimer_id)
{
uint32_t retVal;
retVal = btmr_inst[btimer_id]->CONTROL.w;
return retVal;
}
/** Sets enable bit in the control register
* @param btimer_id Basic Timer ID
*/
void p_btimer_ctrl_enable_set(uint8_t btimer_id)
{
btmr_inst[btimer_id]->CONTROL.b[0] |= BTIMER_CNTL_ENABLE;
}
/** Clears enable bit in the control register
* @param btimer_id Basic Timer ID
*/
void p_btimer_ctrl_enable_clr(uint8_t btimer_id)
{
btmr_inst[btimer_id]->CONTROL.b[0] &= ~BTIMER_CNTL_ENABLE;
}
/** Sets counter direction bit in the control register
* @param btimer_id Basic Timer ID
*/
void p_btimer_ctrl_counter_dir_set(uint8_t btimer_id)
{
btmr_inst[btimer_id]->CONTROL.b[0] |= BTIMER_CNTL_COUNT_UP;
}
/** Clears counter direction bit in the control register
* @param btimer_id Basic Timer ID
*/
void p_btimer_ctrl_counter_dir_clr(uint8_t btimer_id)
{
btmr_inst[btimer_id]->CONTROL.b[0] &= ~BTIMER_CNTL_COUNT_UP;
}
/** Sets auto restart bit in the control register
* @param btimer_id Basic Timer ID
*/
void p_btimer_ctrl_auto_restart_set(uint8_t btimer_id)
{
btmr_inst[btimer_id]->CONTROL.b[0] |= BTIMER_CNTL_AUTO_RESTART;
}
/** Clears auto resetart bit in the control register
* @param btimer_id Basic Timer ID
*/
void p_btimer_ctrl_auto_restart_clr(uint8_t btimer_id)
{
btmr_inst[btimer_id]->CONTROL.b[0] &= ~BTIMER_CNTL_AUTO_RESTART;
}
/** Sets soft reset bit in the control register
* @param btimer_id Basic Timer ID
*/
void p_btimer_ctrl_soft_reset_set(uint8_t btimer_id)
{
btmr_inst[btimer_id]->CONTROL.b[0] |= BTIMER_CNTL_SOFT_RESET;
}
/** Read Soft Reset bit
* @param btimer_id Basic Timer ID
* @return 0 if soft reset status bit cleared; else non-zero value
*/
uint8_t p_btimer_ctrl_soft_reset_sts_get(uint8_t btimer_id)
{
return (btmr_inst[btimer_id]->CONTROL.b[0] & BTIMER_CNTL_SOFT_RESET);
}
/** Sets start bit in the control register
* @param btimer_id Basic Timer ID
*/
void p_btimer_ctrl_start_set(uint8_t btimer_id)
{
btmr_inst[btimer_id]->CONTROL.b[0] |= BTIMER_CNTL_START;
}
/** Read start bit in the control register
* @param btimer_id Basic Timer ID
* @return 0 if start bit not set; else non-zero value
*/
uint8_t p_btimer_ctrl_start_get(uint8_t btimer_id)
{
return (btmr_inst[btimer_id]->CONTROL.b[0] & BTIMER_CNTL_START);
}
/** Clears start bit in the control register
* @param btimer_id Basic Timer ID
*/
void p_btimer_ctrl_start_clr(uint8_t btimer_id)
{
btmr_inst[btimer_id]->CONTROL.b[0] &= ~BTIMER_CNTL_START;
}
/** Sets reload bit in the control register
* @param btimer_id Basic Timer ID
*/
void p_btimer_ctrl_reload_set(uint8_t btimer_id)
{
btmr_inst[btimer_id]->CONTROL.b[0] |= BTIMER_CNTL_RELOAD;
}
/** Clears reload bit in the control register
* @param btimer_id Basic Timer ID
*/
void p_btimer_ctrl_reload_clr(uint8_t btimer_id)
{
btmr_inst[btimer_id]->CONTROL.b[0] &= ~BTIMER_CNTL_RELOAD;
}
/** Sets halt bit in the control register
* @param btimer_id Basic Timer ID
*/
void p_btimer_ctrl_halt_set(uint8_t btimer_id)
{
btmr_inst[btimer_id]->CONTROL.b[0] |= BTIMER_CNTL_HALT;
}
/** Clears halt bit in the control register
* @param btimer_id Basic Timer ID
*/
void p_btimer_ctrl_halt_clr(uint8_t btimer_id)
{
btmr_inst[btimer_id]->CONTROL.b[0] &= ~BTIMER_CNTL_HALT;
}
/** Sets prescale value
* @param btimer_id Basic Timer ID
* @param prescaler - 16-bit pre-scale value
*/
void p_btimer_ctrl_prescale_set(uint8_t btimer_id, uint16_t prescaler)
{
btmr_inst[btimer_id]->CONTROL.h[1] = prescaler;
}
/* end btimer_perphl.c */
/** @} //Peripheral Basic_Timer
*/

View File

@ -1,71 +1,70 @@
/*
**********************************************************************************
* © 2013 Microchip Technology Inc. and its subsidiaries.
* You may use this software and any derivatives exclusively with
* Microchip products.
* THIS SOFTWARE IS SUPPLIED BY MICROCHIP "AS IS".
* NO WARRANTIES, WHETHER EXPRESS, IMPLIED OR STATUTORY, APPLY TO THIS SOFTWARE,
* INCLUDING ANY IMPLIED WARRANTIES OF NON-INFRINGEMENT, MERCHANTABILITY,
* AND FITNESS FOR A PARTICULAR PURPOSE, OR ITS INTERACTION WITH MICROCHIP
* PRODUCTS, COMBINATION WITH ANY OTHER PRODUCTS, OR USE IN ANY APPLICATION.
* IN NO EVENT WILL MICROCHIP BE LIABLE FOR ANY INDIRECT, SPECIAL, PUNITIVE,
* INCIDENTAL OR CONSEQUENTIAL LOSS, DAMAGE, COST OR EXPENSE OF ANY KIND
* WHATSOEVER RELATED TO THE SOFTWARE, HOWEVER CAUSED, EVEN IF MICROCHIP HAS
* BEEN ADVISED OF THE POSSIBILITY OR THE DAMAGES ARE FORESEEABLE.
* TO THE FULLEST EXTENT ALLOWED BY LAW, MICROCHIP'S TOTAL LIABILITY ON ALL
* CLAIMS IN ANY WAY RELATED TO THIS SOFTWARE WILL NOT EXCEED THE AMOUNT OF
* FEES, IF ANY, THAT YOU HAVE PAID DIRECTLY TO MICROCHIP FOR THIS SOFTWARE.
* MICROCHIP PROVIDES THIS SOFTWARE CONDITIONALLY UPON YOUR ACCEPTANCE
* OF THESE TERMS.
**********************************************************************************
* common.h
* This is the header file including common headers from various modules
**********************************************************************************
* $Revision: #1 $ $DateTime: 2015/12/23 15:37:58 $ $ $
* Description: added ict module
**********************************************************************************
* #xx
**********************************************************************************
* $File: //depot_pcs/FWEng/Release/projects/CEC1302_CLIB/release2/Source/hw_blks/common/include/common.h $
*/
/*********************************************************************************/
/** @defgroup common common
* @{
*/
/** @file common.h
* \brief header file including common headers from various modules
* \author App Firmware Team
*
**********************************************************************************/
#ifndef _COMMON_H_
#define _COMMON_H_
// Include common headers from various modules
// !!! The include order is important !!!
#include "cfg.h"
#include "platform.h"
#include "MCHP_CEC1302.h"
#include "ARM_REG.h"
/* Cortex-M4 processor and core peripherals */
#include "core_cm4.h"
#include "MEC1322.h"
#include "defs.h"
#include "string.h"
#include "kernel.h"
#include "..\system\system.h"
#include "..\debug\trace.h"
#include "..\interrupt\interrupt.h"
#include "..\timer\timer_app.h"
#include "cec1302_crypto_api.h"
#endif /*_COMMON_H_*/
/** @}
*/
/*
**********************************************************************************
* © 2013 Microchip Technology Inc. and its subsidiaries.
* You may use this software and any derivatives exclusively with
* Microchip products.
* THIS SOFTWARE IS SUPPLIED BY MICROCHIP "AS IS".
* NO WARRANTIES, WHETHER EXPRESS, IMPLIED OR STATUTORY, APPLY TO THIS SOFTWARE,
* INCLUDING ANY IMPLIED WARRANTIES OF NON-INFRINGEMENT, MERCHANTABILITY,
* AND FITNESS FOR A PARTICULAR PURPOSE, OR ITS INTERACTION WITH MICROCHIP
* PRODUCTS, COMBINATION WITH ANY OTHER PRODUCTS, OR USE IN ANY APPLICATION.
* IN NO EVENT WILL MICROCHIP BE LIABLE FOR ANY INDIRECT, SPECIAL, PUNITIVE,
* INCIDENTAL OR CONSEQUENTIAL LOSS, DAMAGE, COST OR EXPENSE OF ANY KIND
* WHATSOEVER RELATED TO THE SOFTWARE, HOWEVER CAUSED, EVEN IF MICROCHIP HAS
* BEEN ADVISED OF THE POSSIBILITY OR THE DAMAGES ARE FORESEEABLE.
* TO THE FULLEST EXTENT ALLOWED BY LAW, MICROCHIP'S TOTAL LIABILITY ON ALL
* CLAIMS IN ANY WAY RELATED TO THIS SOFTWARE WILL NOT EXCEED THE AMOUNT OF
* FEES, IF ANY, THAT YOU HAVE PAID DIRECTLY TO MICROCHIP FOR THIS SOFTWARE.
* MICROCHIP PROVIDES THIS SOFTWARE CONDITIONALLY UPON YOUR ACCEPTANCE
* OF THESE TERMS.
**********************************************************************************
* common.h
* This is the header file including common headers from various modules
**********************************************************************************
* $Revision: #1 $ $DateTime: 2016/04/08 10:18:28 $ $ $
* Description: added ict module
**********************************************************************************
* #xx
**********************************************************************************
* $File: //depot_pcs/FWEng/Release/projects/CEC1302_PLIB_CLIB/release5/Source/hw_blks/common/include/common.h $
*/
/*********************************************************************************/
/** @defgroup common common
* @{
*/
/** @file common.h
* \brief header file including common headers from various modules
* \author App Firmware Team
*
**********************************************************************************/
#ifndef _COMMON_H_
#define _COMMON_H_
// Include common headers from various modules
// !!! The include order is important !!!
#include "cfg.h"
#include "platform.h"
#include "MCHP_CEC1302.h"
#include "ARM_REG.h"
/* Cortex-M4 processor and core peripherals */
#include "core_cm4.h"
#include "defs.h"
#include "string.h"
#include "kernel.h"
#include "..\system\system.h"
#include "..\debug\trace.h"
#include "..\interrupt\irqhandler.h"
#include "..\timer\timer_app.h"
#include "cec1302_crypto_api.h"
#endif /*_COMMON_H_*/
/** @}
*/

View File

@ -1,64 +1,63 @@
/*
**********************************************************************************
* © 2013 Microchip Technology Inc. and its subsidiaries.
* You may use this software and any derivatives exclusively with
* Microchip products.
* THIS SOFTWARE IS SUPPLIED BY MICROCHIP "AS IS".
* NO WARRANTIES, WHETHER EXPRESS, IMPLIED OR STATUTORY, APPLY TO THIS SOFTWARE,
* INCLUDING ANY IMPLIED WARRANTIES OF NON-INFRINGEMENT, MERCHANTABILITY,
* AND FITNESS FOR A PARTICULAR PURPOSE, OR ITS INTERACTION WITH MICROCHIP
* PRODUCTS, COMBINATION WITH ANY OTHER PRODUCTS, OR USE IN ANY APPLICATION.
* IN NO EVENT WILL MICROCHIP BE LIABLE FOR ANY INDIRECT, SPECIAL, PUNITIVE,
* INCIDENTAL OR CONSEQUENTIAL LOSS, DAMAGE, COST OR EXPENSE OF ANY KIND
* WHATSOEVER RELATED TO THE SOFTWARE, HOWEVER CAUSED, EVEN IF MICROCHIP HAS
* BEEN ADVISED OF THE POSSIBILITY OR THE DAMAGES ARE FORESEEABLE.
* TO THE FULLEST EXTENT ALLOWED BY LAW, MICROCHIP'S TOTAL LIABILITY ON ALL
* CLAIMS IN ANY WAY RELATED TO THIS SOFTWARE WILL NOT EXCEED THE AMOUNT OF
* FEES, IF ANY, THAT YOU HAVE PAID DIRECTLY TO MICROCHIP FOR THIS SOFTWARE.
* MICROCHIP PROVIDES THIS SOFTWARE CONDITIONALLY UPON YOUR ACCEPTANCE
* OF THESE TERMS.
**********************************************************************************
* common.h
* This is the header file including common headers from various modules
**********************************************************************************
* $Revision: #1 $ $DateTime: 2015/12/23 15:37:58 $ $ $
* Description: added ict module
**********************************************************************************
* #xx
**********************************************************************************
* $File: //depot_pcs/FWEng/Release/projects/CEC1302_CLIB/release2/Source/hw_blks/common/include/common_lib.h $
*/
/*********************************************************************************/
/** @defgroup common common
* @{
*/
/** @file common.h
* \brief header file including common headers from various modules
* \author App Firmware Team
*
**********************************************************************************/
#ifndef _COMMON_LIB_H_
#define _COMMON_LIB_H_
// Include common headers from various modules
// !!! The include order is important !!!
#include "platform.h"
#include "ARM_REG.h"
#include "MCHP_CEC1302.h"
/* Cortex-M4 processor and core peripherals */
#include "core_cm4.h"
#include "MEC1322.h"
#include "defs.h"
#include "string.h"
//_RB_#include "build.h"
//_RB_#include "..\system\system.h"
//_RB_#include "..\debug\trace.h"
#include <stdbool.h>
#endif /*_COMMON_LIB_H_*/
/** @}
*/
/*
**********************************************************************************
* © 2013 Microchip Technology Inc. and its subsidiaries.
* You may use this software and any derivatives exclusively with
* Microchip products.
* THIS SOFTWARE IS SUPPLIED BY MICROCHIP "AS IS".
* NO WARRANTIES, WHETHER EXPRESS, IMPLIED OR STATUTORY, APPLY TO THIS SOFTWARE,
* INCLUDING ANY IMPLIED WARRANTIES OF NON-INFRINGEMENT, MERCHANTABILITY,
* AND FITNESS FOR A PARTICULAR PURPOSE, OR ITS INTERACTION WITH MICROCHIP
* PRODUCTS, COMBINATION WITH ANY OTHER PRODUCTS, OR USE IN ANY APPLICATION.
* IN NO EVENT WILL MICROCHIP BE LIABLE FOR ANY INDIRECT, SPECIAL, PUNITIVE,
* INCIDENTAL OR CONSEQUENTIAL LOSS, DAMAGE, COST OR EXPENSE OF ANY KIND
* WHATSOEVER RELATED TO THE SOFTWARE, HOWEVER CAUSED, EVEN IF MICROCHIP HAS
* BEEN ADVISED OF THE POSSIBILITY OR THE DAMAGES ARE FORESEEABLE.
* TO THE FULLEST EXTENT ALLOWED BY LAW, MICROCHIP'S TOTAL LIABILITY ON ALL
* CLAIMS IN ANY WAY RELATED TO THIS SOFTWARE WILL NOT EXCEED THE AMOUNT OF
* FEES, IF ANY, THAT YOU HAVE PAID DIRECTLY TO MICROCHIP FOR THIS SOFTWARE.
* MICROCHIP PROVIDES THIS SOFTWARE CONDITIONALLY UPON YOUR ACCEPTANCE
* OF THESE TERMS.
**********************************************************************************
* common.h
* This is the header file including common headers from various modules
**********************************************************************************
* $Revision: #1 $ $DateTime: 2016/04/08 10:18:28 $ $ $
* Description: added ict module
**********************************************************************************
* #xx
**********************************************************************************
* $File: //depot_pcs/FWEng/Release/projects/CEC1302_PLIB_CLIB/release5/Source/hw_blks/common/include/common_lib.h $
*/
/*********************************************************************************/
/** @defgroup common common
* @{
*/
/** @file common.h
* \brief header file including common headers from various modules
* \author App Firmware Team
*
**********************************************************************************/
#ifndef _COMMON_LIB_H_
#define _COMMON_LIB_H_
// Include common headers from various modules
// !!! The include order is important !!!
#include "platform.h"
#include "ARM_REG.h"
#include "MCHP_CEC1302.h"
/* Cortex-M4 processor and core peripherals */
#include "core_cm4.h"
#include "defs.h"
#include "string.h"
//#include "build.h"
//#include "..\system\system.h"
//#include "..\debug\trace.h"
#include <stdbool.h>
#endif /*_COMMON_LIB_H_*/
/** @}
*/

View File

@ -1,54 +1,54 @@
/*
**********************************************************************************
* © 2013 Microchip Technology Inc. and its subsidiaries.
* You may use this software and any derivatives exclusively with
* Microchip products.
* THIS SOFTWARE IS SUPPLIED BY MICROCHIP "AS IS".
* NO WARRANTIES, WHETHER EXPRESS, IMPLIED OR STATUTORY, APPLY TO THIS SOFTWARE,
* INCLUDING ANY IMPLIED WARRANTIES OF NON-INFRINGEMENT, MERCHANTABILITY,
* AND FITNESS FOR A PARTICULAR PURPOSE, OR ITS INTERACTION WITH MICROCHIP
* PRODUCTS, COMBINATION WITH ANY OTHER PRODUCTS, OR USE IN ANY APPLICATION.
* IN NO EVENT WILL MICROCHIP BE LIABLE FOR ANY INDIRECT, SPECIAL, PUNITIVE,
* INCIDENTAL OR CONSEQUENTIAL LOSS, DAMAGE, COST OR EXPENSE OF ANY KIND
* WHATSOEVER RELATED TO THE SOFTWARE, HOWEVER CAUSED, EVEN IF MICROCHIP HAS
* BEEN ADVISED OF THE POSSIBILITY OR THE DAMAGES ARE FORESEEABLE.
* TO THE FULLEST EXTENT ALLOWED BY LAW, MICROCHIP'S TOTAL LIABILITY ON ALL
* CLAIMS IN ANY WAY RELATED TO THIS SOFTWARE WILL NOT EXCEED THE AMOUNT OF
* FEES, IF ANY, THAT YOU HAVE PAID DIRECTLY TO MICROCHIP FOR THIS SOFTWARE.
* MICROCHIP PROVIDES THIS SOFTWARE CONDITIONALLY UPON YOUR ACCEPTANCE
* OF THESE TERMS.
**********************************************************************************
* defs.h
* This is the definition header file for generic usages
**********************************************************************************
* #xx
**********************************************************************************
* $File: //depot_pcs/FWEng/Release/projects/CEC1302_CLIB/release2/Source/hw_blks/common/include/defs.h $
*/
/*********************************************************************************/
/** @defgroup defs defs
* @{
*/
/** @file defs.h
* \brief definition header file for generic usages
* \author App Firmware Team
*
**********************************************************************************/
#ifndef _DEFS_H_
#define _DEFS_H_
/* bit operation MACRO, xvar could be byte, word or dword */
#define mSET_BIT(x, xvar) ( xvar |= x )
#define mCLR_BIT(x, xvar) ( xvar &= ~x )
#define mGET_BIT(x, xvar) ( xvar & x )
#define mCLR_SRC_BIT(x, xvar) ( xvar = x )
#define mTOGGLE_BIT(x, xvar) {if(mGET_BIT(x, xvar)){mCLR_BIT(x, xvar);}else{mSET_BIT(x, xvar);}}
#endif /*_DEFS_H_*/
/** @}
*/
/*
**********************************************************************************
* © 2013 Microchip Technology Inc. and its subsidiaries.
* You may use this software and any derivatives exclusively with
* Microchip products.
* THIS SOFTWARE IS SUPPLIED BY MICROCHIP "AS IS".
* NO WARRANTIES, WHETHER EXPRESS, IMPLIED OR STATUTORY, APPLY TO THIS SOFTWARE,
* INCLUDING ANY IMPLIED WARRANTIES OF NON-INFRINGEMENT, MERCHANTABILITY,
* AND FITNESS FOR A PARTICULAR PURPOSE, OR ITS INTERACTION WITH MICROCHIP
* PRODUCTS, COMBINATION WITH ANY OTHER PRODUCTS, OR USE IN ANY APPLICATION.
* IN NO EVENT WILL MICROCHIP BE LIABLE FOR ANY INDIRECT, SPECIAL, PUNITIVE,
* INCIDENTAL OR CONSEQUENTIAL LOSS, DAMAGE, COST OR EXPENSE OF ANY KIND
* WHATSOEVER RELATED TO THE SOFTWARE, HOWEVER CAUSED, EVEN IF MICROCHIP HAS
* BEEN ADVISED OF THE POSSIBILITY OR THE DAMAGES ARE FORESEEABLE.
* TO THE FULLEST EXTENT ALLOWED BY LAW, MICROCHIP'S TOTAL LIABILITY ON ALL
* CLAIMS IN ANY WAY RELATED TO THIS SOFTWARE WILL NOT EXCEED THE AMOUNT OF
* FEES, IF ANY, THAT YOU HAVE PAID DIRECTLY TO MICROCHIP FOR THIS SOFTWARE.
* MICROCHIP PROVIDES THIS SOFTWARE CONDITIONALLY UPON YOUR ACCEPTANCE
* OF THESE TERMS.
**********************************************************************************
* defs.h
* This is the definition header file for generic usages
**********************************************************************************
* #xx
**********************************************************************************
* $File: //depot_pcs/FWEng/Release/projects/CEC1302_PLIB_CLIB/release5/Source/hw_blks/common/include/defs.h $
*/
/*********************************************************************************/
/** @defgroup defs defs
* @{
*/
/** @file defs.h
* \brief definition header file for generic usages
* \author App Firmware Team
*
**********************************************************************************/
#ifndef _DEFS_H_
#define _DEFS_H_
/* bit operation MACRO, xvar could be byte, word or dword */
#define mSET_BIT(x, xvar) ( xvar |= x )
#define mCLR_BIT(x, xvar) ( xvar &= ~x )
#define mGET_BIT(x, xvar) ( xvar & x )
#define mCLR_SRC_BIT(x, xvar) ( xvar = x )
#define mTOGGLE_BIT(x, xvar) {if(mGET_BIT(x, xvar)){mCLR_BIT(x, xvar);}else{mSET_BIT(x, xvar);}}
#endif /*_DEFS_H_*/
/** @}
*/

View File

@ -1,111 +1,108 @@
/*****************************************************************************
* © 2015 Microchip Technology Inc. and its subsidiaries.
* You may use this software and any derivatives exclusively with
* Microchip products.
* THIS SOFTWARE IS SUPPLIED BY MICROCHIP "AS IS".
* NO WARRANTIES, WHETHER EXPRESS, IMPLIED OR STATUTORY, APPLY TO THIS SOFTWARE,
* INCLUDING ANY IMPLIED WARRANTIES OF NON-INFRINGEMENT, MERCHANTABILITY,
* AND FITNESS FOR A PARTICULAR PURPOSE, OR ITS INTERACTION WITH MICROCHIP
* PRODUCTS, COMBINATION WITH ANY OTHER PRODUCTS, OR USE IN ANY APPLICATION.
* IN NO EVENT WILL MICROCHIP BE LIABLE FOR ANY INDIRECT, SPECIAL, PUNITIVE,
* INCIDENTAL OR CONSEQUENTIAL LOSS, DAMAGE, COST OR EXPENSE OF ANY KIND
* WHATSOEVER RELATED TO THE SOFTWARE, HOWEVER CAUSED, EVEN IF MICROCHIP HAS
* BEEN ADVISED OF THE POSSIBILITY OR THE DAMAGES ARE FORESEEABLE.
* TO THE FULLEST EXTENT ALLOWED BY LAW, MICROCHIP'S TOTAL LIABILITY ON ALL
* CLAIMS IN ANY WAY RELATED TO THIS SOFTWARE WILL NOT EXCEED THE AMOUNT OF
* FEES, IF ANY, THAT YOU HAVE PAID DIRECTLY TO MICROCHIP FOR THIS SOFTWARE.
* MICROCHIP PROVIDES THIS SOFTWARE CONDITIONALLY UPON YOUR ACCEPTANCE
* OF THESE TERMS.
******************************************************************************
Version Control Information (Perforce)
******************************************************************************
$Revision: #1 $
$DateTime: 2015/12/17 01:09:00 $
$Author: snakka $
Last Change: Updated for peripheral functions prefix p_
******************************************************************************/
/** @file btimer.h
* \brief Hibernation Timer Peripheral Header file
* \author jvasanth
*
* This file is the header file for Hibernation Timer Peripheral
******************************************************************************/
/** @defgroup Hibernation_Timer
* @{
*/
#ifndef _HTIMER_H
#define _HTIMER_H
/******************************************************************************/
/** Logical Timer ID for APIs.
* This is the timer IDs passed to Hibernation Timer function calls
*******************************************************************************/
enum _PID_HTIMER_
{
PID_HTIMER_0,
PID_HTIMER_MAX
};
#define HTIMER_MAX_INSTANCE PID_HTIMER_MAX
/* -------------------------------------------------------------------- */
/* Hibernation Timer APIs */
/* -------------------------------------------------------------------- */
/** Enables hibernation timer
* @param htimer_id Hibernation Timer ID
* @param preload_value - 16-bit preload value
* @param resolution_mode 0 - resolution of 30.5us per LSB,
* 1 - resolution of 0.125s per LSB
*/
void htimer_enable(uint8_t htimer_id, uint16_t preload_value, uint8_t resolution_mode);
/** Disables the hibernation timer by programming the prelaod value as 0
* @param htimer_id Hibernation Timer ID
*/
void htimer_disable(uint8_t htimer_id);
/** Reloads new preload value for the hibernation timer
* @param htimer_id Hibernation Timer ID
* @param reload_value - 16-bit preload value
*/
void htimer_reload(uint8_t htimer_id, uint16_t reload_value);
/* -------------------------------------------------------------------- */
/* Hibernation Timer Peripheral Functions */
/* -------------------------------------------------------------------- */
/** Sets hibernation timer preload value
* @param htimer_id Hibernation Timer ID
* @param preload_value - 16-bit preload value
*/
void p_htimer_preload_set(uint8_t htimer_id, uint16_t preload_value);
/*_RB_ Added by RB. */
uint16_t p_htimer_preload_get(uint8_t htimer_id);
/** Sets hibernation timer resolution
* @param htimer_id Hibernation Timer ID
* @param resolution_mode 0 - resolution of 30.5us per LSB,
* 1 - resolution of 0.125s per LSB
*/
void p_htimer_resolution_set(uint8_t htimer_id, uint8_t resolution_mode);
/** Returns the Hibernation Timer current count value
* @param htimer_id Hibernation Timer ID
* @return 16-bit count value
*/
uint16_t p_htimer_count_get(uint8_t htimer_id);
#endif // #ifndef _HTIMER_H
/* end htimer.h */
/** @} //Peripherals Hibernation_Timer
*/
/*****************************************************************************
* © 2015 Microchip Technology Inc. and its subsidiaries.
* You may use this software and any derivatives exclusively with
* Microchip products.
* THIS SOFTWARE IS SUPPLIED BY MICROCHIP "AS IS".
* NO WARRANTIES, WHETHER EXPRESS, IMPLIED OR STATUTORY, APPLY TO THIS SOFTWARE,
* INCLUDING ANY IMPLIED WARRANTIES OF NON-INFRINGEMENT, MERCHANTABILITY,
* AND FITNESS FOR A PARTICULAR PURPOSE, OR ITS INTERACTION WITH MICROCHIP
* PRODUCTS, COMBINATION WITH ANY OTHER PRODUCTS, OR USE IN ANY APPLICATION.
* IN NO EVENT WILL MICROCHIP BE LIABLE FOR ANY INDIRECT, SPECIAL, PUNITIVE,
* INCIDENTAL OR CONSEQUENTIAL LOSS, DAMAGE, COST OR EXPENSE OF ANY KIND
* WHATSOEVER RELATED TO THE SOFTWARE, HOWEVER CAUSED, EVEN IF MICROCHIP HAS
* BEEN ADVISED OF THE POSSIBILITY OR THE DAMAGES ARE FORESEEABLE.
* TO THE FULLEST EXTENT ALLOWED BY LAW, MICROCHIP'S TOTAL LIABILITY ON ALL
* CLAIMS IN ANY WAY RELATED TO THIS SOFTWARE WILL NOT EXCEED THE AMOUNT OF
* FEES, IF ANY, THAT YOU HAVE PAID DIRECTLY TO MICROCHIP FOR THIS SOFTWARE.
* MICROCHIP PROVIDES THIS SOFTWARE CONDITIONALLY UPON YOUR ACCEPTANCE
* OF THESE TERMS.
******************************************************************************
Version Control Information (Perforce)
******************************************************************************
$Revision: #1 $
$DateTime: 2016/04/08 10:18:28 $
$Author: pramans $
Last Change: Updated for peripheral functions prefix p_
******************************************************************************/
/** @file btimer.h
* \brief Hibernation Timer Peripheral Header file
* \author jvasanth
*
* This file is the header file for Hibernation Timer Peripheral
******************************************************************************/
/** @defgroup Hibernation_Timer
* @{
*/
#ifndef _HTIMER_H
#define _HTIMER_H
/******************************************************************************/
/** Logical Timer ID for APIs.
* This is the timer IDs passed to Hibernation Timer function calls
*******************************************************************************/
enum _PID_HTIMER_
{
PID_HTIMER_0,
PID_HTIMER_MAX
};
#define HTIMER_MAX_INSTANCE PID_HTIMER_MAX
/* -------------------------------------------------------------------- */
/* Hibernation Timer APIs */
/* -------------------------------------------------------------------- */
/** Enables hibernation timer
* @param htimer_id Hibernation Timer ID
* @param preload_value - 16-bit preload value
* @param resolution_mode 0 - resolution of 30.5us per LSB,
* 1 - resolution of 0.125s per LSB
*/
void htimer_enable(uint8_t htimer_id, uint16_t preload_value, uint8_t resolution_mode);
/** Disables the hibernation timer by programming the prelaod value as 0
* @param htimer_id Hibernation Timer ID
*/
void htimer_disable(uint8_t htimer_id);
/** Reloads new preload value for the hibernation timer
* @param htimer_id Hibernation Timer ID
* @param reload_value - 16-bit preload value
*/
void htimer_reload(uint8_t htimer_id, uint16_t reload_value);
/* -------------------------------------------------------------------- */
/* Hibernation Timer Peripheral Functions */
/* -------------------------------------------------------------------- */
/** Sets hibernation timer preload value
* @param htimer_id Hibernation Timer ID
* @param preload_value - 16-bit preload value
*/
void p_htimer_preload_set(uint8_t htimer_id, uint16_t preload_value);
/** Sets hibernation timer resolution
* @param htimer_id Hibernation Timer ID
* @param resolution_mode 0 - resolution of 30.5us per LSB,
* 1 - resolution of 0.125s per LSB
*/
void p_htimer_resolution_set(uint8_t htimer_id, uint8_t resolution_mode);
/** Returns the Hibernation Timer current count value
* @param htimer_id Hibernation Timer ID
* @return 16-bit count value
*/
uint16_t p_htimer_count_get(uint8_t htimer_id);
#endif // #ifndef _HTIMER_H
/* end htimer.h */
/** @} //Peripherals Hibernation_Timer
*/

View File

@ -1,112 +1,112 @@
/*****************************************************************************
* © 2015 Microchip Technology Inc. and its subsidiaries.
* You may use this software and any derivatives exclusively with
* Microchip products.
* THIS SOFTWARE IS SUPPLIED BY MICROCHIP "AS IS".
* NO WARRANTIES, WHETHER EXPRESS, IMPLIED OR STATUTORY, APPLY TO THIS SOFTWARE,
* INCLUDING ANY IMPLIED WARRANTIES OF NON-INFRINGEMENT, MERCHANTABILITY,
* AND FITNESS FOR A PARTICULAR PURPOSE, OR ITS INTERACTION WITH MICROCHIP
* PRODUCTS, COMBINATION WITH ANY OTHER PRODUCTS, OR USE IN ANY APPLICATION.
* IN NO EVENT WILL MICROCHIP BE LIABLE FOR ANY INDIRECT, SPECIAL, PUNITIVE,
* INCIDENTAL OR CONSEQUENTIAL LOSS, DAMAGE, COST OR EXPENSE OF ANY KIND
* WHATSOEVER RELATED TO THE SOFTWARE, HOWEVER CAUSED, EVEN IF MICROCHIP HAS
* BEEN ADVISED OF THE POSSIBILITY OR THE DAMAGES ARE FORESEEABLE.
* TO THE FULLEST EXTENT ALLOWED BY LAW, MICROCHIP'S TOTAL LIABILITY ON ALL
* CLAIMS IN ANY WAY RELATED TO THIS SOFTWARE WILL NOT EXCEED THE AMOUNT OF
* FEES, IF ANY, THAT YOU HAVE PAID DIRECTLY TO MICROCHIP FOR THIS SOFTWARE.
* MICROCHIP PROVIDES THIS SOFTWARE CONDITIONALLY UPON YOUR ACCEPTANCE
* OF THESE TERMS.
******************************************************************************
Version Control Information (Perforce)
******************************************************************************
$Revision: #1 $
$DateTime: 2015/12/17 01:09:00 $
$Author: snakka $
Last Change: Updated for peripheral functions prefix p_
******************************************************************************/
/** @file btimer_perphl.c
* \brief Hibernation Timer API Source file
* \author jvasanth
*
* This file implements Hibernation Timer APIs
******************************************************************************/
/** @defgroup Hibernation_Timer
* @{
*/
#include "common_lib.h"
#include "htimer.h"
#ifdef PLIB_HTIMER_CHECK_ID
/** Local helper that checks if logical Timer ID is valid.
* @param htimer_id Hibernation Timer ID
* @return uint8_t Non-zero(VALID), 0(Invalid)
*/
static uint8_t htmr_valid(uint8_t htimer_id)
{
if ( htimer_id < (PID_HTIMER_MAX ) ) {
return 1;
}
return 0;
}
#else
/** This version of tmr_valid skips checking always returning 1.
* Compiler may optimize it out.
* @param htimer_id Hibernation Timer ID
* @return uint8_t 1(VALID)
*/
static uint8_t htmr_valid(uint8_t htimer_id) { return 1; }
#endif
/** Enables hibernation timer
* @param htimer_id Hibernation Timer ID
* @param preload_value - 16-bit preload value
* @param resolution_mode 0 - resolution of 30.5us per LSB,
* 1 - resolution of 0.125s per LSB
*/
void htimer_enable(uint8_t htimer_id, uint16_t preload_value, uint8_t resolution_mode)
{
if (htmr_valid(htimer_id))
{
p_htimer_preload_set(htimer_id, preload_value);
p_htimer_resolution_set(htimer_id, resolution_mode);
}
}
/** Disables the hibernation timer by programming the prelaod value as 0
* @param htimer_id Hibernation Timer ID
*/
void htimer_disable(uint8_t htimer_id)
{
if (htmr_valid(htimer_id))
{
p_htimer_preload_set(htimer_id, 0);
}
}
/** Reloads new preload value for the hibernation timer
* @param htimer_id Hibernation Timer ID
* @param reload_value - 16-bit preload value
*/
void htimer_reload(uint8_t htimer_id, uint16_t reload_value)
{
if ( htmr_valid(htimer_id))
{
p_htimer_preload_set(htimer_id, reload_value);
}
}
/* end htimer_api.c */
/** @} //APIs Hibernation_Timer
*/
/*****************************************************************************
* © 2015 Microchip Technology Inc. and its subsidiaries.
* You may use this software and any derivatives exclusively with
* Microchip products.
* THIS SOFTWARE IS SUPPLIED BY MICROCHIP "AS IS".
* NO WARRANTIES, WHETHER EXPRESS, IMPLIED OR STATUTORY, APPLY TO THIS SOFTWARE,
* INCLUDING ANY IMPLIED WARRANTIES OF NON-INFRINGEMENT, MERCHANTABILITY,
* AND FITNESS FOR A PARTICULAR PURPOSE, OR ITS INTERACTION WITH MICROCHIP
* PRODUCTS, COMBINATION WITH ANY OTHER PRODUCTS, OR USE IN ANY APPLICATION.
* IN NO EVENT WILL MICROCHIP BE LIABLE FOR ANY INDIRECT, SPECIAL, PUNITIVE,
* INCIDENTAL OR CONSEQUENTIAL LOSS, DAMAGE, COST OR EXPENSE OF ANY KIND
* WHATSOEVER RELATED TO THE SOFTWARE, HOWEVER CAUSED, EVEN IF MICROCHIP HAS
* BEEN ADVISED OF THE POSSIBILITY OR THE DAMAGES ARE FORESEEABLE.
* TO THE FULLEST EXTENT ALLOWED BY LAW, MICROCHIP'S TOTAL LIABILITY ON ALL
* CLAIMS IN ANY WAY RELATED TO THIS SOFTWARE WILL NOT EXCEED THE AMOUNT OF
* FEES, IF ANY, THAT YOU HAVE PAID DIRECTLY TO MICROCHIP FOR THIS SOFTWARE.
* MICROCHIP PROVIDES THIS SOFTWARE CONDITIONALLY UPON YOUR ACCEPTANCE
* OF THESE TERMS.
******************************************************************************
Version Control Information (Perforce)
******************************************************************************
$Revision: #1 $
$DateTime: 2016/04/08 10:18:28 $
$Author: pramans $
Last Change: Updated for peripheral functions prefix p_
******************************************************************************/
/** @file btimer_perphl.c
* \brief Hibernation Timer API Source file
* \author jvasanth
*
* This file implements Hibernation Timer APIs
******************************************************************************/
/** @defgroup Hibernation_Timer
* @{
*/
#include "common_lib.h"
#include "htimer.h"
#ifdef PLIB_HTIMER_CHECK_ID
/** Local helper that checks if logical Timer ID is valid.
* @param htimer_id Hibernation Timer ID
* @return uint8_t Non-zero(VALID), 0(Invalid)
*/
static uint8_t htmr_valid(uint8_t htimer_id)
{
if ( htimer_id < (PID_HTIMER_MAX ) ) {
return 1;
}
return 0;
}
#else
/** This version of tmr_valid skips checking always returning 1.
* Compiler may optimize it out.
* @param htimer_id Hibernation Timer ID
* @return uint8_t 1(VALID)
*/
static uint8_t htmr_valid(uint8_t htimer_id) { return 1; }
#endif
/** Enables hibernation timer
* @param htimer_id Hibernation Timer ID
* @param preload_value - 16-bit preload value
* @param resolution_mode 0 - resolution of 30.5us per LSB,
* 1 - resolution of 0.125s per LSB
*/
void htimer_enable(uint8_t htimer_id, uint16_t preload_value, uint8_t resolution_mode)
{
if (htmr_valid(htimer_id))
{
p_htimer_preload_set(htimer_id, preload_value);
p_htimer_resolution_set(htimer_id, resolution_mode);
}
}
/** Disables the hibernation timer by programming the prelaod value as 0
* @param htimer_id Hibernation Timer ID
*/
void htimer_disable(uint8_t htimer_id)
{
if (htmr_valid(htimer_id))
{
p_htimer_preload_set(htimer_id, 0);
}
}
/** Reloads new preload value for the hibernation timer
* @param htimer_id Hibernation Timer ID
* @param reload_value - 16-bit preload value
*/
void htimer_reload(uint8_t htimer_id, uint16_t reload_value)
{
if ( htmr_valid(htimer_id))
{
p_htimer_preload_set(htimer_id, reload_value);
}
}
/* end htimer_api.c */
/** @} //APIs Hibernation_Timer
*/

View File

@ -1,93 +1,87 @@
/*****************************************************************************
* © 2015 Microchip Technology Inc. and its subsidiaries.
* You may use this software and any derivatives exclusively with
* Microchip products.
* THIS SOFTWARE IS SUPPLIED BY MICROCHIP "AS IS".
* NO WARRANTIES, WHETHER EXPRESS, IMPLIED OR STATUTORY, APPLY TO THIS SOFTWARE,
* INCLUDING ANY IMPLIED WARRANTIES OF NON-INFRINGEMENT, MERCHANTABILITY,
* AND FITNESS FOR A PARTICULAR PURPOSE, OR ITS INTERACTION WITH MICROCHIP
* PRODUCTS, COMBINATION WITH ANY OTHER PRODUCTS, OR USE IN ANY APPLICATION.
* IN NO EVENT WILL MICROCHIP BE LIABLE FOR ANY INDIRECT, SPECIAL, PUNITIVE,
* INCIDENTAL OR CONSEQUENTIAL LOSS, DAMAGE, COST OR EXPENSE OF ANY KIND
* WHATSOEVER RELATED TO THE SOFTWARE, HOWEVER CAUSED, EVEN IF MICROCHIP HAS
* BEEN ADVISED OF THE POSSIBILITY OR THE DAMAGES ARE FORESEEABLE.
* TO THE FULLEST EXTENT ALLOWED BY LAW, MICROCHIP'S TOTAL LIABILITY ON ALL
* CLAIMS IN ANY WAY RELATED TO THIS SOFTWARE WILL NOT EXCEED THE AMOUNT OF
* FEES, IF ANY, THAT YOU HAVE PAID DIRECTLY TO MICROCHIP FOR THIS SOFTWARE.
* MICROCHIP PROVIDES THIS SOFTWARE CONDITIONALLY UPON YOUR ACCEPTANCE
* OF THESE TERMS.
******************************************************************************
Version Control Information (Perforce)
******************************************************************************
$Revision: #1 $
$DateTime: 2015/12/17 01:09:00 $
$Author: snakka $
Last Change: Updated for peripheral functions prefix p_
******************************************************************************/
/** @file btimer_perphl.c
* \brief Hibernation Timer Peripheral Source file
* \author jvasanth
*
* This file implements Hibernation Timer Peripheral functions
******************************************************************************/
/** @defgroup Hibernation_Timer
* @{
*/
#include "common_lib.h"
#include "htimer.h"
/** Hibernation Timer Instance base addresses */
static HTM_Type * const htmr_inst[HTIMER_MAX_INSTANCE] = {
CEC1302_HTM
};
/** Sets hibernation timer preload value
* @param htimer_id Hibernation Timer ID
* @param preload_value - 16-bit preload value
* @note Setting the preload with a non-zero value starts
* the hibernation timer to down count. Setting the preload
* to 0 disables the hibernation counter
*/
void p_htimer_preload_set(uint8_t htimer_id, uint16_t preload_value)
{
htmr_inst[htimer_id]->PRELOAD = preload_value;
}
/** Sets hibernation timer resolution
* @param htimer_id Hibernation Timer ID
* @param resolution_mode 0 - resolution of 30.5us per LSB,
* 1 - resolution of 0.125s per LSB
*/
void p_htimer_resolution_set(uint8_t htimer_id, uint8_t resolution_mode)
{
htmr_inst[htimer_id]->CONTROL = resolution_mode;
}
/** Returns the Hibernation Timer current count value
* @param htimer_id Hibernation Timer ID
* @return 16-bit count value
*/
uint16_t p_htimer_count_get(uint8_t htimer_id)
{
uint16_t htimer_count;
htimer_count = htmr_inst[htimer_id]->COUNT;
return htimer_count;
}
/*_RB_ Added by RB. */
uint16_t p_htimer_preload_get(uint8_t htimer_id)
{
return htmr_inst[htimer_id]->PRELOAD;
}
/* end htimer_perphl.c */
/** @} //Peripheral Hibernation_Timer
*/
/*****************************************************************************
* © 2015 Microchip Technology Inc. and its subsidiaries.
* You may use this software and any derivatives exclusively with
* Microchip products.
* THIS SOFTWARE IS SUPPLIED BY MICROCHIP "AS IS".
* NO WARRANTIES, WHETHER EXPRESS, IMPLIED OR STATUTORY, APPLY TO THIS SOFTWARE,
* INCLUDING ANY IMPLIED WARRANTIES OF NON-INFRINGEMENT, MERCHANTABILITY,
* AND FITNESS FOR A PARTICULAR PURPOSE, OR ITS INTERACTION WITH MICROCHIP
* PRODUCTS, COMBINATION WITH ANY OTHER PRODUCTS, OR USE IN ANY APPLICATION.
* IN NO EVENT WILL MICROCHIP BE LIABLE FOR ANY INDIRECT, SPECIAL, PUNITIVE,
* INCIDENTAL OR CONSEQUENTIAL LOSS, DAMAGE, COST OR EXPENSE OF ANY KIND
* WHATSOEVER RELATED TO THE SOFTWARE, HOWEVER CAUSED, EVEN IF MICROCHIP HAS
* BEEN ADVISED OF THE POSSIBILITY OR THE DAMAGES ARE FORESEEABLE.
* TO THE FULLEST EXTENT ALLOWED BY LAW, MICROCHIP'S TOTAL LIABILITY ON ALL
* CLAIMS IN ANY WAY RELATED TO THIS SOFTWARE WILL NOT EXCEED THE AMOUNT OF
* FEES, IF ANY, THAT YOU HAVE PAID DIRECTLY TO MICROCHIP FOR THIS SOFTWARE.
* MICROCHIP PROVIDES THIS SOFTWARE CONDITIONALLY UPON YOUR ACCEPTANCE
* OF THESE TERMS.
******************************************************************************
Version Control Information (Perforce)
******************************************************************************
$Revision: #1 $
$DateTime: 2016/04/08 10:18:28 $
$Author: pramans $
Last Change: Updated for peripheral functions prefix p_
******************************************************************************/
/** @file btimer_perphl.c
* \brief Hibernation Timer Peripheral Source file
* \author jvasanth
*
* This file implements Hibernation Timer Peripheral functions
******************************************************************************/
/** @defgroup Hibernation_Timer
* @{
*/
#include "common_lib.h"
#include "htimer.h"
/** Hibernation Timer Instance base addresses */
static HTM_Type * const htmr_inst[HTIMER_MAX_INSTANCE] = {
CEC1302_HTM
};
/** Sets hibernation timer preload value
* @param htimer_id Hibernation Timer ID
* @param preload_value - 16-bit preload value
* @note Setting the preload with a non-zero value starts
* the hibernation timer to down count. Setting the preload
* to 0 disables the hibernation counter
*/
void p_htimer_preload_set(uint8_t htimer_id, uint16_t preload_value)
{
htmr_inst[htimer_id]->PRELOAD = preload_value;
}
/** Sets hibernation timer resolution
* @param htimer_id Hibernation Timer ID
* @param resolution_mode 0 - resolution of 30.5us per LSB,
* 1 - resolution of 0.125s per LSB
*/
void p_htimer_resolution_set(uint8_t htimer_id, uint8_t resolution_mode)
{
htmr_inst[htimer_id]->CONTROL = resolution_mode;
}
/** Returns the Hibernation Timer current count value
* @param htimer_id Hibernation Timer ID
* @return 16-bit count value
*/
uint16_t p_htimer_count_get(uint8_t htimer_id)
{
uint16_t htimer_count;
htimer_count = htmr_inst[htimer_id]->COUNT;
return htimer_count;
}
/* end htimer_perphl.c */
/** @} //Peripheral Hibernation_Timer
*/

View File

@ -1,462 +1,462 @@
/*****************************************************************************
* © 2015 Microchip Technology Inc. and its subsidiaries.
* You may use this software and any derivatives exclusively with
* Microchip products.
* THIS SOFTWARE IS SUPPLIED BY MICROCHIP "AS IS".
* NO WARRANTIES, WHETHER EXPRESS, IMPLIED OR STATUTORY, APPLY TO THIS SOFTWARE,
* INCLUDING ANY IMPLIED WARRANTIES OF NON-INFRINGEMENT, MERCHANTABILITY,
* AND FITNESS FOR A PARTICULAR PURPOSE, OR ITS INTERACTION WITH MICROCHIP
* PRODUCTS, COMBINATION WITH ANY OTHER PRODUCTS, OR USE IN ANY APPLICATION.
* IN NO EVENT WILL MICROCHIP BE LIABLE FOR ANY INDIRECT, SPECIAL, PUNITIVE,
* INCIDENTAL OR CONSEQUENTIAL LOSS, DAMAGE, COST OR EXPENSE OF ANY KIND
* WHATSOEVER RELATED TO THE SOFTWARE, HOWEVER CAUSED, EVEN IF MICROCHIP HAS
* BEEN ADVISED OF THE POSSIBILITY OR THE DAMAGES ARE FORESEEABLE.
* TO THE FULLEST EXTENT ALLOWED BY LAW, MICROCHIP'S TOTAL LIABILITY ON ALL
* CLAIMS IN ANY WAY RELATED TO THIS SOFTWARE WILL NOT EXCEED THE AMOUNT OF
* FEES, IF ANY, THAT YOU HAVE PAID DIRECTLY TO MICROCHIP FOR THIS SOFTWARE.
* MICROCHIP PROVIDES THIS SOFTWARE CONDITIONALLY UPON YOUR ACCEPTANCE
* OF THESE TERMS.
******************************************************************************
Version Control Information (Perforce)
******************************************************************************
$Revision: #1 $
$DateTime: 2015/11/24 06:28:28 $
$Author: amohandas $
Last Change: Updated for tabs
******************************************************************************/
/** @file pcr.h
* \brief Power, Clocks, and Resets Header file
* \author jvasanth
*
* This file is the PCR header file
******************************************************************************/
/** @defgroup PCR
* @{
*/
#ifndef _PCR_H
#define _PCR_H
/******************************************************************************/
/** PCR Register IDS
*******************************************************************************/
enum _PCR_REGSET_ID_
{
PCR_REG_CHIP_SLEEP_ENABLE =0,
PCR_REG_CHIP_CLK_REQD_STS,
PCR_REG_EC_SLEEP_ENABLE,
PCR_REG_EC_CLK_REQD_STS,
PCR_REG_HOST_SLEEP_ENABLE,
PCR_REG_HOST_CLK_REQD_STS,
PCR_REG_SYSTEM_SLEEP_CTRL,
PCR_REG_PROCESSOR_CLK_CTRL = 8,
PCR_REG_EC_SLEEP_ENABLE_2,
PCR_REG_EC_CLK_REQD_STS_2,
PCR_REG_SLOW_CLK_CTRL,
PCR_REG_OSCILLATOR_ID,
PCR_REG_CHIP_SUBSYSTEM_PWR_RESET_STS,
PCR_REG_CHIP_RESET_ENABLE,
PCR_REG_HOST_RESET_ENABLE,
PCR_REG_EC_RESET_ENABLE,
PCR_REG_EC_RESET_ENABLE_2,
PCR_REG_PWR_RESET_CTRL
};
/* ---------------------------------------------------------------------- */
// Encode the Register ids for Sleep Enable, Clock Required, Reset Enable
//PCR register group 0 - CHIP
#define PCR0_REGS_CHIP (((uint32_t)(PCR_REG_CHIP_SLEEP_ENABLE) & 0xFF) + \
(((uint32_t)(PCR_REG_CHIP_CLK_REQD_STS) & 0xFF)<<8u) + \
(((uint32_t)(PCR_REG_CHIP_RESET_ENABLE) & 0xFF)<<16u))
//PCR register group 1 - EC
#define PCR1_REGS_EC (((uint32_t)(PCR_REG_EC_SLEEP_ENABLE) & 0xFF) + \
(((uint32_t)(PCR_REG_EC_CLK_REQD_STS) & 0xFF)<<8u) + \
(((uint32_t)(PCR_REG_EC_RESET_ENABLE) & 0xFF)<<16u))
//PCR register group 2 - HOST
#define PCR2_REGS_HOST (((uint32_t)(PCR_REG_EC_SLEEP_ENABLE) & 0xFF) + \
(((uint32_t)(PCR_REG_EC_CLK_REQD_STS) & 0xFF)<<8u) + \
(((uint32_t)(PCR_REG_EC_RESET_ENABLE) & 0xFF)<<16u))
//PCR register group 3 - EC 2
#define PCR3_REGS_EC2 (((uint32_t)(PCR_REG_EC_SLEEP_ENABLE_2) & 0xFF) + \
(((uint32_t)(PCR_REG_EC_CLK_REQD_STS_2) & 0xFF)<<8u) + \
(((uint32_t)(PCR_REG_EC_RESET_ENABLE_2) & 0xFF)<<16u))
//PCR1_EC -> SLEEP_ENABLE, CLK REQD STS, RESET_ENABLE Bit Positions
#define PCR1_EC_INT_BITPOS (0u)
#define PCR1_EC_PECI_BITPOS (1u)
#define PCR1_EC_TACH0_BITPOS (2u)
#define PCR1_EC_PWM0_BITPOS (4u)
#define PCR1_EC_PMC_BITPOS (5u)
#define PCR1_EC_DMA_BITPOS (6u)
#define PCR1_EC_TFDP_BITPOS (7u)
#define PCR1_EC_CPU_BITPOS (8u)
#define PCR1_EC_WDT_BITPOS (9u)
#define PCR1_EC_SMB0_BITPOS (10u)
#define PCR1_EC_TACH1_BITPOS (11u)
#define PCR1_EC_PWM1_BITPOS (20u)
#define PCR1_EC_PWM2_BITPOS (21u)
#define PCR1_EC_PWM3_BITPOS (22u)
#define PCR1_EC_REG_BITPOS (29u)
#define PCR1_EC_BTIMER0_BITPOS (30u)
#define PCR1_EC_BTIMER1_BITPOS (31u)
//PCR2_HOST -> SLEEP_ENABLE, CLK REQD STS, RESET_ENABLE Bit Positions
#define PCR2_HOST_LPC_BITPOS (0u)
#define PCR2_HOST_UART0_BITPOS (1u)
#define PCR2_HOST_GLBL_CFG_BITPOS (12u)
#define PCR2_HOST_ACPI_EC0_BITPOS (13u)
#define PCR2_HOST_ACPI_EC1_BITPOS (14u)
#define PCR2_HOST_ACPI_PM1_BITPOS (15u)
#define PCR2_HOST_8042EM_BITPOS (16u)
#define PCR2_HOST_RTC_BITPOS (18u)
//PCR3_EC2 -> SLEEP_ENABLE, CLK REQD STS, RESET_ENABLE Bit Positions
#define PCR3_EC2_ADC_BITPOS (3u)
#define PCR3_EC2_PS2_0_BITPOS (5u)
#define PCR3_EC2_PS2_1_BITPOS (6u)
#define PCR3_EC2_PS2_2_BITPOS (7u)
#define PCR3_EC2_PS2_3_BITPOS (8u)
#define PCR3_EC2_SPI0_BITPOS (9u)
#define PCR3_EC2_HTIMER_BITPOS (10u)
#define PCR3_EC2_KEYSCAN_BITPOS (11u)
#define PCR3_EC2_RPM_PWM_BITPOS (12u)
#define PCR3_EC2_SMB1_BITPOS (13u)
#define PCR3_EC2_SMB2_BITPOS (14u)
#define PCR3_EC2_SMB3_BITPOS (15u)
#define PCR3_EC2_LED0_BITPOS (16u)
#define PCR3_EC2_LED1_BITPOS (17u)
#define PCR3_EC2_LED2_BITPOS (18u)
#define PCR3_EC2_BCM_BITPOS (19u)
#define PCR3_EC2_SPI1_BITPOS (20u)
#define PCR3_EC2_BTIMER2_BITPOS (21u)
#define PCR3_EC2_BTIMER3_BITPOS (22u)
#define PCR3_EC2_BTIMER4_BITPOS (23u)
#define PCR3_EC2_BTIMER5_BITPOS (24u)
#define PCR3_EC2_LED3_BITPOS (25u)
/*
* n = b[7:0] = PCR Reg Bit Position
* m = b[31:8] = PCRx Regs IDs
*/
//#define PCRx_REGS_BIT(m,n) ((((uint32_t)(m)&0xFFFFFFul)<<8u) + ((uint32_t)(n)&0xFFul))
//PCRx_REGS_BIT positions
#define PCRx_REGS_POS_SLEEP_ENABLE (8u)
#define PCRx_REGS_POS_CLK_REQD_STS (16u)
#define PCRx_REGS_POS_RESET_ENABLE (24u)
/******************************************************************************/
/** PCR Block IDS.
* These IDs are used to directly refer to a block
*******************************************************************************/
typedef enum {
PCR_INT = (((uint32_t)(PCR1_REGS_EC) << 8) + (uint32_t)(PCR1_EC_INT_BITPOS & 0xFFu)),
PCR_PECI = (((uint32_t)(PCR1_REGS_EC) << 8) + (uint32_t)(PCR1_EC_PECI_BITPOS & 0xFFu)),
PCR_TACH0 = (((uint32_t)(PCR1_REGS_EC) << 8) + (uint32_t)(PCR1_EC_TACH0_BITPOS & 0xFFu)),
PCR_PWM0 = (((uint32_t)(PCR1_REGS_EC) << 8) + (uint32_t)(PCR1_EC_PWM0_BITPOS & 0xFFu)),
PCR_PMC = (((uint32_t)(PCR1_REGS_EC) << 8) + (uint32_t)(PCR1_EC_PMC_BITPOS & 0xFFu)),
PCR_DMA = (((uint32_t)(PCR1_REGS_EC) << 8) + (uint32_t)(PCR1_EC_DMA_BITPOS & 0xFFu)),
PCR_TFDP = (((uint32_t)(PCR1_REGS_EC) << 8) + (uint32_t)(PCR1_EC_TFDP_BITPOS & 0xFFu)),
PCR_CPU = (((uint32_t)(PCR1_REGS_EC) << 8) + (uint32_t)(PCR1_EC_CPU_BITPOS & 0xFFu)),
PCR_WDT = (((uint32_t)(PCR1_REGS_EC) << 8) + (uint32_t)(PCR1_EC_WDT_BITPOS & 0xFFu)),
PCR_SMB0 = (((uint32_t)(PCR1_REGS_EC) << 8) + (uint32_t)(PCR1_EC_SMB0_BITPOS & 0xFFu)),
PCR_TACH1 = (((uint32_t)(PCR1_REGS_EC) << 8) + (uint32_t)(PCR1_EC_TACH1_BITPOS & 0xFFu)),
PCR_PWM1 = (((uint32_t)(PCR1_REGS_EC) << 8) + (uint32_t)(PCR1_EC_PWM1_BITPOS & 0xFFu)),
PCR_PWM2 = (((uint32_t)(PCR1_REGS_EC) << 8) + (uint32_t)(PCR1_EC_PWM2_BITPOS & 0xFFu)),
PCR_PWM3 = (((uint32_t)(PCR1_REGS_EC) << 8) + (uint32_t)(PCR1_EC_PWM3_BITPOS & 0xFFu)),
PCR_REG = (((uint32_t)(PCR1_REGS_EC) << 8) + (uint32_t)(PCR1_EC_REG_BITPOS & 0xFFu)),
PCR_BTIMER0 = (((uint32_t)(PCR1_REGS_EC) << 8) + (uint32_t)(PCR1_EC_BTIMER0_BITPOS & 0xFFu)),
PCR_BTIMER1 = (((uint32_t)(PCR1_REGS_EC) << 8) + (uint32_t)(PCR1_EC_BTIMER1_BITPOS & 0xFFu)),
PCR_LPC = (((uint32_t)(PCR2_REGS_HOST) << 8) + (uint32_t)(PCR2_HOST_LPC_BITPOS & 0xFFu)),
PCR_UART0 = (((uint32_t)(PCR2_REGS_HOST) << 8) + (uint32_t)(PCR2_HOST_UART0_BITPOS & 0xFFu)),
PCR_GLBL_CFG = (((uint32_t)(PCR2_REGS_HOST) << 8) + (uint32_t)(PCR2_HOST_GLBL_CFG_BITPOS & 0xFFu)),
PCR_ACPI_EC0 = (((uint32_t)(PCR2_REGS_HOST) << 8) + (uint32_t)(PCR2_HOST_ACPI_EC0_BITPOS & 0xFFu)),
PCR_ACPI_EC1 = (((uint32_t)(PCR2_REGS_HOST) << 8) + (uint32_t)(PCR2_HOST_ACPI_EC1_BITPOS & 0xFFu)),
PCR_ACPI_PM1 = (((uint32_t)(PCR2_REGS_HOST) << 8) + (uint32_t)(PCR2_HOST_ACPI_PM1_BITPOS & 0xFFu)),
PCR_8042EM = (((uint32_t)(PCR2_REGS_HOST) << 8) + (uint32_t)(PCR2_HOST_8042EM_BITPOS & 0xFFu)),
PCR_RTC = (((uint32_t)(PCR2_REGS_HOST) << 8) + (uint32_t)(PCR2_HOST_RTC_BITPOS & 0xFFu)),
PCR_ADC = (((uint32_t)(PCR3_REGS_EC2) << 8) + (uint32_t)(PCR3_EC2_ADC_BITPOS & 0xFFu)),
PCR_PS2_0 = (((uint32_t)(PCR3_REGS_EC2) << 8) + (uint32_t)(PCR3_EC2_PS2_0_BITPOS & 0xFFu)),
PCR_PS2_1 = (((uint32_t)(PCR3_REGS_EC2) << 8) + (uint32_t)(PCR3_EC2_PS2_1_BITPOS & 0xFFu)),
PCR_PS2_2 = (((uint32_t)(PCR3_REGS_EC2) << 8) + (uint32_t)(PCR3_EC2_PS2_2_BITPOS & 0xFFu)),
PCR_PS2_3 = (((uint32_t)(PCR3_REGS_EC2) << 8) + (uint32_t)(PCR3_EC2_PS2_3_BITPOS & 0xFFu)),
PCR_SPI0 = (((uint32_t)(PCR3_REGS_EC2) << 8) + (uint32_t)(PCR3_EC2_SPI0_BITPOS & 0xFFu)),
PCR_HTIMER = (((uint32_t)(PCR3_REGS_EC2) << 8) + (uint32_t)(PCR3_EC2_HTIMER_BITPOS & 0xFFu)),
PCR_KEYSCAN = (((uint32_t)(PCR3_REGS_EC2) << 8) + (uint32_t)(PCR3_EC2_KEYSCAN_BITPOS & 0xFFu)),
PCR_RPM_PWM = (((uint32_t)(PCR3_REGS_EC2) << 8) + (uint32_t)(PCR3_EC2_RPM_PWM_BITPOS & 0xFFu)),
PCR_SMB1 = (((uint32_t)(PCR3_REGS_EC2) << 8) + (uint32_t)(PCR3_EC2_SMB1_BITPOS & 0xFFu)),
PCR_SMB2 = (((uint32_t)(PCR3_REGS_EC2) << 8) + (uint32_t)(PCR3_EC2_SMB2_BITPOS & 0xFFu)),
PCR_SMB3 = (((uint32_t)(PCR3_REGS_EC2) << 8) + (uint32_t)(PCR3_EC2_SMB3_BITPOS & 0xFFu)),
PCR_LED0 = (((uint32_t)(PCR3_REGS_EC2) << 8) + (uint32_t)(PCR3_EC2_LED0_BITPOS & 0xFFu)),
PCR_LED1 = (((uint32_t)(PCR3_REGS_EC2) << 8) + (uint32_t)(PCR3_EC2_LED1_BITPOS & 0xFFu)),
PCR_LED2 = (((uint32_t)(PCR3_REGS_EC2) << 8) + (uint32_t)(PCR3_EC2_LED2_BITPOS & 0xFFu)),
PCR_BCM = (((uint32_t)(PCR3_REGS_EC2) << 8) + (uint32_t)(PCR3_EC2_BCM_BITPOS & 0xFFu)),
PCR_SPI1 = (((uint32_t)(PCR3_REGS_EC2) << 8) + (uint32_t)(PCR3_EC2_SPI1_BITPOS & 0xFFu)),
PCR_BTIMER2 = (((uint32_t)(PCR3_REGS_EC2) << 8) + (uint32_t)(PCR3_EC2_BTIMER2_BITPOS & 0xFFu)),
PCR_BTIMER3 = (((uint32_t)(PCR3_REGS_EC2) << 8) + (uint32_t)(PCR3_EC2_BTIMER3_BITPOS & 0xFFu)),
PCR_BTIMER4 = (((uint32_t)(PCR3_REGS_EC2) << 8) + (uint32_t)(PCR3_EC2_BTIMER4_BITPOS & 0xFFu)),
PCR_BTIMER5 = (((uint32_t)(PCR3_REGS_EC2) << 8) + (uint32_t)(PCR3_EC2_BTIMER5_BITPOS & 0xFFu)),
PCR_LED3 = (((uint32_t)(PCR3_REGS_EC2) << 8) + (uint32_t)(PCR3_EC2_LED3_BITPOS & 0xFFu)),
} PCR_BLK_ID;
/******************************************************************************/
/** PCR Processor ClK Divide Values
*******************************************************************************/
enum PROCESSOR_CLK_DIVIDE_VALUE
{
PCR_CPU_CLK_DIVIDE_1 = 1,
PCR_CPU_CLK_DIVIDE_4 = 4,
PCR_CPU_CLK_DIVIDE_16 = 16,
PCR_CPU_CLK_DIVIDE_48 = 48
};
/******************************************************************************/
/** System Sleep Modes
*******************************************************************************/
enum SYSTEM_SLEEP_MODES
{
SYSTEM_HEAVY_SLEEP_1 = 0,
SYSTEM_HEAVY_SLEEP_3 = 1,
SYSTEM_HEAVY_SLEEP_2 = 2,
SYSTEM_DEEPEST_SLEEP = 5
};
/* Bitmask for System Sleep Control Register */
#define PCR_SYS_SLP_CTRL_RING_OSC_PWR_DOWN_BITMASK (1UL<<0)
#define PCR_SYS_SLP_CTRL_RING_OSC_OUTPUT_GATE_BITMASK (1UL<<1)
#define PCR_SYS_SLP_CTRL_CORE_REGLTOR_STDBY_BITMASK (1UL<<2)
/* Bitmask for Chip Sub-system Power Reset Status Register */
#define PCR_CHIP_SUBSYSTEM_VCC_RESET_STS_BITMASK (1UL<<2)
#define PCR_CHIP_SUBSYSTEM_SIO_RESET_STS_BITMASK (1UL<<3)
#define PCR_CHIP_SUBSYSTEM_VBAT_RESET_STS_BITMASK (1UL<<5)
#define PCR_CHIP_SUBSYSTEM_VCC1_RESET_STS_BITMASK (1UL<<6)
#define PCR_CHIP_SUBSYSTEM_32K_ACTIVE_STS_BITMASK (1UL<<10)
#define PCR_CHIP_SUBSYSTEM_PCICLK_ACTIVE_STS_BITMASK (1UL<<11)
/* Bitmask for Processor Clock Control Register */
#define PCR_OSCILLATOR_LOCK_STATUS_BITMASK (1UL<<8)
/* Bitmask for Power Reset Control Register */
#define PCR_iRESET_OUT_BITMASK (1UL<<0)
/* ---------------------------------------------------------------------- */
/* API - Functions to program Sleep Enable, CLK Reqd Status, *
* Reset Enable for a block *
* ---------------------------------------------------------------------- */
/** Sets or Clears block specific bit in PCR Sleep Enable Register
* @param pcr_block_id - pcr block id encoded using PCRx_REGS_BIT
* @param set_clr_flag - Flag to set (1) or clear (0) bit in the PCR Sleep Enable Register
*/
void pcr_sleep_enable(uint32_t pcr_block_id, uint8_t set_clr_flag);
/** Get Clock Required Status for the block
* @param pcr_block_id - pcr block id encoded using PCRx_REGS_BIT
* @return uint8_t - 1 if Clock Required Status set, else 0
*/
uint8_t pcr_clock_reqd_status_get(uint32_t pcr_block_id);
/** Sets or Clears Reset Enable register bit for the block
* @param pcr_block_id - pcr block id encoded using PCRx_REGS_BIT
* @param set_clr_flag - Flag to set (1) or clear (0) bit in the PCR Reset Enable Register
*/
void pcr_reset_enable(uint32_t pcr_block_id, uint8_t set_clr_flag);
/* ---------------------------------------------------------------------- */
/* API - Functions for entering low power modes */
/* ---------------------------------------------------------------------- */
/** Instructs all blocks to sleep by setting the Sleep Enable bits */
void pcr_all_blocks_sleep(void);
/** Clears the Sleep Enable bits for all blocks */
void pcr_all_blocks_wake(void);
/** Programs required sleep mode in System Sleep Control Register
* @param sleep_mode - see enum SYSTEM_SLEEP_MODES
*/
void pcr_system_sleep(uint8_t sleep_mode);
/* ---------------------------------------------------------------------- */
/* Peripheral Function - Functions to program and read 32-bit values *
* from PCR Registers *
* ---------------------------------------------------------------------- */
/** Write 32-bit value in the PCR Register
* @param pcr_reg_id - pcr register id
* @param value - 32-bit value
*/
void p_pcr_reg_write(uint8_t pcr_reg_id, uint32_t value);
/** Reads 32-bit value from the PCR Register
* @param pcr_reg_id - pcr register id
* @return value - 32-bit value
*/
uint32_t p_pcr_reg_read(uint8_t pcr_reg_id);
/* ---------------------------------------------------------------------- */
/* Peripheral Function - Functions to set, clr and get bits in *
* PCR Registers *
* ---------------------------------------------------------------------- */
/** Sets bits in a PCR Register
* @param pcr_reg_id - pcr register id
* @param bit_mask - Bit mask of bits to set
*/
void p_pcr_reg_set(uint8_t pcr_reg_id, uint32_t bit_mask);
/** Clears bits in a PCR Register
* @param pcr_reg_id - pcr register id
* @param bit_mask - Bit mask of bits to clear
*/
void p_pcr_reg_clr(uint8_t pcr_reg_id, uint32_t bit_mask);
/** Read bits in a PCR Register
* @param pcr_reg_id - pcr register id
* @param bit_mask - Bit mask of bits to read
* @return value - 32-bit value
*/
uint32_t p_pcr_reg_get(uint8_t pcr_reg_id, uint32_t bit_mask);
/** Sets or Clears bits in a PCR Register - Helper Function
* @param pcr_reg_id - pcr register id
* @param bit_mask - Bit mask of bits to set or clear
* @param set_clr_flag - Flag to set (1) or clear (0) bits in the PCR Register
*/
void p_pcr_reg_update(uint8_t pcr_reg_id, uint32_t bit_mask, uint8_t set_clr_flag);
//Functions to operate on System Sleep Control Register
/* ---------------------------------------------------------------------- */
/* Peripheral Function - Functions to operate on System Sleep Control *
* Register *
* ---------------------------------------------------------------------- */
/** Sets/Clears the Ring oscillator power down bit
* in System Sleep Control Register
* @param set_clr_flag - 1 - Sets the bit, 0 - clears the bit
*/
void p_pcr_system_sleep_ctrl_ring_osc_power_down(uint8_t set_clr_flag);
/** Sets/Clears the Ring oscillator output gate bit
* in System Sleep Control Register
* @param set_clr_flag - 1 - Sets the bit, 0 - clears the bit
*/
void p_pcr_system_sleep_ctrl_ring_osc_output_gate(uint8_t set_clr_flag);
/** Sets/Clears the Core regulator standby bit
* in System Sleep Control Register
* @param set_clr_flag - 1 - Sets the bit, 0 - clears the bit
*/
void p_pcr_system_sleep_ctrl_core_regulator_stdby(uint8_t set_clr_flag);
/** Writes required sleep mode in System Sleep Control Register
* @param sleep_value - System Sleep control value - [D2, D1, D0]
*/
void p_pcr_system_sleep_ctrl_write(uint8_t sleep_value);
/** Reads the System Sleep Control PCR Register
* @return value - byte 0 of the system sleep control PCR register
*/
uint8_t p_pcr_system_sleep_ctrl_read(void);
/* ---------------------------------------------------------------------- */
/* Peripheral Function - Function to program to CLK Divide Value *
* ---------------------------------------------------------------------- */
/** Writes the clock divide value in the Processor Clock Control Register
* @param clk_divide_value - clk divide values, valid values in enum PROCESSOR_CLK_DIVIDE_VALUE
*/
void p_pcr_processor_clk_ctrl_write(uint8_t clk_divide_value);
/* ---------------------------------------------------------------------- */
/* Peripheral Function - Function to program the Slow Clock Control *
* Register *
* ---------------------------------------------------------------------- */
/** Write the slow clock divide value in the Slow Clock Control Register
* @param slow_clk_divide_value - slow clk divide value
*/
void p_pcr_slow_clk_ctrl_write(uint8_t slow_clk_divide_value);
/* ---------------------------------------------------------------------- */
/* Peripheral Function - Function to read the Oscillator Lock Status */
/* ---------------------------------------------------------------------- */
/** Reads the Oscillator Lock status bit in the Oscillator ID Register
* @return 1 if Oscillator Lock Status bit is set, else 0
*/
uint8_t p_pcr_oscillator_lock_sts_get(void);
/* ---------------------------------------------------------------------- */
/* Peripheral Function - Functions to read various power status in *
* Chip Sub-System register *
* ---------------------------------------------------------------------- */
/** Reads the VCC Reset Status bit
* in the Chip Subsystem Power Reset Status Register
* @return 1 if VCC Reset Status bit is set, else 0
*/
uint8_t p_pcr_chip_subsystem_vcc_reset_sts_get(void);
/** Reads the SIO Reset Status bit
* in the Chip Subsystem Power Reset Status Register
* @return 1 if SIO Reset Status bit is set, else 0
*/
uint8_t p_pcr_chip_subsystem_sio_reset_sts_get(void);
/** Reads the VBAT Reset Status bit
* in the Chip Subsystem Power Reset Status Register
* @return 1 if VBAT Reset Status bit is set, else 0
*/
uint8_t p_pcr_chip_subsystem_vbat_reset_sts_get(void);
/** Clears the VBAT Reset Status bit
* in the Chip Subsystem Power Reset Status Register
*/
void p_pcr_chip_subsystem_vbat_reset_sts_clr(void);
/** Reads the VCC1 Reset Status bit
* in the Chip Subsystem Power Reset Status Register
* @return 1 if VCC1 Reset Status bit is set, else 0
*/
uint8_t p_pcr_chip_subsystem_vcc1_reset_sts_get(void);
/** Clears the VCC1 Reset Status bit
* in the Chip Subsystem Power Reset Status Register
*/
void p_pcr_chip_subsystem_vcc1_reset_sts_clr(void);
/** Reads the 32K_ACTIVE status bit
* in the Chip Subsystem Power Reset Status Register
* @return 1 if 32_ACTIVE bit is set, else 0
*/
uint8_t p_pcr_chip_subsystem_32K_active_sts_get(void);
/** Reads the PCICLK_ACTIVE status bit
* in the Chip Subsystem Power Reset Status Register
* @return 1 if CICLK_ACTIVE bit is set, else 0
*/
uint8_t p_pcr_chip_subsystem_pciclk_active_sts_get(void);
/* ---------------------------------------------------------------------- */
/* Peripheral Function - Functions for Power Reset Control Register */
/* ---------------------------------------------------------------------- */
/** Reads the iRESET_OUT bit in the Power Reset Control Register
* @return 1 if iRESET_OUT bit is set, else 0
*/
uint8_t p_pcr_iReset_Out_get(void);
/** Sets/Clears the iRESET_OUT bit in the Power Reset Control Register
* @param 1 Set iRESET_OUT bit; 0 - Clear the bit
*/
void p_pcr_iReset_Out(uint8_t set_clr_flag);
#endif // #ifndef _PCR_H
/* end pcr.h */
/** @}
*/
/*****************************************************************************
* © 2015 Microchip Technology Inc. and its subsidiaries.
* You may use this software and any derivatives exclusively with
* Microchip products.
* THIS SOFTWARE IS SUPPLIED BY MICROCHIP "AS IS".
* NO WARRANTIES, WHETHER EXPRESS, IMPLIED OR STATUTORY, APPLY TO THIS SOFTWARE,
* INCLUDING ANY IMPLIED WARRANTIES OF NON-INFRINGEMENT, MERCHANTABILITY,
* AND FITNESS FOR A PARTICULAR PURPOSE, OR ITS INTERACTION WITH MICROCHIP
* PRODUCTS, COMBINATION WITH ANY OTHER PRODUCTS, OR USE IN ANY APPLICATION.
* IN NO EVENT WILL MICROCHIP BE LIABLE FOR ANY INDIRECT, SPECIAL, PUNITIVE,
* INCIDENTAL OR CONSEQUENTIAL LOSS, DAMAGE, COST OR EXPENSE OF ANY KIND
* WHATSOEVER RELATED TO THE SOFTWARE, HOWEVER CAUSED, EVEN IF MICROCHIP HAS
* BEEN ADVISED OF THE POSSIBILITY OR THE DAMAGES ARE FORESEEABLE.
* TO THE FULLEST EXTENT ALLOWED BY LAW, MICROCHIP'S TOTAL LIABILITY ON ALL
* CLAIMS IN ANY WAY RELATED TO THIS SOFTWARE WILL NOT EXCEED THE AMOUNT OF
* FEES, IF ANY, THAT YOU HAVE PAID DIRECTLY TO MICROCHIP FOR THIS SOFTWARE.
* MICROCHIP PROVIDES THIS SOFTWARE CONDITIONALLY UPON YOUR ACCEPTANCE
* OF THESE TERMS.
******************************************************************************
Version Control Information (Perforce)
******************************************************************************
$Revision: #1 $
$DateTime: 2016/04/08 10:18:28 $
$Author: pramans $
Last Change: Updated for tabs
******************************************************************************/
/** @file pcr.h
* \brief Power, Clocks, and Resets Header file
* \author jvasanth
*
* This file is the PCR header file
******************************************************************************/
/** @defgroup PCR
* @{
*/
#ifndef _PCR_H
#define _PCR_H
/******************************************************************************/
/** PCR Register IDS
*******************************************************************************/
enum _PCR_REGSET_ID_
{
PCR_REG_CHIP_SLEEP_ENABLE =0,
PCR_REG_CHIP_CLK_REQD_STS,
PCR_REG_EC_SLEEP_ENABLE,
PCR_REG_EC_CLK_REQD_STS,
PCR_REG_HOST_SLEEP_ENABLE,
PCR_REG_HOST_CLK_REQD_STS,
PCR_REG_SYSTEM_SLEEP_CTRL,
PCR_REG_PROCESSOR_CLK_CTRL = 8,
PCR_REG_EC_SLEEP_ENABLE_2,
PCR_REG_EC_CLK_REQD_STS_2,
PCR_REG_SLOW_CLK_CTRL,
PCR_REG_OSCILLATOR_ID,
PCR_REG_CHIP_SUBSYSTEM_PWR_RESET_STS,
PCR_REG_CHIP_RESET_ENABLE,
PCR_REG_HOST_RESET_ENABLE,
PCR_REG_EC_RESET_ENABLE,
PCR_REG_EC_RESET_ENABLE_2,
PCR_REG_PWR_RESET_CTRL
};
/* ---------------------------------------------------------------------- */
// Encode the Register ids for Sleep Enable, Clock Required, Reset Enable
//PCR register group 0 - CHIP
#define PCR0_REGS_CHIP (((uint32_t)(PCR_REG_CHIP_SLEEP_ENABLE) & 0xFF) + \
(((uint32_t)(PCR_REG_CHIP_CLK_REQD_STS) & 0xFF)<<8u) + \
(((uint32_t)(PCR_REG_CHIP_RESET_ENABLE) & 0xFF)<<16u))
//PCR register group 1 - EC
#define PCR1_REGS_EC (((uint32_t)(PCR_REG_EC_SLEEP_ENABLE) & 0xFF) + \
(((uint32_t)(PCR_REG_EC_CLK_REQD_STS) & 0xFF)<<8u) + \
(((uint32_t)(PCR_REG_EC_RESET_ENABLE) & 0xFF)<<16u))
//PCR register group 2 - HOST
#define PCR2_REGS_HOST (((uint32_t)(PCR_REG_EC_SLEEP_ENABLE) & 0xFF) + \
(((uint32_t)(PCR_REG_EC_CLK_REQD_STS) & 0xFF)<<8u) + \
(((uint32_t)(PCR_REG_EC_RESET_ENABLE) & 0xFF)<<16u))
//PCR register group 3 - EC 2
#define PCR3_REGS_EC2 (((uint32_t)(PCR_REG_EC_SLEEP_ENABLE_2) & 0xFF) + \
(((uint32_t)(PCR_REG_EC_CLK_REQD_STS_2) & 0xFF)<<8u) + \
(((uint32_t)(PCR_REG_EC_RESET_ENABLE_2) & 0xFF)<<16u))
//PCR1_EC -> SLEEP_ENABLE, CLK REQD STS, RESET_ENABLE Bit Positions
#define PCR1_EC_INT_BITPOS (0u)
#define PCR1_EC_PECI_BITPOS (1u)
#define PCR1_EC_TACH0_BITPOS (2u)
#define PCR1_EC_PWM0_BITPOS (4u)
#define PCR1_EC_PMC_BITPOS (5u)
#define PCR1_EC_DMA_BITPOS (6u)
#define PCR1_EC_TFDP_BITPOS (7u)
#define PCR1_EC_CPU_BITPOS (8u)
#define PCR1_EC_WDT_BITPOS (9u)
#define PCR1_EC_SMB0_BITPOS (10u)
#define PCR1_EC_TACH1_BITPOS (11u)
#define PCR1_EC_PWM1_BITPOS (20u)
#define PCR1_EC_PWM2_BITPOS (21u)
#define PCR1_EC_PWM3_BITPOS (22u)
#define PCR1_EC_REG_BITPOS (29u)
#define PCR1_EC_BTIMER0_BITPOS (30u)
#define PCR1_EC_BTIMER1_BITPOS (31u)
//PCR2_HOST -> SLEEP_ENABLE, CLK REQD STS, RESET_ENABLE Bit Positions
#define PCR2_HOST_LPC_BITPOS (0u)
#define PCR2_HOST_UART0_BITPOS (1u)
#define PCR2_HOST_GLBL_CFG_BITPOS (12u)
#define PCR2_HOST_ACPI_EC0_BITPOS (13u)
#define PCR2_HOST_ACPI_EC1_BITPOS (14u)
#define PCR2_HOST_ACPI_PM1_BITPOS (15u)
#define PCR2_HOST_8042EM_BITPOS (16u)
#define PCR2_HOST_RTC_BITPOS (18u)
//PCR3_EC2 -> SLEEP_ENABLE, CLK REQD STS, RESET_ENABLE Bit Positions
#define PCR3_EC2_ADC_BITPOS (3u)
#define PCR3_EC2_PS2_0_BITPOS (5u)
#define PCR3_EC2_PS2_1_BITPOS (6u)
#define PCR3_EC2_PS2_2_BITPOS (7u)
#define PCR3_EC2_PS2_3_BITPOS (8u)
#define PCR3_EC2_SPI0_BITPOS (9u)
#define PCR3_EC2_HTIMER_BITPOS (10u)
#define PCR3_EC2_KEYSCAN_BITPOS (11u)
#define PCR3_EC2_RPM_PWM_BITPOS (12u)
#define PCR3_EC2_SMB1_BITPOS (13u)
#define PCR3_EC2_SMB2_BITPOS (14u)
#define PCR3_EC2_SMB3_BITPOS (15u)
#define PCR3_EC2_LED0_BITPOS (16u)
#define PCR3_EC2_LED1_BITPOS (17u)
#define PCR3_EC2_LED2_BITPOS (18u)
#define PCR3_EC2_BCM_BITPOS (19u)
#define PCR3_EC2_SPI1_BITPOS (20u)
#define PCR3_EC2_BTIMER2_BITPOS (21u)
#define PCR3_EC2_BTIMER3_BITPOS (22u)
#define PCR3_EC2_BTIMER4_BITPOS (23u)
#define PCR3_EC2_BTIMER5_BITPOS (24u)
#define PCR3_EC2_LED3_BITPOS (25u)
/*
* n = b[7:0] = PCR Reg Bit Position
* m = b[31:8] = PCRx Regs IDs
*/
//#define PCRx_REGS_BIT(m,n) ((((uint32_t)(m)&0xFFFFFFul)<<8u) + ((uint32_t)(n)&0xFFul))
//PCRx_REGS_BIT positions
#define PCRx_REGS_POS_SLEEP_ENABLE (8u)
#define PCRx_REGS_POS_CLK_REQD_STS (16u)
#define PCRx_REGS_POS_RESET_ENABLE (24u)
/******************************************************************************/
/** PCR Block IDS.
* These IDs are used to directly refer to a block
*******************************************************************************/
typedef enum {
PCR_INT = (((uint32_t)(PCR1_REGS_EC) << 8) + (uint32_t)(PCR1_EC_INT_BITPOS & 0xFFu)),
PCR_PECI = (((uint32_t)(PCR1_REGS_EC) << 8) + (uint32_t)(PCR1_EC_PECI_BITPOS & 0xFFu)),
PCR_TACH0 = (((uint32_t)(PCR1_REGS_EC) << 8) + (uint32_t)(PCR1_EC_TACH0_BITPOS & 0xFFu)),
PCR_PWM0 = (((uint32_t)(PCR1_REGS_EC) << 8) + (uint32_t)(PCR1_EC_PWM0_BITPOS & 0xFFu)),
PCR_PMC = (((uint32_t)(PCR1_REGS_EC) << 8) + (uint32_t)(PCR1_EC_PMC_BITPOS & 0xFFu)),
PCR_DMA = (((uint32_t)(PCR1_REGS_EC) << 8) + (uint32_t)(PCR1_EC_DMA_BITPOS & 0xFFu)),
PCR_TFDP = (((uint32_t)(PCR1_REGS_EC) << 8) + (uint32_t)(PCR1_EC_TFDP_BITPOS & 0xFFu)),
PCR_CPU = (((uint32_t)(PCR1_REGS_EC) << 8) + (uint32_t)(PCR1_EC_CPU_BITPOS & 0xFFu)),
PCR_WDT = (((uint32_t)(PCR1_REGS_EC) << 8) + (uint32_t)(PCR1_EC_WDT_BITPOS & 0xFFu)),
PCR_SMB0 = (((uint32_t)(PCR1_REGS_EC) << 8) + (uint32_t)(PCR1_EC_SMB0_BITPOS & 0xFFu)),
PCR_TACH1 = (((uint32_t)(PCR1_REGS_EC) << 8) + (uint32_t)(PCR1_EC_TACH1_BITPOS & 0xFFu)),
PCR_PWM1 = (((uint32_t)(PCR1_REGS_EC) << 8) + (uint32_t)(PCR1_EC_PWM1_BITPOS & 0xFFu)),
PCR_PWM2 = (((uint32_t)(PCR1_REGS_EC) << 8) + (uint32_t)(PCR1_EC_PWM2_BITPOS & 0xFFu)),
PCR_PWM3 = (((uint32_t)(PCR1_REGS_EC) << 8) + (uint32_t)(PCR1_EC_PWM3_BITPOS & 0xFFu)),
PCR_REG = (((uint32_t)(PCR1_REGS_EC) << 8) + (uint32_t)(PCR1_EC_REG_BITPOS & 0xFFu)),
PCR_BTIMER0 = (((uint32_t)(PCR1_REGS_EC) << 8) + (uint32_t)(PCR1_EC_BTIMER0_BITPOS & 0xFFu)),
PCR_BTIMER1 = (((uint32_t)(PCR1_REGS_EC) << 8) + (uint32_t)(PCR1_EC_BTIMER1_BITPOS & 0xFFu)),
PCR_LPC = (((uint32_t)(PCR2_REGS_HOST) << 8) + (uint32_t)(PCR2_HOST_LPC_BITPOS & 0xFFu)),
PCR_UART0 = (((uint32_t)(PCR2_REGS_HOST) << 8) + (uint32_t)(PCR2_HOST_UART0_BITPOS & 0xFFu)),
PCR_GLBL_CFG = (((uint32_t)(PCR2_REGS_HOST) << 8) + (uint32_t)(PCR2_HOST_GLBL_CFG_BITPOS & 0xFFu)),
PCR_ACPI_EC0 = (((uint32_t)(PCR2_REGS_HOST) << 8) + (uint32_t)(PCR2_HOST_ACPI_EC0_BITPOS & 0xFFu)),
PCR_ACPI_EC1 = (((uint32_t)(PCR2_REGS_HOST) << 8) + (uint32_t)(PCR2_HOST_ACPI_EC1_BITPOS & 0xFFu)),
PCR_ACPI_PM1 = (((uint32_t)(PCR2_REGS_HOST) << 8) + (uint32_t)(PCR2_HOST_ACPI_PM1_BITPOS & 0xFFu)),
PCR_8042EM = (((uint32_t)(PCR2_REGS_HOST) << 8) + (uint32_t)(PCR2_HOST_8042EM_BITPOS & 0xFFu)),
PCR_RTC = (((uint32_t)(PCR2_REGS_HOST) << 8) + (uint32_t)(PCR2_HOST_RTC_BITPOS & 0xFFu)),
PCR_ADC = (((uint32_t)(PCR3_REGS_EC2) << 8) + (uint32_t)(PCR3_EC2_ADC_BITPOS & 0xFFu)),
PCR_PS2_0 = (((uint32_t)(PCR3_REGS_EC2) << 8) + (uint32_t)(PCR3_EC2_PS2_0_BITPOS & 0xFFu)),
PCR_PS2_1 = (((uint32_t)(PCR3_REGS_EC2) << 8) + (uint32_t)(PCR3_EC2_PS2_1_BITPOS & 0xFFu)),
PCR_PS2_2 = (((uint32_t)(PCR3_REGS_EC2) << 8) + (uint32_t)(PCR3_EC2_PS2_2_BITPOS & 0xFFu)),
PCR_PS2_3 = (((uint32_t)(PCR3_REGS_EC2) << 8) + (uint32_t)(PCR3_EC2_PS2_3_BITPOS & 0xFFu)),
PCR_SPI0 = (((uint32_t)(PCR3_REGS_EC2) << 8) + (uint32_t)(PCR3_EC2_SPI0_BITPOS & 0xFFu)),
PCR_HTIMER = (((uint32_t)(PCR3_REGS_EC2) << 8) + (uint32_t)(PCR3_EC2_HTIMER_BITPOS & 0xFFu)),
PCR_KEYSCAN = (((uint32_t)(PCR3_REGS_EC2) << 8) + (uint32_t)(PCR3_EC2_KEYSCAN_BITPOS & 0xFFu)),
PCR_RPM_PWM = (((uint32_t)(PCR3_REGS_EC2) << 8) + (uint32_t)(PCR3_EC2_RPM_PWM_BITPOS & 0xFFu)),
PCR_SMB1 = (((uint32_t)(PCR3_REGS_EC2) << 8) + (uint32_t)(PCR3_EC2_SMB1_BITPOS & 0xFFu)),
PCR_SMB2 = (((uint32_t)(PCR3_REGS_EC2) << 8) + (uint32_t)(PCR3_EC2_SMB2_BITPOS & 0xFFu)),
PCR_SMB3 = (((uint32_t)(PCR3_REGS_EC2) << 8) + (uint32_t)(PCR3_EC2_SMB3_BITPOS & 0xFFu)),
PCR_LED0 = (((uint32_t)(PCR3_REGS_EC2) << 8) + (uint32_t)(PCR3_EC2_LED0_BITPOS & 0xFFu)),
PCR_LED1 = (((uint32_t)(PCR3_REGS_EC2) << 8) + (uint32_t)(PCR3_EC2_LED1_BITPOS & 0xFFu)),
PCR_LED2 = (((uint32_t)(PCR3_REGS_EC2) << 8) + (uint32_t)(PCR3_EC2_LED2_BITPOS & 0xFFu)),
PCR_BCM = (((uint32_t)(PCR3_REGS_EC2) << 8) + (uint32_t)(PCR3_EC2_BCM_BITPOS & 0xFFu)),
PCR_SPI1 = (((uint32_t)(PCR3_REGS_EC2) << 8) + (uint32_t)(PCR3_EC2_SPI1_BITPOS & 0xFFu)),
PCR_BTIMER2 = (((uint32_t)(PCR3_REGS_EC2) << 8) + (uint32_t)(PCR3_EC2_BTIMER2_BITPOS & 0xFFu)),
PCR_BTIMER3 = (((uint32_t)(PCR3_REGS_EC2) << 8) + (uint32_t)(PCR3_EC2_BTIMER3_BITPOS & 0xFFu)),
PCR_BTIMER4 = (((uint32_t)(PCR3_REGS_EC2) << 8) + (uint32_t)(PCR3_EC2_BTIMER4_BITPOS & 0xFFu)),
PCR_BTIMER5 = (((uint32_t)(PCR3_REGS_EC2) << 8) + (uint32_t)(PCR3_EC2_BTIMER5_BITPOS & 0xFFu)),
PCR_LED3 = (((uint32_t)(PCR3_REGS_EC2) << 8) + (uint32_t)(PCR3_EC2_LED3_BITPOS & 0xFFu)),
} PCR_BLK_ID;
/******************************************************************************/
/** PCR Processor ClK Divide Values
*******************************************************************************/
enum PROCESSOR_CLK_DIVIDE_VALUE
{
PCR_CPU_CLK_DIVIDE_1 = 1,
PCR_CPU_CLK_DIVIDE_4 = 4,
PCR_CPU_CLK_DIVIDE_16 = 16,
PCR_CPU_CLK_DIVIDE_48 = 48
};
/******************************************************************************/
/** System Sleep Modes
*******************************************************************************/
enum SYSTEM_SLEEP_MODES
{
SYSTEM_HEAVY_SLEEP_1 = 0,
SYSTEM_HEAVY_SLEEP_3 = 1,
SYSTEM_HEAVY_SLEEP_2 = 2,
SYSTEM_DEEPEST_SLEEP = 5
};
/* Bitmask for System Sleep Control Register */
#define PCR_SYS_SLP_CTRL_RING_OSC_PWR_DOWN_BITMASK (1UL<<0)
#define PCR_SYS_SLP_CTRL_RING_OSC_OUTPUT_GATE_BITMASK (1UL<<1)
#define PCR_SYS_SLP_CTRL_CORE_REGLTOR_STDBY_BITMASK (1UL<<2)
/* Bitmask for Chip Sub-system Power Reset Status Register */
#define PCR_CHIP_SUBSYSTEM_VCC_RESET_STS_BITMASK (1UL<<2)
#define PCR_CHIP_SUBSYSTEM_SIO_RESET_STS_BITMASK (1UL<<3)
#define PCR_CHIP_SUBSYSTEM_VBAT_RESET_STS_BITMASK (1UL<<5)
#define PCR_CHIP_SUBSYSTEM_VCC1_RESET_STS_BITMASK (1UL<<6)
#define PCR_CHIP_SUBSYSTEM_32K_ACTIVE_STS_BITMASK (1UL<<10)
#define PCR_CHIP_SUBSYSTEM_PCICLK_ACTIVE_STS_BITMASK (1UL<<11)
/* Bitmask for Processor Clock Control Register */
#define PCR_OSCILLATOR_LOCK_STATUS_BITMASK (1UL<<8)
/* Bitmask for Power Reset Control Register */
#define PCR_iRESET_OUT_BITMASK (1UL<<0)
/* ---------------------------------------------------------------------- */
/* API - Functions to program Sleep Enable, CLK Reqd Status, *
* Reset Enable for a block *
* ---------------------------------------------------------------------- */
/** Sets or Clears block specific bit in PCR Sleep Enable Register
* @param pcr_block_id - pcr block id encoded using PCRx_REGS_BIT
* @param set_clr_flag - Flag to set (1) or clear (0) bit in the PCR Sleep Enable Register
*/
void pcr_sleep_enable(uint32_t pcr_block_id, uint8_t set_clr_flag);
/** Get Clock Required Status for the block
* @param pcr_block_id - pcr block id encoded using PCRx_REGS_BIT
* @return uint8_t - 1 if Clock Required Status set, else 0
*/
uint8_t pcr_clock_reqd_status_get(uint32_t pcr_block_id);
/** Sets or Clears Reset Enable register bit for the block
* @param pcr_block_id - pcr block id encoded using PCRx_REGS_BIT
* @param set_clr_flag - Flag to set (1) or clear (0) bit in the PCR Reset Enable Register
*/
void pcr_reset_enable(uint32_t pcr_block_id, uint8_t set_clr_flag);
/* ---------------------------------------------------------------------- */
/* API - Functions for entering low power modes */
/* ---------------------------------------------------------------------- */
/** Instructs all blocks to sleep by setting the Sleep Enable bits */
void pcr_all_blocks_sleep(void);
/** Clears the Sleep Enable bits for all blocks */
void pcr_all_blocks_wake(void);
/** Programs required sleep mode in System Sleep Control Register
* @param sleep_mode - see enum SYSTEM_SLEEP_MODES
*/
void pcr_system_sleep(uint8_t sleep_mode);
/* ---------------------------------------------------------------------- */
/* Peripheral Function - Functions to program and read 32-bit values *
* from PCR Registers *
* ---------------------------------------------------------------------- */
/** Write 32-bit value in the PCR Register
* @param pcr_reg_id - pcr register id
* @param value - 32-bit value
*/
void p_pcr_reg_write(uint8_t pcr_reg_id, uint32_t value);
/** Reads 32-bit value from the PCR Register
* @param pcr_reg_id - pcr register id
* @return value - 32-bit value
*/
uint32_t p_pcr_reg_read(uint8_t pcr_reg_id);
/* ---------------------------------------------------------------------- */
/* Peripheral Function - Functions to set, clr and get bits in *
* PCR Registers *
* ---------------------------------------------------------------------- */
/** Sets bits in a PCR Register
* @param pcr_reg_id - pcr register id
* @param bit_mask - Bit mask of bits to set
*/
void p_pcr_reg_set(uint8_t pcr_reg_id, uint32_t bit_mask);
/** Clears bits in a PCR Register
* @param pcr_reg_id - pcr register id
* @param bit_mask - Bit mask of bits to clear
*/
void p_pcr_reg_clr(uint8_t pcr_reg_id, uint32_t bit_mask);
/** Read bits in a PCR Register
* @param pcr_reg_id - pcr register id
* @param bit_mask - Bit mask of bits to read
* @return value - 32-bit value
*/
uint32_t p_pcr_reg_get(uint8_t pcr_reg_id, uint32_t bit_mask);
/** Sets or Clears bits in a PCR Register - Helper Function
* @param pcr_reg_id - pcr register id
* @param bit_mask - Bit mask of bits to set or clear
* @param set_clr_flag - Flag to set (1) or clear (0) bits in the PCR Register
*/
void p_pcr_reg_update(uint8_t pcr_reg_id, uint32_t bit_mask, uint8_t set_clr_flag);
//Functions to operate on System Sleep Control Register
/* ---------------------------------------------------------------------- */
/* Peripheral Function - Functions to operate on System Sleep Control *
* Register *
* ---------------------------------------------------------------------- */
/** Sets/Clears the Ring oscillator power down bit
* in System Sleep Control Register
* @param set_clr_flag - 1 - Sets the bit, 0 - clears the bit
*/
void p_pcr_system_sleep_ctrl_ring_osc_power_down(uint8_t set_clr_flag);
/** Sets/Clears the Ring oscillator output gate bit
* in System Sleep Control Register
* @param set_clr_flag - 1 - Sets the bit, 0 - clears the bit
*/
void p_pcr_system_sleep_ctrl_ring_osc_output_gate(uint8_t set_clr_flag);
/** Sets/Clears the Core regulator standby bit
* in System Sleep Control Register
* @param set_clr_flag - 1 - Sets the bit, 0 - clears the bit
*/
void p_pcr_system_sleep_ctrl_core_regulator_stdby(uint8_t set_clr_flag);
/** Writes required sleep mode in System Sleep Control Register
* @param sleep_value - System Sleep control value - [D2, D1, D0]
*/
void p_pcr_system_sleep_ctrl_write(uint8_t sleep_value);
/** Reads the System Sleep Control PCR Register
* @return value - byte 0 of the system sleep control PCR register
*/
uint8_t p_pcr_system_sleep_ctrl_read(void);
/* ---------------------------------------------------------------------- */
/* Peripheral Function - Function to program to CLK Divide Value *
* ---------------------------------------------------------------------- */
/** Writes the clock divide value in the Processor Clock Control Register
* @param clk_divide_value - clk divide values, valid values in enum PROCESSOR_CLK_DIVIDE_VALUE
*/
void p_pcr_processor_clk_ctrl_write(uint8_t clk_divide_value);
/* ---------------------------------------------------------------------- */
/* Peripheral Function - Function to program the Slow Clock Control *
* Register *
* ---------------------------------------------------------------------- */
/** Write the slow clock divide value in the Slow Clock Control Register
* @param slow_clk_divide_value - slow clk divide value
*/
void p_pcr_slow_clk_ctrl_write(uint8_t slow_clk_divide_value);
/* ---------------------------------------------------------------------- */
/* Peripheral Function - Function to read the Oscillator Lock Status */
/* ---------------------------------------------------------------------- */
/** Reads the Oscillator Lock status bit in the Oscillator ID Register
* @return 1 if Oscillator Lock Status bit is set, else 0
*/
uint8_t p_pcr_oscillator_lock_sts_get(void);
/* ---------------------------------------------------------------------- */
/* Peripheral Function - Functions to read various power status in *
* Chip Sub-System register *
* ---------------------------------------------------------------------- */
/** Reads the VCC Reset Status bit
* in the Chip Subsystem Power Reset Status Register
* @return 1 if VCC Reset Status bit is set, else 0
*/
uint8_t p_pcr_chip_subsystem_vcc_reset_sts_get(void);
/** Reads the SIO Reset Status bit
* in the Chip Subsystem Power Reset Status Register
* @return 1 if SIO Reset Status bit is set, else 0
*/
uint8_t p_pcr_chip_subsystem_sio_reset_sts_get(void);
/** Reads the VBAT Reset Status bit
* in the Chip Subsystem Power Reset Status Register
* @return 1 if VBAT Reset Status bit is set, else 0
*/
uint8_t p_pcr_chip_subsystem_vbat_reset_sts_get(void);
/** Clears the VBAT Reset Status bit
* in the Chip Subsystem Power Reset Status Register
*/
void p_pcr_chip_subsystem_vbat_reset_sts_clr(void);
/** Reads the VCC1 Reset Status bit
* in the Chip Subsystem Power Reset Status Register
* @return 1 if VCC1 Reset Status bit is set, else 0
*/
uint8_t p_pcr_chip_subsystem_vcc1_reset_sts_get(void);
/** Clears the VCC1 Reset Status bit
* in the Chip Subsystem Power Reset Status Register
*/
void p_pcr_chip_subsystem_vcc1_reset_sts_clr(void);
/** Reads the 32K_ACTIVE status bit
* in the Chip Subsystem Power Reset Status Register
* @return 1 if 32_ACTIVE bit is set, else 0
*/
uint8_t p_pcr_chip_subsystem_32K_active_sts_get(void);
/** Reads the PCICLK_ACTIVE status bit
* in the Chip Subsystem Power Reset Status Register
* @return 1 if CICLK_ACTIVE bit is set, else 0
*/
uint8_t p_pcr_chip_subsystem_pciclk_active_sts_get(void);
/* ---------------------------------------------------------------------- */
/* Peripheral Function - Functions for Power Reset Control Register */
/* ---------------------------------------------------------------------- */
/** Reads the iRESET_OUT bit in the Power Reset Control Register
* @return 1 if iRESET_OUT bit is set, else 0
*/
uint8_t p_pcr_iReset_Out_get(void);
/** Sets/Clears the iRESET_OUT bit in the Power Reset Control Register
* @param 1 Set iRESET_OUT bit; 0 - Clear the bit
*/
void p_pcr_iReset_Out(uint8_t set_clr_flag);
#endif // #ifndef _PCR_H
/* end pcr.h */
/** @}
*/

View File

@ -1,133 +1,133 @@
/*****************************************************************************
* © 2015 Microchip Technology Inc. and its subsidiaries.
* You may use this software and any derivatives exclusively with
* Microchip products.
* THIS SOFTWARE IS SUPPLIED BY MICROCHIP "AS IS".
* NO WARRANTIES, WHETHER EXPRESS, IMPLIED OR STATUTORY, APPLY TO THIS SOFTWARE,
* INCLUDING ANY IMPLIED WARRANTIES OF NON-INFRINGEMENT, MERCHANTABILITY,
* AND FITNESS FOR A PARTICULAR PURPOSE, OR ITS INTERACTION WITH MICROCHIP
* PRODUCTS, COMBINATION WITH ANY OTHER PRODUCTS, OR USE IN ANY APPLICATION.
* IN NO EVENT WILL MICROCHIP BE LIABLE FOR ANY INDIRECT, SPECIAL, PUNITIVE,
* INCIDENTAL OR CONSEQUENTIAL LOSS, DAMAGE, COST OR EXPENSE OF ANY KIND
* WHATSOEVER RELATED TO THE SOFTWARE, HOWEVER CAUSED, EVEN IF MICROCHIP HAS
* BEEN ADVISED OF THE POSSIBILITY OR THE DAMAGES ARE FORESEEABLE.
* TO THE FULLEST EXTENT ALLOWED BY LAW, MICROCHIP'S TOTAL LIABILITY ON ALL
* CLAIMS IN ANY WAY RELATED TO THIS SOFTWARE WILL NOT EXCEED THE AMOUNT OF
* FEES, IF ANY, THAT YOU HAVE PAID DIRECTLY TO MICROCHIP FOR THIS SOFTWARE.
* MICROCHIP PROVIDES THIS SOFTWARE CONDITIONALLY UPON YOUR ACCEPTANCE
* OF THESE TERMS.
******************************************************************************
Version Control Information (Perforce)
******************************************************************************
$Revision: #1 $
$DateTime: 2015/11/24 06:28:28 $
$Author: amohandas $
Last Change: Updated for tabs
******************************************************************************/
/** @file pcr_api.c
* \brief Power, Clocks, and Resets API Source file
* \author jvasanth
*
* This file implements the PCR APIs
******************************************************************************/
/** @defgroup PCR
* @{
*/
#include "common_lib.h"
#include "pcr.h"
/* ------------------------------------------------------------------------------- */
/* Functions to program Sleep Enable, CLK Reqd Status, Reset Enable for a block */
/* ------------------------------------------------------------------------------- */
/** Sets or Clears block specific bit in PCR Sleep Enable Register
* @param pcr_block_id - pcr block id encoded using PCRx_REGS_BIT
* @param set_clr_flag - Flag to set (1) or clear (0) bit in the PCR Sleep Enable Register
*/
void pcr_sleep_enable(uint32_t pcr_block_id, uint8_t set_clr_flag)
{
uint32_t bit_mask;
uint8_t pcr_reg_id;
bit_mask = 1UL<<(pcr_block_id & 0xFFu);
pcr_reg_id = (uint8_t)((pcr_block_id >> PCRx_REGS_POS_SLEEP_ENABLE) & 0xFFu);
p_pcr_reg_update(pcr_reg_id, bit_mask, set_clr_flag);
}
/** Get Clock Required Status for the block
* @param pcr_block_id - pcr block id encoded using PCRx_REGS_BIT
* @return uint8_t - 1 if Clock Required Status set, else 0
*/
uint8_t pcr_clock_reqd_status_get(uint32_t pcr_block_id)
{
uint32_t bit_mask;
uint8_t pcr_reg_id, retVal;
bit_mask = 1UL<<(pcr_block_id & 0xFFu);
pcr_reg_id = (uint8_t)((pcr_block_id >> PCRx_REGS_POS_CLK_REQD_STS) & 0xFFu);
retVal = 0;
if (p_pcr_reg_get(pcr_reg_id, bit_mask))
{
retVal = 1;
}
return retVal;
}
/** Sets or Clears Reset Enable register bit for the block
* @param pcr_block_id - pcr block id encoded using PCRx_REGS_BIT
* @param set_clr_flag - Flag to set (1) or clear (0) bit in the PCR Reset Enable Register
*/
void pcr_reset_enable(uint32_t pcr_block_id, uint8_t set_clr_flag)
{
uint32_t bit_mask;
uint8_t pcr_reg_id;
bit_mask = 1UL<<(pcr_block_id & 0xFFu);
pcr_reg_id = (uint8_t)((pcr_block_id >> PCRx_REGS_POS_RESET_ENABLE) & 0xFFu);
p_pcr_reg_update(pcr_reg_id, bit_mask, set_clr_flag);
}
/* ------------------------------------------------------------------------------- */
/* Functions for entering low power modes */
/* ------------------------------------------------------------------------------- */
/** Instructs all blocks to sleep by setting the Sleep Enable bits */
void pcr_all_blocks_sleep(void)
{
p_pcr_reg_write(PCR_REG_CHIP_SLEEP_ENABLE, 0xFFFFFFFF);
p_pcr_reg_write(PCR_REG_EC_SLEEP_ENABLE, 0xFFFFFFFF);
p_pcr_reg_write(PCR_REG_HOST_SLEEP_ENABLE, 0xFFFFFFFF);
p_pcr_reg_write(PCR_REG_EC_SLEEP_ENABLE_2, 0xFFFFFFFF);
}
/** Clears the Sleep Enable bits for all blocks */
void pcr_all_blocks_wake(void)
{
p_pcr_reg_write(PCR_REG_CHIP_SLEEP_ENABLE, 0);
p_pcr_reg_write(PCR_REG_EC_SLEEP_ENABLE, 0);
p_pcr_reg_write(PCR_REG_HOST_SLEEP_ENABLE, 0);
p_pcr_reg_write(PCR_REG_EC_SLEEP_ENABLE_2, 0);
}
/** Programs required sleep mode in System Sleep Control Register
* @param sleep_mode - see enum SYSTEM_SLEEP_MODES
*/
void pcr_system_sleep(uint8_t sleep_mode)
{
p_pcr_system_sleep_ctrl_write(sleep_mode);
}
/* end pcr_api.c */
/** @}
*/
/*****************************************************************************
* © 2015 Microchip Technology Inc. and its subsidiaries.
* You may use this software and any derivatives exclusively with
* Microchip products.
* THIS SOFTWARE IS SUPPLIED BY MICROCHIP "AS IS".
* NO WARRANTIES, WHETHER EXPRESS, IMPLIED OR STATUTORY, APPLY TO THIS SOFTWARE,
* INCLUDING ANY IMPLIED WARRANTIES OF NON-INFRINGEMENT, MERCHANTABILITY,
* AND FITNESS FOR A PARTICULAR PURPOSE, OR ITS INTERACTION WITH MICROCHIP
* PRODUCTS, COMBINATION WITH ANY OTHER PRODUCTS, OR USE IN ANY APPLICATION.
* IN NO EVENT WILL MICROCHIP BE LIABLE FOR ANY INDIRECT, SPECIAL, PUNITIVE,
* INCIDENTAL OR CONSEQUENTIAL LOSS, DAMAGE, COST OR EXPENSE OF ANY KIND
* WHATSOEVER RELATED TO THE SOFTWARE, HOWEVER CAUSED, EVEN IF MICROCHIP HAS
* BEEN ADVISED OF THE POSSIBILITY OR THE DAMAGES ARE FORESEEABLE.
* TO THE FULLEST EXTENT ALLOWED BY LAW, MICROCHIP'S TOTAL LIABILITY ON ALL
* CLAIMS IN ANY WAY RELATED TO THIS SOFTWARE WILL NOT EXCEED THE AMOUNT OF
* FEES, IF ANY, THAT YOU HAVE PAID DIRECTLY TO MICROCHIP FOR THIS SOFTWARE.
* MICROCHIP PROVIDES THIS SOFTWARE CONDITIONALLY UPON YOUR ACCEPTANCE
* OF THESE TERMS.
******************************************************************************
Version Control Information (Perforce)
******************************************************************************
$Revision: #1 $
$DateTime: 2016/04/08 10:18:28 $
$Author: pramans $
Last Change: Updated for tabs
******************************************************************************/
/** @file pcr_api.c
* \brief Power, Clocks, and Resets API Source file
* \author jvasanth
*
* This file implements the PCR APIs
******************************************************************************/
/** @defgroup PCR
* @{
*/
#include "common_lib.h"
#include "pcr.h"
/* ------------------------------------------------------------------------------- */
/* Functions to program Sleep Enable, CLK Reqd Status, Reset Enable for a block */
/* ------------------------------------------------------------------------------- */
/** Sets or Clears block specific bit in PCR Sleep Enable Register
* @param pcr_block_id - pcr block id encoded using PCRx_REGS_BIT
* @param set_clr_flag - Flag to set (1) or clear (0) bit in the PCR Sleep Enable Register
*/
void pcr_sleep_enable(uint32_t pcr_block_id, uint8_t set_clr_flag)
{
uint32_t bit_mask;
uint8_t pcr_reg_id;
bit_mask = 1UL<<(pcr_block_id & 0xFFu);
pcr_reg_id = (uint8_t)((pcr_block_id >> PCRx_REGS_POS_SLEEP_ENABLE) & 0xFFu);
p_pcr_reg_update(pcr_reg_id, bit_mask, set_clr_flag);
}
/** Get Clock Required Status for the block
* @param pcr_block_id - pcr block id encoded using PCRx_REGS_BIT
* @return uint8_t - 1 if Clock Required Status set, else 0
*/
uint8_t pcr_clock_reqd_status_get(uint32_t pcr_block_id)
{
uint32_t bit_mask;
uint8_t pcr_reg_id, retVal;
bit_mask = 1UL<<(pcr_block_id & 0xFFu);
pcr_reg_id = (uint8_t)((pcr_block_id >> PCRx_REGS_POS_CLK_REQD_STS) & 0xFFu);
retVal = 0;
if (p_pcr_reg_get(pcr_reg_id, bit_mask))
{
retVal = 1;
}
return retVal;
}
/** Sets or Clears Reset Enable register bit for the block
* @param pcr_block_id - pcr block id encoded using PCRx_REGS_BIT
* @param set_clr_flag - Flag to set (1) or clear (0) bit in the PCR Reset Enable Register
*/
void pcr_reset_enable(uint32_t pcr_block_id, uint8_t set_clr_flag)
{
uint32_t bit_mask;
uint8_t pcr_reg_id;
bit_mask = 1UL<<(pcr_block_id & 0xFFu);
pcr_reg_id = (uint8_t)((pcr_block_id >> PCRx_REGS_POS_RESET_ENABLE) & 0xFFu);
p_pcr_reg_update(pcr_reg_id, bit_mask, set_clr_flag);
}
/* ------------------------------------------------------------------------------- */
/* Functions for entering low power modes */
/* ------------------------------------------------------------------------------- */
/** Instructs all blocks to sleep by setting the Sleep Enable bits */
void pcr_all_blocks_sleep(void)
{
p_pcr_reg_write(PCR_REG_CHIP_SLEEP_ENABLE, 0xFFFFFFFF);
p_pcr_reg_write(PCR_REG_EC_SLEEP_ENABLE, 0xFFFFFFFF);
p_pcr_reg_write(PCR_REG_HOST_SLEEP_ENABLE, 0xFFFFFFFF);
p_pcr_reg_write(PCR_REG_EC_SLEEP_ENABLE_2, 0xFFFFFFFF);
}
/** Clears the Sleep Enable bits for all blocks */
void pcr_all_blocks_wake(void)
{
p_pcr_reg_write(PCR_REG_CHIP_SLEEP_ENABLE, 0);
p_pcr_reg_write(PCR_REG_EC_SLEEP_ENABLE, 0);
p_pcr_reg_write(PCR_REG_HOST_SLEEP_ENABLE, 0);
p_pcr_reg_write(PCR_REG_EC_SLEEP_ENABLE_2, 0);
}
/** Programs required sleep mode in System Sleep Control Register
* @param sleep_mode - see enum SYSTEM_SLEEP_MODES
*/
void pcr_system_sleep(uint8_t sleep_mode)
{
p_pcr_system_sleep_ctrl_write(sleep_mode);
}
/* end pcr_api.c */
/** @}
*/

View File

@ -1,490 +1,490 @@
/*****************************************************************************
* © 2015 Microchip Technology Inc. and its subsidiaries.
* You may use this software and any derivatives exclusively with
* Microchip products.
* THIS SOFTWARE IS SUPPLIED BY MICROCHIP "AS IS".
* NO WARRANTIES, WHETHER EXPRESS, IMPLIED OR STATUTORY, APPLY TO THIS SOFTWARE,
* INCLUDING ANY IMPLIED WARRANTIES OF NON-INFRINGEMENT, MERCHANTABILITY,
* AND FITNESS FOR A PARTICULAR PURPOSE, OR ITS INTERACTION WITH MICROCHIP
* PRODUCTS, COMBINATION WITH ANY OTHER PRODUCTS, OR USE IN ANY APPLICATION.
* IN NO EVENT WILL MICROCHIP BE LIABLE FOR ANY INDIRECT, SPECIAL, PUNITIVE,
* INCIDENTAL OR CONSEQUENTIAL LOSS, DAMAGE, COST OR EXPENSE OF ANY KIND
* WHATSOEVER RELATED TO THE SOFTWARE, HOWEVER CAUSED, EVEN IF MICROCHIP HAS
* BEEN ADVISED OF THE POSSIBILITY OR THE DAMAGES ARE FORESEEABLE.
* TO THE FULLEST EXTENT ALLOWED BY LAW, MICROCHIP'S TOTAL LIABILITY ON ALL
* CLAIMS IN ANY WAY RELATED TO THIS SOFTWARE WILL NOT EXCEED THE AMOUNT OF
* FEES, IF ANY, THAT YOU HAVE PAID DIRECTLY TO MICROCHIP FOR THIS SOFTWARE.
* MICROCHIP PROVIDES THIS SOFTWARE CONDITIONALLY UPON YOUR ACCEPTANCE
* OF THESE TERMS.
******************************************************************************
Version Control Information (Perforce)
******************************************************************************
$Revision: #1 $
$DateTime: 2015/11/24 06:28:28 $
$Author: amohandas $
Last Change: Updated for tabs
******************************************************************************/
/** @file pcr_perphl.c
* \brief Power, Clocks, and Resets Peripheral Source file
* \author jvasanth
*
* This file implements the PCR Peripheral functions
******************************************************************************/
/** @defgroup PCR
* @{
*/
#include "common_lib.h"
#include "pcr.h"
/* ---------------------------------------------------------------------- */
/* Generic functions to program and read 32-bit values from PCR Registers */
/* ---------------------------------------------------------------------- */
/** Writes 32-bit value in the PCR Register
* @param pcr_reg_id - pcr register id
* @param value - 32-bit value
*/
void p_pcr_reg_write(uint8_t pcr_reg_id, uint32_t value)
{
__IO uint32_t *pPCR_Reg;
pPCR_Reg = (uint32_t *)(PCR_BASE);
pPCR_Reg += pcr_reg_id;
*pPCR_Reg = value;
}
/** Reads 32-bit value from the PCR Register
* @param pcr_reg_id - pcr register id
* @return value - 32-bit value
*/
uint32_t p_pcr_reg_read(uint8_t pcr_reg_id)
{
__IO uint32_t *pPCR_Reg;
uint32_t retVal;
pPCR_Reg = (uint32_t *)(PCR_BASE);
pPCR_Reg += pcr_reg_id;
retVal = *pPCR_Reg;
return retVal;
}
/* ---------------------------------------------------------------------- */
/* Functions to set, clr and get bits in PCR Registers */
/* ---------------------------------------------------------------------- */
/** Sets bits in a PCR Register
* @param pcr_reg_id - pcr register id
* @param bit_mask - Bit mask of bits to set
*/
void p_pcr_reg_set(uint8_t pcr_reg_id, uint32_t bit_mask)
{
__IO uint32_t *pPCR_Reg;
pPCR_Reg = (uint32_t *)(PCR_BASE);
pPCR_Reg += pcr_reg_id;
*pPCR_Reg |= bit_mask;
}
/** Clears bits in a PCR Register
* @param pcr_reg_id - pcr register id
* @param bit_mask - Bit mask of bits to clear
*/
void p_pcr_reg_clr(uint8_t pcr_reg_id, uint32_t bit_mask)
{
__IO uint32_t *pPCR_Reg;
pPCR_Reg = (uint32_t *)(PCR_BASE);
pPCR_Reg += pcr_reg_id;
*pPCR_Reg &= ~bit_mask;
}
/** Read bits in a PCR Register
* @param pcr_reg_id - pcr register id
* @param bit_mask - Bit mask of bits to read
* @return value - 32-bit value
*/
uint32_t p_pcr_reg_get(uint8_t pcr_reg_id, uint32_t bit_mask)
{
__IO uint32_t *pPCR_Reg;
uint32_t retVal;
pPCR_Reg = (uint32_t *)(PCR_BASE);
pPCR_Reg += pcr_reg_id;
retVal = (*pPCR_Reg) & bit_mask;
return retVal;
}
/** Sets or Clears bits in a PCR Register - Helper Function
* @param pcr_reg_id - pcr register id
* @param bit_mask - Bit mask of bits to set or clear
* @param set_clr_flag - Flag to set (1) or clear (0) bits in the PCR Register
*/
void p_pcr_reg_update(uint8_t pcr_reg_id, uint32_t bit_mask, uint8_t set_clr_flag)
{
if (set_clr_flag)
{
p_pcr_reg_set(pcr_reg_id, bit_mask);
}
else
{
p_pcr_reg_clr(pcr_reg_id, bit_mask);
}
}
/* ---------------------------------------------------------------------- */
/* Functions to operate on System Sleep Control Register */
/* ---------------------------------------------------------------------- */
/**
* Sets/Clears the Ring oscillator power down bit
* in System Sleep Control Register
* @param set_clr_flag - 1 - Sets the bit, 0 - clears the bit
*/
void p_pcr_system_sleep_ctrl_ring_osc_power_down(uint8_t set_clr_flag)
{
__IO uint32_t *pPCR_Reg;
pPCR_Reg = (uint32_t *)(PCR_BASE) + PCR_REG_SYSTEM_SLEEP_CTRL;
if (set_clr_flag)
{
*pPCR_Reg |= PCR_SYS_SLP_CTRL_RING_OSC_PWR_DOWN_BITMASK;
}
else
{
*pPCR_Reg &= ~PCR_SYS_SLP_CTRL_RING_OSC_PWR_DOWN_BITMASK;
}
}
/** Sets/Clears the Ring oscillator output gate bit
* in System Sleep Control Register
* @param set_clr_flag - 1 - Sets the bit, 0 - clears the bit
*/
void p_pcr_system_sleep_ctrl_ring_osc_output_gate(uint8_t set_clr_flag)
{
__IO uint32_t *pPCR_Reg;
pPCR_Reg = (uint32_t *)(PCR_BASE) + PCR_REG_SYSTEM_SLEEP_CTRL;
if (set_clr_flag)
{
*pPCR_Reg |= PCR_SYS_SLP_CTRL_RING_OSC_OUTPUT_GATE_BITMASK;
}
else
{
*pPCR_Reg &= ~PCR_SYS_SLP_CTRL_RING_OSC_OUTPUT_GATE_BITMASK;
}
}
/** Sets/Clears the Core regulator standby bit
* in System Sleep Control Register
* @param set_clr_flag - 1 - Sets the bit, 0 - clears the bit
*/
void p_pcr_system_sleep_ctrl_core_regulator_stdby(uint8_t set_clr_flag)
{
__IO uint32_t *pPCR_Reg;
pPCR_Reg = (uint32_t *)(PCR_BASE) + PCR_REG_SYSTEM_SLEEP_CTRL;
if (set_clr_flag)
{
*pPCR_Reg |= PCR_SYS_SLP_CTRL_CORE_REGLTOR_STDBY_BITMASK;
}
else
{
*pPCR_Reg &= ~PCR_SYS_SLP_CTRL_CORE_REGLTOR_STDBY_BITMASK;
}
}
/** Writes required sleep mode in System Sleep Control Register
* @param sleep_value - System Sleep control value - [D2, D1, D0]
*/
void p_pcr_system_sleep_ctrl_write(uint8_t sleep_value)
{
__IO uint32_t *pPCR_Reg;
pPCR_Reg = (uint32_t *)(PCR_BASE) + PCR_REG_SYSTEM_SLEEP_CTRL;
*pPCR_Reg = (sleep_value & 0x7);
}
/** Reads the System Sleep Control PCR Register
* @return value - byte 0 of the system sleep control PCR register
*/
uint8_t p_pcr_system_sleep_ctrl_read(void)
{
__IO uint32_t *pPCR_Reg;
uint8_t retVal;
pPCR_Reg = (uint32_t *)(PCR_BASE) + PCR_REG_SYSTEM_SLEEP_CTRL;
retVal = (uint8_t)((*pPCR_Reg) & 0xFF);
return retVal;
}
/* ---------------------------------------------------------------------- */
/* Function to program to CLK Divide Value */
/* ---------------------------------------------------------------------- */
/** Writes the clock divide value in the Processor Clock Control Register
* @param clk_divide_value - clk divide values, valid values in enum PROCESSOR_CLK_DIVIDE_VALUE
*/
void p_pcr_processor_clk_ctrl_write(uint8_t clk_divide_value)
{
__IO uint32_t *pPCR_Reg;
pPCR_Reg = (uint32_t *)(PCR_BASE) + PCR_REG_PROCESSOR_CLK_CTRL;
*pPCR_Reg = (clk_divide_value & 0xFF);
}
/* ---------------------------------------------------------------------- */
/* Function to program the slow clock divide value */
/* ---------------------------------------------------------------------- */
/** Write the slow clock divide value in the Slow Clock Control Register
* @param slow_clk_divide_value - slow clk divide value
*/
void p_pcr_slow_clk_ctrl_write(uint8_t slow_clk_divide_value)
{
__IO uint32_t *pPCR_Reg;
pPCR_Reg = (uint32_t *)(PCR_BASE) + PCR_REG_SLOW_CLK_CTRL;
*pPCR_Reg = (slow_clk_divide_value & 0x3FF);
}
/* ---------------------------------------------------------------------- */
/* Function to read the Oscillator Lock Status */
/* ---------------------------------------------------------------------- */
/** Reads the Oscillator Lock status bit in the Oscillator ID Register
* @return 1 if Oscillator Lock Status bit is set, else 0
*/
uint8_t p_pcr_oscillator_lock_sts_get(void)
{
__IO uint32_t *pPCR_Reg;
uint8_t retVal;
pPCR_Reg = (uint32_t *)(PCR_BASE) + PCR_REG_OSCILLATOR_ID;
retVal = 0;
if (*pPCR_Reg & PCR_OSCILLATOR_LOCK_STATUS_BITMASK)
{
retVal = 1;
}
return retVal;
}
/* ---------------------------------------------------------------------- */
/* Functions to read various power status in Chip Sub-System register */
/* ---------------------------------------------------------------------- */
/** Reads the VCC Reset Status bit
* in the Chip Subsystem Power Reset Status Register
* @return 1 if VCC Reset Status bit is set, else 0
*/
uint8_t p_pcr_chip_subsystem_vcc_reset_sts_get(void)
{
__IO uint32_t *pPCR_Reg;
uint8_t retVal;
pPCR_Reg = (uint32_t *)(PCR_BASE) + PCR_REG_CHIP_SUBSYSTEM_PWR_RESET_STS;
retVal = 0;
if (*pPCR_Reg & PCR_CHIP_SUBSYSTEM_VCC_RESET_STS_BITMASK)
{
retVal = 1;
}
return retVal;
}
/** Reads the SIO Reset Status bit
* in the Chip Subsystem Power Reset Status Register
* @return 1 if SIO Reset Status bit is set, else 0
*/
uint8_t p_pcr_chip_subsystem_sio_reset_sts_get(void)
{
__IO uint32_t *pPCR_Reg;
uint8_t retVal;
pPCR_Reg = (uint32_t *)(PCR_BASE) + PCR_REG_CHIP_SUBSYSTEM_PWR_RESET_STS;
retVal = 0;
if (*pPCR_Reg & PCR_CHIP_SUBSYSTEM_SIO_RESET_STS_BITMASK)
{
retVal = 1;
}
return retVal;
}
/** Reads the VBAT Reset Status bit
* in the Chip Subsystem Power Reset Status Register
* @return 1 if VBAT Reset Status bit is set, else 0
*/
uint8_t p_pcr_chip_subsystem_vbat_reset_sts_get(void)
{
__IO uint32_t *pPCR_Reg;
uint8_t retVal;
pPCR_Reg = (uint32_t *)(PCR_BASE) + PCR_REG_CHIP_SUBSYSTEM_PWR_RESET_STS;
retVal = 0;
if (*pPCR_Reg & PCR_CHIP_SUBSYSTEM_VBAT_RESET_STS_BITMASK)
{
retVal = 1;
}
return retVal;
}
/** Clears the VBAT Reset Status bit
* in the Chip Subsystem Power Reset Status Register
*/
void p_pcr_chip_subsystem_vbat_reset_sts_clr(void)
{
__IO uint32_t *pPCR_Reg;
pPCR_Reg = (uint32_t *)(PCR_BASE) + PCR_REG_CHIP_SUBSYSTEM_PWR_RESET_STS;
// Write to clear
*pPCR_Reg = PCR_CHIP_SUBSYSTEM_VBAT_RESET_STS_BITMASK;
}
/** Reads the VCC1 Reset Status bit
* in the Chip Subsystem Power Reset Status Register
* @return 1 if VCC1 Reset Status bit is set, else 0
*/
uint8_t p_pcr_chip_subsystem_vcc1_reset_sts_get(void)
{
__IO uint32_t *pPCR_Reg;
uint8_t retVal;
pPCR_Reg = (uint32_t *)(PCR_BASE) + PCR_REG_CHIP_SUBSYSTEM_PWR_RESET_STS;
retVal = 0;
if (*pPCR_Reg & PCR_CHIP_SUBSYSTEM_VCC1_RESET_STS_BITMASK)
{
retVal = 1;
}
return retVal;
}
/** Clears the VCC1 Reset Status bit
* in the Chip Subsystem Power Reset Status Register
*/
void p_pcr_chip_subsystem_vcc1_reset_sts_clr(void)
{
__IO uint32_t *pPCR_Reg;
pPCR_Reg = (uint32_t *)(PCR_BASE) + PCR_REG_CHIP_SUBSYSTEM_PWR_RESET_STS;
// Write to clear
*pPCR_Reg = PCR_CHIP_SUBSYSTEM_VCC1_RESET_STS_BITMASK;
}
/** Reads the 32K_ACTIVE status bit
* in the Chip Subsystem Power Reset Status Register
* @return 1 if 32_ACTIVE bit is set, else 0
*/
uint8_t p_pcr_chip_subsystem_32K_active_sts_get(void)
{
__IO uint32_t *pPCR_Reg;
uint8_t retVal;
pPCR_Reg = (uint32_t *)(PCR_BASE) + PCR_REG_CHIP_SUBSYSTEM_PWR_RESET_STS;
retVal = 0;
if (*pPCR_Reg & PCR_CHIP_SUBSYSTEM_32K_ACTIVE_STS_BITMASK)
{
retVal = 1;
}
return retVal;
}
/** Reads the PCICLK_ACTIVE status bit
* in the Chip Subsystem Power Reset Status Register
* @return 1 if CICLK_ACTIVE bit is set, else 0
*/
uint8_t p_pcr_chip_subsystem_pciclk_active_sts_get(void)
{
__IO uint32_t *pPCR_Reg;
uint8_t retVal;
pPCR_Reg = (uint32_t *)(PCR_BASE) + PCR_REG_CHIP_SUBSYSTEM_PWR_RESET_STS;
retVal = 0;
if (*pPCR_Reg & PCR_CHIP_SUBSYSTEM_PCICLK_ACTIVE_STS_BITMASK)
{
retVal = 1;
}
return retVal;
}
/* ---------------------------------------------------------------------- */
/* Functions for Power Reset Control Register */
/* ---------------------------------------------------------------------- */
/** Reads the iRESET_OUT bit in the Power Reset Control Register
* @return 1 if iRESET_OUT bit is set, else 0
*/
uint8_t p_pcr_iReset_Out_get(void)
{
__IO uint32_t *pPCR_Reg;
uint8_t retVal;
pPCR_Reg = (uint32_t *)(PCR_BASE) + PCR_REG_PWR_RESET_CTRL;
retVal = 0;
if (*pPCR_Reg & PCR_iRESET_OUT_BITMASK)
{
retVal = 1;
}
return retVal;
}
/** Sets/Clears the iRESET_OUT bit in the Power Reset Control Register
* @param 1 Set iRESET_OUT bit; 0 - Clear the bit
*/
void p_pcr_iReset_Out(uint8_t set_clr_flag)
{
__IO uint32_t *pPCR_Reg;
pPCR_Reg = (uint32_t *)(PCR_BASE) + PCR_REG_PWR_RESET_CTRL;
*pPCR_Reg = (set_clr_flag & 0x1);
}
/* end pcr_perphl.c */
/** @}
*/
/*****************************************************************************
* © 2015 Microchip Technology Inc. and its subsidiaries.
* You may use this software and any derivatives exclusively with
* Microchip products.
* THIS SOFTWARE IS SUPPLIED BY MICROCHIP "AS IS".
* NO WARRANTIES, WHETHER EXPRESS, IMPLIED OR STATUTORY, APPLY TO THIS SOFTWARE,
* INCLUDING ANY IMPLIED WARRANTIES OF NON-INFRINGEMENT, MERCHANTABILITY,
* AND FITNESS FOR A PARTICULAR PURPOSE, OR ITS INTERACTION WITH MICROCHIP
* PRODUCTS, COMBINATION WITH ANY OTHER PRODUCTS, OR USE IN ANY APPLICATION.
* IN NO EVENT WILL MICROCHIP BE LIABLE FOR ANY INDIRECT, SPECIAL, PUNITIVE,
* INCIDENTAL OR CONSEQUENTIAL LOSS, DAMAGE, COST OR EXPENSE OF ANY KIND
* WHATSOEVER RELATED TO THE SOFTWARE, HOWEVER CAUSED, EVEN IF MICROCHIP HAS
* BEEN ADVISED OF THE POSSIBILITY OR THE DAMAGES ARE FORESEEABLE.
* TO THE FULLEST EXTENT ALLOWED BY LAW, MICROCHIP'S TOTAL LIABILITY ON ALL
* CLAIMS IN ANY WAY RELATED TO THIS SOFTWARE WILL NOT EXCEED THE AMOUNT OF
* FEES, IF ANY, THAT YOU HAVE PAID DIRECTLY TO MICROCHIP FOR THIS SOFTWARE.
* MICROCHIP PROVIDES THIS SOFTWARE CONDITIONALLY UPON YOUR ACCEPTANCE
* OF THESE TERMS.
******************************************************************************
Version Control Information (Perforce)
******************************************************************************
$Revision: #1 $
$DateTime: 2016/04/08 10:18:28 $
$Author: pramans $
Last Change: Updated for tabs
******************************************************************************/
/** @file pcr_perphl.c
* \brief Power, Clocks, and Resets Peripheral Source file
* \author jvasanth
*
* This file implements the PCR Peripheral functions
******************************************************************************/
/** @defgroup PCR
* @{
*/
#include "common_lib.h"
#include "pcr.h"
/* ---------------------------------------------------------------------- */
/* Generic functions to program and read 32-bit values from PCR Registers */
/* ---------------------------------------------------------------------- */
/** Writes 32-bit value in the PCR Register
* @param pcr_reg_id - pcr register id
* @param value - 32-bit value
*/
void p_pcr_reg_write(uint8_t pcr_reg_id, uint32_t value)
{
__IO uint32_t *pPCR_Reg;
pPCR_Reg = (uint32_t *)(PCR_BASE);
pPCR_Reg += pcr_reg_id;
*pPCR_Reg = value;
}
/** Reads 32-bit value from the PCR Register
* @param pcr_reg_id - pcr register id
* @return value - 32-bit value
*/
uint32_t p_pcr_reg_read(uint8_t pcr_reg_id)
{
__IO uint32_t *pPCR_Reg;
uint32_t retVal;
pPCR_Reg = (uint32_t *)(PCR_BASE);
pPCR_Reg += pcr_reg_id;
retVal = *pPCR_Reg;
return retVal;
}
/* ---------------------------------------------------------------------- */
/* Functions to set, clr and get bits in PCR Registers */
/* ---------------------------------------------------------------------- */
/** Sets bits in a PCR Register
* @param pcr_reg_id - pcr register id
* @param bit_mask - Bit mask of bits to set
*/
void p_pcr_reg_set(uint8_t pcr_reg_id, uint32_t bit_mask)
{
__IO uint32_t *pPCR_Reg;
pPCR_Reg = (uint32_t *)(PCR_BASE);
pPCR_Reg += pcr_reg_id;
*pPCR_Reg |= bit_mask;
}
/** Clears bits in a PCR Register
* @param pcr_reg_id - pcr register id
* @param bit_mask - Bit mask of bits to clear
*/
void p_pcr_reg_clr(uint8_t pcr_reg_id, uint32_t bit_mask)
{
__IO uint32_t *pPCR_Reg;
pPCR_Reg = (uint32_t *)(PCR_BASE);
pPCR_Reg += pcr_reg_id;
*pPCR_Reg &= ~bit_mask;
}
/** Read bits in a PCR Register
* @param pcr_reg_id - pcr register id
* @param bit_mask - Bit mask of bits to read
* @return value - 32-bit value
*/
uint32_t p_pcr_reg_get(uint8_t pcr_reg_id, uint32_t bit_mask)
{
__IO uint32_t *pPCR_Reg;
uint32_t retVal;
pPCR_Reg = (uint32_t *)(PCR_BASE);
pPCR_Reg += pcr_reg_id;
retVal = (*pPCR_Reg) & bit_mask;
return retVal;
}
/** Sets or Clears bits in a PCR Register - Helper Function
* @param pcr_reg_id - pcr register id
* @param bit_mask - Bit mask of bits to set or clear
* @param set_clr_flag - Flag to set (1) or clear (0) bits in the PCR Register
*/
void p_pcr_reg_update(uint8_t pcr_reg_id, uint32_t bit_mask, uint8_t set_clr_flag)
{
if (set_clr_flag)
{
p_pcr_reg_set(pcr_reg_id, bit_mask);
}
else
{
p_pcr_reg_clr(pcr_reg_id, bit_mask);
}
}
/* ---------------------------------------------------------------------- */
/* Functions to operate on System Sleep Control Register */
/* ---------------------------------------------------------------------- */
/**
* Sets/Clears the Ring oscillator power down bit
* in System Sleep Control Register
* @param set_clr_flag - 1 - Sets the bit, 0 - clears the bit
*/
void p_pcr_system_sleep_ctrl_ring_osc_power_down(uint8_t set_clr_flag)
{
__IO uint32_t *pPCR_Reg;
pPCR_Reg = (uint32_t *)(PCR_BASE) + PCR_REG_SYSTEM_SLEEP_CTRL;
if (set_clr_flag)
{
*pPCR_Reg |= PCR_SYS_SLP_CTRL_RING_OSC_PWR_DOWN_BITMASK;
}
else
{
*pPCR_Reg &= ~PCR_SYS_SLP_CTRL_RING_OSC_PWR_DOWN_BITMASK;
}
}
/** Sets/Clears the Ring oscillator output gate bit
* in System Sleep Control Register
* @param set_clr_flag - 1 - Sets the bit, 0 - clears the bit
*/
void p_pcr_system_sleep_ctrl_ring_osc_output_gate(uint8_t set_clr_flag)
{
__IO uint32_t *pPCR_Reg;
pPCR_Reg = (uint32_t *)(PCR_BASE) + PCR_REG_SYSTEM_SLEEP_CTRL;
if (set_clr_flag)
{
*pPCR_Reg |= PCR_SYS_SLP_CTRL_RING_OSC_OUTPUT_GATE_BITMASK;
}
else
{
*pPCR_Reg &= ~PCR_SYS_SLP_CTRL_RING_OSC_OUTPUT_GATE_BITMASK;
}
}
/** Sets/Clears the Core regulator standby bit
* in System Sleep Control Register
* @param set_clr_flag - 1 - Sets the bit, 0 - clears the bit
*/
void p_pcr_system_sleep_ctrl_core_regulator_stdby(uint8_t set_clr_flag)
{
__IO uint32_t *pPCR_Reg;
pPCR_Reg = (uint32_t *)(PCR_BASE) + PCR_REG_SYSTEM_SLEEP_CTRL;
if (set_clr_flag)
{
*pPCR_Reg |= PCR_SYS_SLP_CTRL_CORE_REGLTOR_STDBY_BITMASK;
}
else
{
*pPCR_Reg &= ~PCR_SYS_SLP_CTRL_CORE_REGLTOR_STDBY_BITMASK;
}
}
/** Writes required sleep mode in System Sleep Control Register
* @param sleep_value - System Sleep control value - [D2, D1, D0]
*/
void p_pcr_system_sleep_ctrl_write(uint8_t sleep_value)
{
__IO uint32_t *pPCR_Reg;
pPCR_Reg = (uint32_t *)(PCR_BASE) + PCR_REG_SYSTEM_SLEEP_CTRL;
*pPCR_Reg = (sleep_value & 0x7);
}
/** Reads the System Sleep Control PCR Register
* @return value - byte 0 of the system sleep control PCR register
*/
uint8_t p_pcr_system_sleep_ctrl_read(void)
{
__IO uint32_t *pPCR_Reg;
uint8_t retVal;
pPCR_Reg = (uint32_t *)(PCR_BASE) + PCR_REG_SYSTEM_SLEEP_CTRL;
retVal = (uint8_t)((*pPCR_Reg) & 0xFF);
return retVal;
}
/* ---------------------------------------------------------------------- */
/* Function to program to CLK Divide Value */
/* ---------------------------------------------------------------------- */
/** Writes the clock divide value in the Processor Clock Control Register
* @param clk_divide_value - clk divide values, valid values in enum PROCESSOR_CLK_DIVIDE_VALUE
*/
void p_pcr_processor_clk_ctrl_write(uint8_t clk_divide_value)
{
__IO uint32_t *pPCR_Reg;
pPCR_Reg = (uint32_t *)(PCR_BASE) + PCR_REG_PROCESSOR_CLK_CTRL;
*pPCR_Reg = (clk_divide_value & 0xFF);
}
/* ---------------------------------------------------------------------- */
/* Function to program the slow clock divide value */
/* ---------------------------------------------------------------------- */
/** Write the slow clock divide value in the Slow Clock Control Register
* @param slow_clk_divide_value - slow clk divide value
*/
void p_pcr_slow_clk_ctrl_write(uint8_t slow_clk_divide_value)
{
__IO uint32_t *pPCR_Reg;
pPCR_Reg = (uint32_t *)(PCR_BASE) + PCR_REG_SLOW_CLK_CTRL;
*pPCR_Reg = (slow_clk_divide_value & 0x3FF);
}
/* ---------------------------------------------------------------------- */
/* Function to read the Oscillator Lock Status */
/* ---------------------------------------------------------------------- */
/** Reads the Oscillator Lock status bit in the Oscillator ID Register
* @return 1 if Oscillator Lock Status bit is set, else 0
*/
uint8_t p_pcr_oscillator_lock_sts_get(void)
{
__IO uint32_t *pPCR_Reg;
uint8_t retVal;
pPCR_Reg = (uint32_t *)(PCR_BASE) + PCR_REG_OSCILLATOR_ID;
retVal = 0;
if (*pPCR_Reg & PCR_OSCILLATOR_LOCK_STATUS_BITMASK)
{
retVal = 1;
}
return retVal;
}
/* ---------------------------------------------------------------------- */
/* Functions to read various power status in Chip Sub-System register */
/* ---------------------------------------------------------------------- */
/** Reads the VCC Reset Status bit
* in the Chip Subsystem Power Reset Status Register
* @return 1 if VCC Reset Status bit is set, else 0
*/
uint8_t p_pcr_chip_subsystem_vcc_reset_sts_get(void)
{
__IO uint32_t *pPCR_Reg;
uint8_t retVal;
pPCR_Reg = (uint32_t *)(PCR_BASE) + PCR_REG_CHIP_SUBSYSTEM_PWR_RESET_STS;
retVal = 0;
if (*pPCR_Reg & PCR_CHIP_SUBSYSTEM_VCC_RESET_STS_BITMASK)
{
retVal = 1;
}
return retVal;
}
/** Reads the SIO Reset Status bit
* in the Chip Subsystem Power Reset Status Register
* @return 1 if SIO Reset Status bit is set, else 0
*/
uint8_t p_pcr_chip_subsystem_sio_reset_sts_get(void)
{
__IO uint32_t *pPCR_Reg;
uint8_t retVal;
pPCR_Reg = (uint32_t *)(PCR_BASE) + PCR_REG_CHIP_SUBSYSTEM_PWR_RESET_STS;
retVal = 0;
if (*pPCR_Reg & PCR_CHIP_SUBSYSTEM_SIO_RESET_STS_BITMASK)
{
retVal = 1;
}
return retVal;
}
/** Reads the VBAT Reset Status bit
* in the Chip Subsystem Power Reset Status Register
* @return 1 if VBAT Reset Status bit is set, else 0
*/
uint8_t p_pcr_chip_subsystem_vbat_reset_sts_get(void)
{
__IO uint32_t *pPCR_Reg;
uint8_t retVal;
pPCR_Reg = (uint32_t *)(PCR_BASE) + PCR_REG_CHIP_SUBSYSTEM_PWR_RESET_STS;
retVal = 0;
if (*pPCR_Reg & PCR_CHIP_SUBSYSTEM_VBAT_RESET_STS_BITMASK)
{
retVal = 1;
}
return retVal;
}
/** Clears the VBAT Reset Status bit
* in the Chip Subsystem Power Reset Status Register
*/
void p_pcr_chip_subsystem_vbat_reset_sts_clr(void)
{
__IO uint32_t *pPCR_Reg;
pPCR_Reg = (uint32_t *)(PCR_BASE) + PCR_REG_CHIP_SUBSYSTEM_PWR_RESET_STS;
// Write to clear
*pPCR_Reg = PCR_CHIP_SUBSYSTEM_VBAT_RESET_STS_BITMASK;
}
/** Reads the VCC1 Reset Status bit
* in the Chip Subsystem Power Reset Status Register
* @return 1 if VCC1 Reset Status bit is set, else 0
*/
uint8_t p_pcr_chip_subsystem_vcc1_reset_sts_get(void)
{
__IO uint32_t *pPCR_Reg;
uint8_t retVal;
pPCR_Reg = (uint32_t *)(PCR_BASE) + PCR_REG_CHIP_SUBSYSTEM_PWR_RESET_STS;
retVal = 0;
if (*pPCR_Reg & PCR_CHIP_SUBSYSTEM_VCC1_RESET_STS_BITMASK)
{
retVal = 1;
}
return retVal;
}
/** Clears the VCC1 Reset Status bit
* in the Chip Subsystem Power Reset Status Register
*/
void p_pcr_chip_subsystem_vcc1_reset_sts_clr(void)
{
__IO uint32_t *pPCR_Reg;
pPCR_Reg = (uint32_t *)(PCR_BASE) + PCR_REG_CHIP_SUBSYSTEM_PWR_RESET_STS;
// Write to clear
*pPCR_Reg = PCR_CHIP_SUBSYSTEM_VCC1_RESET_STS_BITMASK;
}
/** Reads the 32K_ACTIVE status bit
* in the Chip Subsystem Power Reset Status Register
* @return 1 if 32_ACTIVE bit is set, else 0
*/
uint8_t p_pcr_chip_subsystem_32K_active_sts_get(void)
{
__IO uint32_t *pPCR_Reg;
uint8_t retVal;
pPCR_Reg = (uint32_t *)(PCR_BASE) + PCR_REG_CHIP_SUBSYSTEM_PWR_RESET_STS;
retVal = 0;
if (*pPCR_Reg & PCR_CHIP_SUBSYSTEM_32K_ACTIVE_STS_BITMASK)
{
retVal = 1;
}
return retVal;
}
/** Reads the PCICLK_ACTIVE status bit
* in the Chip Subsystem Power Reset Status Register
* @return 1 if CICLK_ACTIVE bit is set, else 0
*/
uint8_t p_pcr_chip_subsystem_pciclk_active_sts_get(void)
{
__IO uint32_t *pPCR_Reg;
uint8_t retVal;
pPCR_Reg = (uint32_t *)(PCR_BASE) + PCR_REG_CHIP_SUBSYSTEM_PWR_RESET_STS;
retVal = 0;
if (*pPCR_Reg & PCR_CHIP_SUBSYSTEM_PCICLK_ACTIVE_STS_BITMASK)
{
retVal = 1;
}
return retVal;
}
/* ---------------------------------------------------------------------- */
/* Functions for Power Reset Control Register */
/* ---------------------------------------------------------------------- */
/** Reads the iRESET_OUT bit in the Power Reset Control Register
* @return 1 if iRESET_OUT bit is set, else 0
*/
uint8_t p_pcr_iReset_Out_get(void)
{
__IO uint32_t *pPCR_Reg;
uint8_t retVal;
pPCR_Reg = (uint32_t *)(PCR_BASE) + PCR_REG_PWR_RESET_CTRL;
retVal = 0;
if (*pPCR_Reg & PCR_iRESET_OUT_BITMASK)
{
retVal = 1;
}
return retVal;
}
/** Sets/Clears the iRESET_OUT bit in the Power Reset Control Register
* @param 1 Set iRESET_OUT bit; 0 - Clear the bit
*/
void p_pcr_iReset_Out(uint8_t set_clr_flag)
{
__IO uint32_t *pPCR_Reg;
pPCR_Reg = (uint32_t *)(PCR_BASE) + PCR_REG_PWR_RESET_CTRL;
*pPCR_Reg = (set_clr_flag & 0x1);
}
/* end pcr_perphl.c */
/** @}
*/

View File

@ -35,10 +35,10 @@
/*******************************************************************************
* SMSC version control information (Perforce):
*
* FILE: $File: //depot_pcs/FWEng/Release/projects/CEC1302_CLIB/release2/Source/hw_blks/common/include/platform.h $
* FILE: $File: //depot_pcs/FWEng/Release/projects/CEC1302_PLIB_CLIB/release5/Source/hw_blks/common/include/platform.h $
* REVISION: $Revision: #1 $
* DATETIME: $DateTime: 2015/12/23 15:37:58 $
* AUTHOR: $Author: akrishnan $
* DATETIME: $DateTime: 2016/04/08 10:18:28 $
* AUTHOR: $Author: pramans $
*
* Revision history (latest first):
* #xx
@ -48,6 +48,12 @@
#ifndef _PLATFORM_H_
#define _PLATFORM_H_
#include <stdint.h>
/* Enable any one of the below flag which enables either Aggregated or Disaggregated Interrupts */
#define DISAGGREGATED_INPT_DEFINED 1
//#define AGGREGATED_INPT_DEFINED 1
/* Platform Configuration PreProcessor Conditions */
#define TOOLKEIL 1
#define TOOLPC 2
@ -132,6 +138,10 @@ typedef signed long INT32;
typedef void VOID;
typedef volatile unsigned char VUINT8;
typedef volatile unsigned short int VUINT16;
typedef volatile unsigned long int VUINT32;
/* union types */
typedef union _BITS_8
{
@ -189,7 +199,7 @@ typedef union _BITS_8
#define FUNC_NEVER_RETURNS
#define BEGIN_SMALL_DATA_BLOCK(x)
#define END_SMALL_DATA_BLOCK()
UINT32 soft_norm(UINT32 val);
uint32_t soft_norm(uint32_t val);
#define NORM(x) soft_norm(x)
//
#define USE_FUNC_REPLACEMENT 0
@ -228,7 +238,7 @@ UINT32 soft_norm(UINT32 val);
#define FUNC_NEVER_RETURNS
#define BEGIN_SMALL_DATA_BLOCK(x)
#define END_SMALL_DATA_BLOCK()
UINT32 soft_norm(UINT32 val);
uint32_t soft_norm(uint32_t val);
#define NORM(x) soft_norm(x)
//
#define USE_FUNC_REPLACEMENT 0
@ -335,7 +345,7 @@ UINT32 soft_norm(UINT32 val);
#else
/* for ARM MDK */
#define FUNC_NEVER_RETURNS
UINT32 soft_norm(UINT32 val);
uint32_t soft_norm(uint32_t val);
#define NORM(x) soft_norm(x)
#endif
#endif