From ad197aab796450a7d27cee6dec2476c037a01bcc Mon Sep 17 00:00:00 2001 From: patacongo Date: Wed, 30 Dec 2009 00:13:31 +0000 Subject: Add clock reset logic git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@2461 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/arch/arm/src/lpc313x/Make.defs | 7 +- nuttx/arch/arm/src/lpc313x/lpc313x_cgudrvr.h | 48 +++++++- nuttx/arch/arm/src/lpc313x/lpc313x_clkexten.c | 152 ++++++++++++++++++++++++++ nuttx/arch/arm/src/lpc313x/lpc313x_defclk.c | 119 ++++++++++++++++++++ nuttx/configs/ea3131/include/board.h | 6 +- 5 files changed, 325 insertions(+), 7 deletions(-) create mode 100755 nuttx/arch/arm/src/lpc313x/lpc313x_clkexten.c create mode 100755 nuttx/arch/arm/src/lpc313x/lpc313x_defclk.c diff --git a/nuttx/arch/arm/src/lpc313x/Make.defs b/nuttx/arch/arm/src/lpc313x/Make.defs index bc3087a29..3b5d975ff 100755 --- a/nuttx/arch/arm/src/lpc313x/Make.defs +++ b/nuttx/arch/arm/src/lpc313x/Make.defs @@ -46,9 +46,10 @@ CMN_CSRCS = up_assert.c up_blocktask.c up_copystate.c up_createstack.c \ up_undefinedinsn.c up_usestack.c CGU_ASRCS = -CGU_CSRCS = lpc313x_bcrndx.c lpc313x_clkdomain.c lpc313x_clkfreq.c \ - lpc313x_esrndx.c lpc313x_fdcndx.c lpc313x_freqin.c \ - lpc313x_pllconfig.c lpc313x_setfreqin.c lpc313x_softreset.c +CGU_CSRCS = lpc313x_bcrndx.c lpc313x_clkdomain.c lpc313x_clkexten.c \ + lpc313x_clkfreq.c lpc313x_defclk.c lpc313x_esrndx.c \ + lpc313x_fdcndx.c lpc313x_freqin.c lpc313x_pllconfig.c \ + lpc313x_resetclks.c lpc313x_setfreqin.c lpc313x_softreset.c CHIP_ASRCS = $(CGU_ASRCS) CHIP_CSRCS = lpc313x_allocateheap.c lpc313x_boot.c lpc313x_irq.c \ diff --git a/nuttx/arch/arm/src/lpc313x/lpc313x_cgudrvr.h b/nuttx/arch/arm/src/lpc313x/lpc313x_cgudrvr.h index 26803f59e..82f26a0be 100755 --- a/nuttx/arch/arm/src/lpc313x/lpc313x_cgudrvr.h +++ b/nuttx/arch/arm/src/lpc313x/lpc313x_cgudrvr.h @@ -45,6 +45,10 @@ ************************************************************************/ #include + +#include +#include + #include "up_arch.h" #include "lpc313x_cgu.h" @@ -170,6 +174,7 @@ #define FRACDIV_BASE11_CNT 0 /* No fractional divider available */ +#define CGU_NFRACDIV 24 /* Number of fractional dividers */ #define FDCNDX_INVALID -1 /* Indicates an invalid fractional * divider index */ @@ -212,7 +217,7 @@ enum lpc313x_clockid_e /* Domain 0: SYS_BASE */ CLKID_APB0CLK = 0, /* 0 APB0_CLK */ - CLKID_SBAPB1CLK, /* 1 APB1_CLK */ + CLKID_APB1CLK, /* 1 APB1_CLK */ CLKID_APB2CLK, /* 2 APB2_CLK */ CLKID_APB3CLK, /* 3 APB3_CLK */ CLKID_APB4CLK, /* 4 APB4_CLK */ @@ -493,6 +498,27 @@ static inline void lpc313x_disableclock(enum lpc313x_clockid_e clkid) * Public Functions ************************************************************************/ +/**************************************************************************** + * Name: lpc313x_defclk + * + * Description: + * Enable the specified clock if it is one of the default clocks needed + * by the board. + * + ****************************************************************************/ + +EXTERN bool lpc313x_defclk(enum lpc313x_clockid_e clkid); + +/**************************************************************************** + * Name: lpc313x_resetclks + * + * Description: + * Put all clocks into a known, initial state + * + ****************************************************************************/ + +EXTERN void lpc313x_resetclks(void); + /**************************************************************************** * Name: lpc313x_pllconfig * @@ -614,6 +640,26 @@ EXTERN void lpc313x_selectfreqin(enum lpc313x_domainid_e dmnid, EXTERN uint32_t lpc313x_clkfreq(enum lpc313x_clockid_e clkid, enum lpc313x_domainid_e dmnid); +/************************************************************************ + * Name: lpc313x_enableexten + * + * Description: + * Enable external enabling for the the specified possible clocks. + * + ************************************************************************/ + +EXTERN void lpc313x_enableexten(enum lpc313x_clockid_e clkid); + +/************************************************************************ + * Name: lpc313x_disableexten + * + * Description: + * Disable external enabling for the the specified possible clocks. + * + ************************************************************************/ + +EXTERN void lpc313x_disableexten(enum lpc313x_clockid_e clkid); + #undef EXTERN #ifdef __cplusplus } diff --git a/nuttx/arch/arm/src/lpc313x/lpc313x_clkexten.c b/nuttx/arch/arm/src/lpc313x/lpc313x_clkexten.c new file mode 100755 index 000000000..20e42a83a --- /dev/null +++ b/nuttx/arch/arm/src/lpc313x/lpc313x_clkexten.c @@ -0,0 +1,152 @@ +/**************************************************************************** + * arch/arm/src/lpc313x/lpc313x_exten.c + * + * Copyright (C) 2009 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include + +#include + +#include "lpc313x_cgudrvr.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: lpc313x_enableexten + * + * Description: + * Enable external enabling for the the specified possible clocks. + * + ****************************************************************************/ + +void lpc313x_enableexten(enum lpc313x_clockid_e clkid) +{ + uint32_t regaddr; + uint32_t regval; + + switch (clkid) + { + case CLKID_DMACLKGATED: /* 9 DMA_CLK_GATED */ + case CLKID_EVENTROUTERPCLK: /* 31 EVENT_ROUTER_PCLK */ + case CLKID_ADCPCLK: /* 32 ADC_PCLK */ + case CLKID_IOCONFPCLK: /* 35 IOCONF_PCLK */ + case CLKID_CGUPCLK: /* 36 CGU_PCLK */ + case CLKID_SYSCREGPCLK: /* 37 SYSCREG_PCLK */ + case CLKID_OTPPCLK: /* 38 OTP_PCLK (Reserved on LPC313X) */ + case CLKID_PWMPCLKREGS: /* 46 PWM_PCLK_REGS */ + case CLKID_PCMAPBPCLK: /* 52 PCM_APB_PCLK */ + case CLKID_SPIPCLKGATED: /* 57 SPI_PCLK_GATED */ + case CLKID_SPICLKGATED: /* 90 SPI_CLK_GATED */ + case CLKID_PCMCLKIP: /* 71 PCM_CLK_IP */ + regaddr = LPC313X_CGU_PCR(clkid); + regval = getreg32(regaddr); + regval |= CGU_PCR_EXTENEN; + putreg32(regval, regaddr); + break; + + /* Otherwise, force disable for the clocks. NOTE that a larger set will + * be disabled than will be enabled. + */ + + default: + lpc313x_disableexten(clkid); + break; + } +} + +/**************************************************************************** + * Name: lpc313x_disableexten + * + * Description: + * Disable external enabling for the the specified possible clocks. + * + ****************************************************************************/ + +void lpc313x_disableexten(enum lpc313x_clockid_e clkid) +{ + uint32_t regaddr; + uint32_t regval; + + switch (clkid) + { + case CLKID_DMACLKGATED: /* 9 DMA_CLK_GATED */ + case CLKID_EVENTROUTERPCLK: /* 31 EVENT_ROUTER_PCLK */ + case CLKID_ADCPCLK: /* 32 ADC_PCLK */ + case CLKID_WDOGPCLK: /* 34 WDOG_PCLK */ + case CLKID_IOCONFPCLK: /* 35 IOCONF_PCLK */ + case CLKID_CGUPCLK: /* 36 CGU_PCLK */ + case CLKID_SYSCREGPCLK: /* 37 SYSCREG_PCLK */ + case CLKID_OTPPCLK: /* 38 OTP_PCLK (Reserved on LPC313X) */ + case CLKID_PWMPCLKREGS: /* 46 PWM_PCLK_REGS */ + case CLKID_I2C0PCLK: /* 48 I2C0_PCLK */ + case CLKID_I2C1PCLK: /* 49 I2C1_PCLK */ + case CLKID_PCMAPBPCLK: /* 52 PCM_APB_PCLK */ + case CLKID_UARTAPBCLK: /* 53 UART_APB_CLK */ + case CLKID_SPIPCLKGATED: /* 57 SPI_PCLK_GATED */ + case CLKID_SPICLKGATED: /* 90 SPI_CLK_GATED */ + case CLKID_PCMCLKIP: /* 71 PCM_CLK_IP */ + case CLKID_LCDPCLK: /* 54 LCD_PCLK */ + regaddr = LPC313X_CGU_PCR(clkid); + regval = getreg32(regaddr); + regval &= ~CGU_PCR_EXTENEN; + putreg32(regval, regaddr); + break; + + default: + break; + } +} diff --git a/nuttx/arch/arm/src/lpc313x/lpc313x_defclk.c b/nuttx/arch/arm/src/lpc313x/lpc313x_defclk.c new file mode 100755 index 000000000..bdef026b5 --- /dev/null +++ b/nuttx/arch/arm/src/lpc313x/lpc313x_defclk.c @@ -0,0 +1,119 @@ +/**************************************************************************** + * arch/arm/src/lpc313x/lpc313x_defclk.c + * + * Copyright (C) 2009 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include + +#include + +#include "lpc313x_cgudrvr.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: lpc313x_defclk + * + * Description: + * Enable the specified clock if it is one of the default clocks needed + * by the board. + * + ****************************************************************************/ + +bool lpc313x_defclk(enum lpc313x_clockid_e clkid) +{ + + uint32_t regaddr; + uint32_t regval; + bool enable; + + /* Check if this clock should be enabled. This is determined by + * 3 bitsets provided by board-specific logic in board/board.h. + */ + + if ((int)clkid < 32) + { + enable = ((BOARD_CLKS_0_31 & (1 << (int)clkid)) != 0); + } + else if ((int)clkid < 64) + { + enable = ((BOARD_CLKS_32_63 & (1 << ((int)clkid - 32))) != 0); + } + else + { + enable = ((BOARD_CLKS_64_92 & (1 << ((int)clkid - 64))) != 0); + } + + /* Then set/clear the RUN bit in the PCR register for this clock + * accordingly. + */ + + regaddr = LPC313X_CGU_PCR((int)clkid); + regval = getreg32(regaddr); + if (enable) + { + regval |= CGU_PCR_RUN; + } + else + { + regval &= ~CGU_PCR_RUN; + } + putreg32(regval, regaddr); + return enable; +} + diff --git a/nuttx/configs/ea3131/include/board.h b/nuttx/configs/ea3131/include/board.h index 8eb6c3aca..eadb7e2a1 100755 --- a/nuttx/configs/ea3131/include/board.h +++ b/nuttx/configs/ea3131/include/board.h @@ -89,13 +89,13 @@ _RBIT(CLKID_APB3CLK,0)|_RBIT(CLKID_APB4CLK,0)|_RBIT(CLKID_AHB2INTCCLK,0)|\ _RBIT(CLKID_AHB0CLK,0)|_RBIT(CLKID_ARM926CORECLK,0)|_RBIT(CLKID_ARM926BUSIFCLK,0)|\ _RBIT(CLKID_ARM926RETIMECLK,0)|_RBIT(CLKID_ISRAM0CLK,0)|_RBIT(CLKID_ISRAM1CLK,0)|\ - _RBIT(CLKID_ISROMCLK,0)|_RBIT(CLKID_INTCCLK,0)|_RBIT(CLKID_AHB2APB0ASYNCPCLK,0)|\ + _RBIT(CLKID_ISROMCLK,0)|_RBIT(CLKID_INTCCLK,0)|_RBIT(CLKID_AHB2APB0PCLK,0)|\ _RBIT(CLKID_EVENTROUTERPCLK,0)|_RBIT(CLKID_CLOCKOUT,0)) #define BOARD_CLKS_32_63 \ (_RBIT(CLKID_IOCONFPCLK,32)|_RBIT(CLKID_CGUPCLK,32)|_RBIT(CLKID_SYSCREGPCLK,32)|\ - _RBIT(CLKID_OTPPCLK,32)|_RBIT(CLKID_AHB2APB1ASYNCPCLK,32)|_RBIT(CLKID_AHB2APB2ASYNCPCLK,32)|\ - _RBIT(CLKID_AHB2APB3ASYNCPCLK,32)|_RBIT(CLKID_EDGEDETPCLK,32)) + _RBIT(CLKID_OTPPCLK,32)|_RBIT(CLKID_AHB2APB1PCLK,32)|_RBIT(CLKID_AHB2APB2PCLK,32)|\ + _RBIT(CLKID_AHB2APB3PCLK,32)|_RBIT(CLKID_EDGEDETPCLK,32)) #define BOARD_CLKS_64_92 \ (0) -- cgit v1.2.3