This thread has been locked.

If you have a related question, please click the "Ask a related question" button in the top right corner. The newly created question will be automatically linked to this question.

L138 PLL Configuration

Other Parts Discussed in Thread: OMAPL138

Hi,

I'm trying to configure the L138 PLL from the DSP at startup.  I've attached the code below.  After configuring it, it never seems to change frequency.  Specifically the EMIF clock.  I'm trying to set it to 100MHz but it stays at 25MHz after I've configured it.

I've even checked using a gel file from one of the forums used for diagnostic.  It says the PLL is setup correctly and should be set to 100MHz.  Do you see anything I may have done wrong.

My configuration code is now based on the "C6000 DSP+ARM Processor Technical Reference Manual" instructions with some additions from a gel file that was provided to me.

Thanks for your help.

Regards,

James McNEill

#define PLL_LOCK_TIME_CNT        2400
#define PLL_STABILIZATION_TIME   2000
#define PLL_RESET_TIME_CNT       200

void Initialize(void)
{
    GIO_Attrs   gioAttrs = GIO_ATTRS;
	Int32       result;
    Int         UartStatus = 0;
    Uint32      cntDACmem=0;
    
    Uint32      temp;
    Uint32      temparray[2048];
    Uint32      FPGA_Ver_Major, FPGA_Ver_Minor, FPGA_Ver_Build;
    
//    Gpio_Params     gpioParams=Gpio_PARAMS;
    
    //-------------------------------------------------
    //  CONFIGURE PIN MUXES
    //-------------------------------------------------
    
	//-- Write Unlock code to the Kick Registers
    SYSCONFIG0->KICK0R = KICK0R_Unlock;
	SYSCONFIG0->KICK1R = KICK1R_Unlock;

    //-- Setup Pin Muxes
    //-- Setup EMFA, UART2, MMCSD0, Inerrupt GPIOs
    SYSCONFIG0->PINMUX0 = PINMUX0_VALUE;
    SYSCONFIG0->PINMUX1 = PINMUX1_VALUE;
    SYSCONFIG0->PINMUX2 = PINMUX2_VALUE;
    SYSCONFIG0->PINMUX3 = PINMUX3_VALUE;
    SYSCONFIG0->PINMUX4 = PINMUX4_VALUE;
    SYSCONFIG0->PINMUX5 = PINMUX5_VALUE;
    SYSCONFIG0->PINMUX6 = PINMUX6_VALUE;
    SYSCONFIG0->PINMUX7 = PINMUX7_VALUE;
    SYSCONFIG0->PINMUX8 = PINMUX8_VALUE;
    SYSCONFIG0->PINMUX9 = PINMUX9_VALUE;
    SYSCONFIG0->PINMUX10 = PINMUX10_VALUE;
    SYSCONFIG0->PINMUX11 = PINMUX11_VALUE;
    SYSCONFIG0->PINMUX12 = PINMUX12_VALUE;
    SYSCONFIG0->PINMUX13 = PINMUX13_VALUE;
    SYSCONFIG0->PINMUX14 = PINMUX14_VALUE;
    SYSCONFIG0->PINMUX15 = PINMUX15_VALUE;
    SYSCONFIG0->PINMUX16 = PINMUX16_VALUE;
    SYSCONFIG0->PINMUX17 = PINMUX17_VALUE;
    SYSCONFIG0->PINMUX18 = PINMUX18_VALUE;
    SYSCONFIG0->PINMUX19 = PINMUX19_VALUE;
    
    //--------------------------------------
    //  Configure the PLLs
    //--------------------------------------
    printf("SETTING UP THE PLLs");
    //-- Clear the PLL register lock
    
    //SYSCONFIG0->CFGCHIP0 &= ~(0x00000010);
    SYSCONFIG0->CFGCHIP0 &= ~CSL_SYSCFG_CFGCHIP0_PLL_MASTER_LOCK_MASK;
    SYSCONFIG0->CFGCHIP3 &= ~CSL_SYSCFG_CFGCHIP3_PLL1_MASTER_LOCK_MASK;
    
    //-- Program the PLL mode bit to internal Oscillator.
    PLL_regs->PLLCTL &= ~CSL_PLLC_PLLCTL_CLKMODE_MASK;
    
    //-- Clear the PLLENSRC bit 
    PLL_regs->PLLCTL &= ~CSL_PLLC_PLLCTL_PLLENSRC_MASK;
    
    //-- Set External source to internal oscillator
    PLL_regs->PLLCTL &= ~CSL_PLLC_PLLCTL_EXTCLKSRC_MASK;
    
    //-- Set the PLLEN to '0'
    PLL_regs->PLLCTL &= ~CSL_PLLC_PLLCTL_PLLEN_MASK;
    
    //-- Wait 5 cycles for PLLEN to take affect
    for(temp=0; temp<4; temp++) {;}
    
    //-- Clear the PLL reset bit
    PLL_regs->PLLCTL &= ~CSL_PLLC_PLLCTL_PLLRST_MASK;
    
    //-- Disable the PLL output
    PLL_regs->PLLCTL |= CSL_PLLC_PLLCTL_PLLDIS_MASK;
    
    //-- Clear the PLL power down bit
    PLL_regs->PLLCTL &= ~CSL_PLLC_PLLCTL_PLLPWRDN_MASK;
    
    //-- Enable the PLL output
    PLL_regs->PLLCTL &= ~CSL_PLLC_PLLCTL_PLLDIS_MASK;
    
    //-- Wait for the PLL stabilisation time
    for(temp=0; temp<PLL_STABILIZATION_TIME; temp++) {;}
    
    //-- Program PLLM
    PLL_regs->PLLM = CSL_PLLC_PLLM_PLLM_MASK & 24;
    
    //-- Make sure PREDIV is enabled
    PLL_regs->PREDIV |= CSL_PLLC_PREDIV_PREDEN_MASK;
    
    //-- Disable POSTDIV
//    PLL_regs->POSTDIV |= CSL_PLLC_POSTDIV_POSTDEN_MASK;
    PLL_regs->POSTDIV = CSL_PLLC_POSTDIV_POSTDEN_MASK | 1;
    
    //-- Wait for GOSTAT to clear
    while ( (PLL_regs->PLLSTAT & 0x1) == 1 ){}
    
    //-- Program the PLLDIVx Registers
    PLL_regs->PLLDIV1 = (0 & CSL_PLLC_PLLDIV1_RATIO_MASK) | CSL_PLLC_PLLDIV1_D1EN_MASK;
    PLL_regs->PLLDIV2 = (1 & CSL_PLLC_PLLDIV2_RATIO_MASK) | CSL_PLLC_PLLDIV2_D2EN_MASK;
    PLL_regs->PLLDIV3 = (2 & CSL_PLLC_PLLDIV3_RATIO_MASK) | CSL_PLLC_PLLDIV3_D3EN_MASK;
    PLL_regs->PLLDIV4 = (3 & CSL_PLLC_PLLDIV4_RATIO_MASK) | CSL_PLLC_PLLDIV4_D4EN_MASK;
    PLL_regs->PLLDIV6 = (0 & CSL_PLLC_PLLDIV6_RATIO_MASK) | CSL_PLLC_PLLDIV6_D6EN_MASK;
    PLL_regs->PLLDIV7 = (5 & CSL_PLLC_PLLDIV7_RATIO_MASK) | CSL_PLLC_PLLDIV7_D7EN_MASK;
    
    //-- Wait for GOSTAT to clear
    while ( (PLL_regs->PLLSTAT & 0x1) == 1 ){}
    
    //-- Set GPSET bit to '1'
    PLL_regs->PLLCTL |= CSL_PLLC_PLLCMD_GOSET_MASK;
    
    //-- Wait for GOSTAT to clear
    while ( (PLL_regs->PLLSTAT & 0x1) == 1 ){}
    
    //-- Wait for PLL to reset properly
    for(temp=0; temp<PLL_RESET_TIME_CNT; temp++) {;}
    
    //-- set the PLL reset bit
    PLL_regs->PLLCTL |= CSL_PLLC_PLLCTL_PLLRST_MASK;
    
    //-- Wait for the PLL to LOCK
    for(temp=0; temp<PLL_LOCK_TIME_CNT; temp++) {;}
    
    //-- Set the PLLEN to '1'
    PLL_regs->PLLCTL |= CSL_PLLC_PLLCTL_PLLEN_MASK;
    
    SYSCONFIG0->CFGCHIP3 &= ~CSL_SYSCFG_CFGCHIP3_EMA_CLKSRC_MASK;
    
    //-- Set the PLL register lock
    //SYSCONFIG0->CFGCHIP0 |= (0x1 << 4) & 0x00000010;
    SYSCONFIG0->CFGCHIP0 |= CSL_SYSCFG_CFGCHIP0_PLL_MASTER_LOCK_MASK;
    SYSCONFIG0->CFGCHIP3 |= CSL_SYSCFG_CFGCHIP3_PLL1_MASTER_LOCK_MASK;
    
    //
    //  END PLL SETUP
    //------------------------------------------
    
    //----------------------------------
    //-- Setup FPGA Memory Space.
    //----------------------------------
    //EMIFA_regs->CE2CFG = 0x8244125;
    EMIFA_regs->CE2CFG = 0x83441A9;
	printf("SETUP THE EMIF MEMORY SPACE\n");
	
}

  • James,

    I am attaching a source file that demonstrates the sequence of how the PLL controller is configured. This might be helpful to configure the delay that we know work reliably for the device for lock up time and PLL reset. This source code is part of the OMAPL138 Starterware package if you need access to full source. Locate the function PLL0Init in the file below

    /**
     * \file  bl_platform.c
     *
     * \brief evmAM1808 Boot loader platform-specific initialization.
     *
     */
    
    /*
    * Copyright (C) 2012 Texas Instruments Incorporated - http://www.ti.com/
    *
    *  Redistribution and use in source and binary forms, with or without
    *  modification, are permitted provided that the following conditions
    *  are met:
    *
    *    Redistributions of source code must retain the above copyright
    *    notice, this list of conditions and the following disclaimer.
    *
    *    Redistributions in binary form must reproduce the above copyright
    *    notice, this list of conditions and the following disclaimer in the
    *    documentation and/or other materials provided with the
    *    distribution.
    *
    *    Neither the name of Texas Instruments Incorporated 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.
    */
    
    #include "hw_types.h"
    #include "hw_syscfg0_AM1808.h"
    #include "hw_pllc_AM1808.h"
    #include "hw_ddr2_mddr.h"
    #include "hw_syscfg1_AM1808.h"
    
    /* Device/Platform lib headers */
    #include "soc_AM1808.h"
    #include "evmAM1808.h"
    #include "psc.h"
    #include "uartStdio.h"
    
    #if defined(SPI)
    
    #elif defined(MMCSD)
    
    #elif defined(NAND)
        #include "hw_emifa2.h"
        #include "emifa.h"
        #include "nandlib.h"
        #include "nand_emifa2.h"
    #endif
    
    #include "bl.h"
    
    /* This module's header */
    #include "bl_platform.h"
    
    /******************************************************************************
    **                     Internal Macro Definitions
    *******************************************************************************/
    #define CLK_PLL0_SYSCLK3                  (0xFFFFFFF8)
    #define DDR2_MDDR_DRPYC1R_READ_LAT        (0x4)
    #define INTVECMAX                         (9)
    
    /******************************************************************************
    **                     Local function Declarations
    *******************************************************************************/
    
    static void PLL0Init(unsigned char clk_src, unsigned char pllm,
            unsigned char prediv, unsigned char postdiv, unsigned char div1,
            unsigned char div3, unsigned char div7);
    static void PLL1Init(unsigned char pllm, unsigned char postdiv,
            unsigned char div1, unsigned char div2, unsigned char div3);
    static void DDRInit(void);
    static void Delay(volatile unsigned int count);
    static void USBSetup(void);
    
    
    /******************************************************************************
    **                     Global variable Definitions
    *******************************************************************************/
    
    char *deviceType = "AM1808";
    
    
    /******************************************************************************
    **                     Local variable Definitions
    *******************************************************************************/
    #if defined(NAND)
      static EMIFANANDTimingInfo_t nandTimingInfo;
    #endif
    
    /******************************************************************************
    **                     Global Function Definitions
    *******************************************************************************/
    
    /*
     * \brief This function Initializes Pll, DDR and Uart
     *
     * \param  none
     *
     * \return none
    */
    void BL_PLATFORM_Config(void)
    {
        HWREG(SOC_SYSCFG_0_REGS + SYSCFG0_SUSPSRC) &= SYSCFG_SUSPSRC_I2C0SRC  | 
                                                      SYSCFG_SUSPSRC_UART2SRC |
                                                      SYSCFG_SUSPSRC_SPI1SRC  | 
                                                      SYSCFG_SUSPSRC_TIMER64P_0SRC;
                                                        
        /* Set the PLL0 to generate 300MHz for ARM */
        PLL0Init(PLL_CLK_SRC, PLL0_MUL, PLL0_PREDIV, PLL0_POSTDIV,
                 PLL0_DIV1,PLL0_DIV3, PLL0_DIV7);
    
        /* DDR Initialization */
        PLL1Init(PLL1_MUL, PLL1_POSTDIV, PLL1_DIV1,PLL1_DIV2, PLL1_DIV3);
        DDRInit();
    
        /* USB Initialization */
        USBSetup();
    }
    
    
    /*
     * \brief This function does any post boot setup/init
     *
     * \param  none
     *
     * \return none
    */
    void BL_PLATFORM_ConfigPostBoot( void )
    {
    }
    
    
    #if defined(SPI)
    /*
     * \brief This function is used to initialize and configure SPI Module.
     *
     * \param  none.
     *
     * \return none
    */
    void BL_PLATFORM_SPISetup(void)
    {
        /* Enable PSC for SPI */
        PSCModuleControl(SOC_PSC_1_REGS, HW_PSC_SCR0_SS, 0, PSC_MDCTL_NEXT_ENABLE);
    
        /* Setup SPI PINMUX */ 
        SPIPinMuxSetup(1);
        SPI1CSPinMuxSetup(0);
    }
    #endif
    
    #if defined(NAND)
    /*
     * \brief This function is used to initialize and configure NAND.
     *
     * \param  none.
     *
     * \return none
    */
    void BL_PLATFORM_NANDSetup(void)
    {
        /* Pin mux and clock setting */
        EMIFAClkConfig();
        NANDPinMuxSetup();
    }
    
    static void NANDTimingInfoInit(void *TimingInfo)
    {
        int moduleClkInMHz = NAND_MODULE_CLK_IN_MHZ;
        EMIFANANDTimingInfo_t *nandTimingInfo;
        
        nandTimingInfo = (EMIFANANDTimingInfo_t * )TimingInfo;
        
        /* Set the asynchronous wait timing                             */
        nandTimingInfo->writeSetup  = ( ((moduleClkInMHz * NAND_WRITE_SETUP_TIME_IN_NS)/1000u) &
                                         EMIFA_WRITE_SETUP_RESETVAL );
        nandTimingInfo->writeStrobe = ( ((moduleClkInMHz * NAND_WRITE_STROBE_TIME_IN_NS)/1000u) &
                                        EMIFA_WRITE_STROBE_RESETVAL );
        nandTimingInfo->writeHold   = ( ((moduleClkInMHz * NAND_WRITE_HOLD_TIME_IN_NS)/1000u) &
                                        EMIFA_WRITE_HOLD_RESETVAL );
        
        nandTimingInfo->readSetup   = ( ((moduleClkInMHz * NAND_READ_SETUP_TIME_IN_NS)/1000u) &
                                        EMIFA_READ_SETUP_RESETVAL );
        nandTimingInfo->readStrobe  = ( ((moduleClkInMHz * NAND_READ_STROBE_TIME_IN_NS)/1000u) &
                                        EMIFA_READ_STROBE_RESETVAL );
        nandTimingInfo->readHold    = ( ((moduleClkInMHz * NAND_READ_HOLD_TIME_IN_NS)/1000u) &
                                        EMIFA_READ_HOLD_RESETVAL );
        
        nandTimingInfo->turnAround  = ( ((moduleClkInMHz * NAND_TURN_ARND_TIME_IN_NS)/1000u) &
                                        EMIFA_TA_RESETVAL );
    }
    
    void BL_PLATFORM_NANDInfoInit(NandInfo_t *nandInfo)
    {
        NandCtrlInfo_t *hNandCtrlInfo = nandInfo->hNandCtrlInfo;
        NandDmaInfo_t  *hNandDmaInfo  = nandInfo->hNandDmaInfo;
        NandEccInfo_t  *hNandEccInfo  = nandInfo->hNandEccInfo;
    
        /* Init the NAND Device Info */
        nandInfo->opMode                        = NAND_DATA_XFER_MODE;
        nandInfo->eccType                       = NAND_ECC_ALGO_RS_4BIT;
        
        nandInfo->chipSelectCnt                 = 1;
        nandInfo->dieCnt                        = 1;
        nandInfo->chipSelects[0]                = NAND_CHIP_SELECT;
        nandInfo->busWidth                      = NAND_BUSWIDTH;
        nandInfo->pageSize                      = NAND_PAGE_SIZE_IN_BYTES;
        nandInfo->blkSize                       = NAND_BLOCK_SIZE_IN_BYTES;
        nandInfo->manId                         = NAND_MANUFATURER_MICRON_ID;
        nandInfo->devId                         = NAND_DEVICE_ID;
    
        nandInfo->dataRegAddr                   = (SOC_EMIFA_CS3_ADDR + 0x00);
        nandInfo->addrRegAddr                   = (SOC_EMIFA_CS3_ADDR + 0x08);
        nandInfo->cmdRegAddr                    = (SOC_EMIFA_CS3_ADDR + 0x10);
    
    
        /* Init the NAND Controller Info struct */
        hNandCtrlInfo->CtrlInit                 = EMIFANANDInit;
        hNandCtrlInfo->WaitPinStatusGet         = EMIFANANDWaitPinStatusGet;
        hNandCtrlInfo->currChipSelect           = NAND_CHIP_SELECT;
        hNandCtrlInfo->baseAddr                 = SOC_EMIFA_0_REGS;
        hNandCtrlInfo->eccSupported             = ( NAND_ECC_ALGO_HAMMING_1BIT |
                                                    NAND_ECC_ALGO_RS_4BIT );
        hNandCtrlInfo->waitPin                  = EMIFA_EMA_WAIT_PIN0;
        hNandCtrlInfo->waitPinPol               = EMIFA_EMA_WAIT_PIN_POLARITY_HIGH;
        hNandCtrlInfo->wpPinPol                 = 0;
        hNandCtrlInfo->chipSelectBaseAddr[0]    = SOC_EMIFA_CS3_ADDR;
        hNandCtrlInfo->chipSelectRegionSize[0]  = EMIFA_CHIP_SELECT_3_SIZE;
        hNandCtrlInfo->hNandTimingInfo          = &nandTimingInfo;
        NANDTimingInfoInit(hNandCtrlInfo->hNandTimingInfo);
                                                    
                                                    
        /* Init the NAND Ecc Info */
        hNandEccInfo->baseAddr                  = 0;    
        hNandEccInfo->ECCInit                   = EMIFANANDECCInit;
        hNandEccInfo->ECCEnable                 = EMIFANANDECCEnable;
        hNandEccInfo->ECCDisable                = EMIFANANDECCDisable;
        hNandEccInfo->ECCWriteSet               = EMIFANANDECCWriteSet;
        hNandEccInfo->ECCReadSet                = EMIFANANDECCReadSet;
        hNandEccInfo->ECCCalculate              = EMIFANANDECCCalculate;
        hNandEccInfo->ECCCheckAndCorrect        = EMIFANANDECCCheckAndCorrect;
        
        /* Init the NAND DMA info */
        hNandDmaInfo->DMAXfer                   = NULL;    
        hNandDmaInfo->DMAInit                   = NULL;
        hNandDmaInfo->DMAXferSetup              = NULL;
        hNandDmaInfo->DMAXferStatusGet          = NULL;
    }
    
    #endif
    
    /******************************************************************************
    **                     Local Function Definitions
    *******************************************************************************/
    
    /*
     * \brief This function is used to initialize and configure USB Module.
     *
     * \param  none.
     *
     * \return none
    */
    static void USBSetup(void)
    {
        /* Enable PSC for USB2 */
        PSCModuleControl(SOC_PSC_1_REGS,1, 0, PSC_MDCTL_NEXT_ENABLE);
        
        /* USB PHY ON*/
        HWREG(SOC_USB_0_PHY_REGS) = 0x09F2;
    }
    
    /*
     * \brief Delay function.
     *
     * \param  count - Halts execution depend upon the value of the variable.
     *
     * \return none
    */
    static void Delay(volatile unsigned int count)
    {
        while(count--);
    }
    
    /*
     * \brief This function Configures the PLL0 registers.
     *      PLL Register are set to achieve the desired frequencies.
     *
     * \param  clk_src
     * \param  pllm             This value is assigned to the PLLMultipler register.
     * \param  prediv           This value is assigned to the PLLMultipler register.
     * \param  postdiv          This value is assigned to the PLL_Postdiv register.
     * \param  div1             This value is assigned to the PLL_DIV1 register.
     * \param  div3             This value is assigned to the PLL_DIV3 register.
     * \param  div7             This value is assigned to the PLL_DIV7 register.
     *
     * \return Int              Returns success or failure
    */
    static void PLL0Init(unsigned char clk_src, unsigned char pllm,
               unsigned char prediv, unsigned char postdiv, unsigned char div1,
               unsigned char div3, unsigned char div7)
    {
        HWREG(SOC_SYSCFG_0_REGS + SYSCFG0_CFGCHIP0) &=
                                                   ~SYSCFG_CFGCHIP0_PLL_MASTER_LOCK;
        /* PLLENSRC must be cleared before PLLEN bit have any effect */
        HWREG(SOC_PLLC_0_REGS + PLLC_PLLCTL) &= ~PLLC_PLLCTL_PLLENSRC;
    
        /* PLLCTL.EXTCLKSRC bit 9 should be left at 0  */
        HWREG(SOC_PLLC_0_REGS + PLLC_PLLCTL) &= ~PLLC_PLLCTL_EXTCLKSRC;
    
        /*PLLEN = 0 put pll in bypass mode  */
        HWREG(SOC_PLLC_0_REGS + PLLC_PLLCTL) &= ~PLLC_PLLCTL_PLLEN;
    
        /*wait for 2 counts to switch pll to the by pass mode */
        Delay(2);
    
        /*Select the Clock Mode bit 8 as External Clock or On Chip Oscilator  */
        HWREG(SOC_PLLC_0_REGS + PLLC_PLLCTL) &= ~PLLC_PLLCTL_CLKMODE;
        HWREG(SOC_PLLC_0_REGS + PLLC_PLLCTL) |= (clk_src << 8);
        /* Clear the PLLRST to reset the PLL */
        HWREG(SOC_PLLC_0_REGS + PLLC_PLLCTL) &= ~PLLC_PLLCTL_PLLRST;
    
        /*Disable PLL out */
        HWREG(SOC_PLLC_0_REGS + PLLC_PLLCTL) |= PLLC_PLLCTL_PLLDIS;
    
        /* PLL initialization sequece, power up the PLL */
        HWREG(SOC_PLLC_0_REGS + PLLC_PLLCTL) &= ~PLLC_PLLCTL_PLLPWRDN;
    
        HWREG(SOC_PLLC_0_REGS + PLLC_PLLCTL) &= ~PLLC_PLLCTL_PLLDIS;
        
        /* Wait for 300 counts */ 
        Delay(300);
        
        HWREG(SOC_PLLC_0_REGS + PLLC_PLLM) = pllm;
    
        /* Program the required multiplier value   */
        HWREG(SOC_PLLC_0_REGS + PLLC_PREDIV) = PLLC_PREDIV_PREDEN | prediv;
        HWREG(SOC_PLLC_0_REGS + PLLC_POSTDIV) = PLLC_POSTDIV_POSTDEN | postdiv;
        /* Check for the GOSTAT bit in PLLSTAT to clear to 0 to indicate that
                    no GO operation is currently in progress */
        while (HWREG(SOC_PLLC_0_REGS + PLLC_PLLSTAT) & PLLC_PLLSTAT_GOSTAT  );
        /* divider values are assigned */
        HWREG(SOC_PLLC_0_REGS + PLLC_PLLDIV1) = PLLC_PLLDIV1_D1EN | div1;
        HWREG(SOC_PLLC_0_REGS + PLLC_PLLDIV2)
            = PLLC_PLLDIV2_D2EN | (((div1 + 1) * 2) - 1);
        HWREG(SOC_PLLC_0_REGS + PLLC_PLLDIV4)
            = PLLC_PLLDIV4_D4EN | (((div1 + 1) * 4)- 1);
        HWREG(SOC_PLLC_0_REGS + PLLC_PLLDIV6)
            = PLLC_PLLDIV6_D6EN | div1;
        HWREG(SOC_PLLC_0_REGS + PLLC_PLLDIV3) = PLLC_PLLDIV3_D3EN | div3;
        HWREG(SOC_PLLC_0_REGS + PLLC_PLLDIV7) = PLLC_PLLDIV7_D7EN | div7;
    
        HWREG(SOC_PLLC_0_REGS + PLLC_PLLCMD) |= PLLC_PLLCMD_GOSET;
        /*Wait for the Gostat bit in PLLSTAT to clear to 0
            ( completion of phase alignment) */
        while (HWREG(SOC_PLLC_0_REGS + PLLC_PLLSTAT) & PLLC_PLLSTAT_GOSTAT);
    
       /* Wait for 40 counts */ 
       Delay(40);
        /* set the PLLRST bit in PLLCTL to 1,bring the PLL out of reset */
        HWREG(SOC_PLLC_0_REGS + PLLC_PLLCTL) |= PLLC_PLLCTL_PLLRST;
    
        /* Wait for 300 counts*/
        Delay (300);
    
        /*removing pll from bypass mode */
        HWREG(SOC_PLLC_0_REGS + PLLC_PLLCTL) |= PLLC_PLLCTL_PLLEN;
    
        /* set PLL lock bit */
        HWREG(SOC_SYSCFG_0_REGS + SYSCFG0_CFGCHIP0) |=
                                         (0x01 << SYSCFG_CFGCHIP0_PLL_MASTER_LOCK_SHIFT )
                                          & SYSCFG_CFGCHIP0_PLL_MASTER_LOCK ;
    
        HWREG(SOC_SYSCFG_0_REGS + SYSCFG0_CFGCHIP3) &= CLK_PLL0_SYSCLK3;
    }
    
    /*
     * \brief This function Configures the PLL1 registers.
        PLL Register are set to achieve the desired frequencies.
     *
     * \param  clk_src
     *          pllm             This value is assigned to the PLL1Multipler register.
     *          postdiv          This value is assigned to the PLL1_Postdiv register.
     *          div1             This value is assigned to the PLL1_Div1 register.
     *          div2             This value is assigned to the PLL1_Div2 register.
     *          div3             This value is assigned to the PLL1_Div3 register.
     *
     * \return Int          Returns Success or Failure,depending on the execution
    */
    static void PLL1Init(unsigned char pllm, unsigned char postdiv,
            unsigned char div1, unsigned char div2, unsigned char div3)
    {
        /* Clear PLL lock bit */
        HWREG(SOC_SYSCFG_0_REGS + SYSCFG0_CFGCHIP3) &=
                ~SYSCFG_CFGCHIP3_PLL1_MASTER_LOCK ;
    
        /* PLLENSRC must be cleared before PLLEN has any effect*/
        HWREG(SOC_PLLC_1_REGS + PLLC_PLLCTL) &= ~PLLC_PLLCTL_PLLENSRC;
    
        /* PLLCTL.EXTCLKSRC bit 9 should be left at 0  */
        HWREG(SOC_PLLC_1_REGS + PLLC_PLLCTL) &= ~PLLC_PLLCTL_EXTCLKSRC;
    
        /* Set PLLEN=0 to put in bypass mode */
        HWREG(SOC_PLLC_1_REGS + PLLC_PLLCTL) &= ~PLLC_PLLCTL_PLLEN;
    
        /* wait for 4 cycles to allow PLLEN mux
                switches properly to bypass clock */
        Delay(4);
    
        /* Clear PLLRST bit to reset the PLL */
        HWREG(SOC_PLLC_1_REGS + PLLC_PLLCTL) &= ~PLLC_PLLCTL_PLLRST;
    
        /* Disable the PLL output */
        HWREG(SOC_PLLC_1_REGS + PLLC_PLLCTL) &= PLLC_PLLCTL_PLLDIS;
    
        /* PLL initialization sequence */
        /* Power up the PLL by setting PWRDN bit set to 0 */
        HWREG(SOC_PLLC_1_REGS + PLLC_PLLCTL) &= ~PLLC_PLLCTL_PLLPWRDN ;
    
        /* Enable the PLL output */
        HWREG(SOC_PLLC_1_REGS + PLLC_PLLCTL) &= ~PLLC_PLLCTL_PLLDIS;
    
        Delay(300);
    
        /* Multiplier value is set */
        HWREG(SOC_PLLC_1_REGS + PLLC_PLLM) = pllm;
    
        HWREG(SOC_PLLC_1_REGS + PLLC_POSTDIV) = PLLC_POSTDIV_POSTDEN | postdiv;
    
        while ( HWREG(SOC_PLLC_1_REGS + PLLC_PLLSTAT) & PLLC_PLLCMD_GOSET  );
        HWREG(SOC_PLLC_1_REGS + PLLC_PLLDIV1) = PLLC_PLLDIV1_D1EN | div1;
        HWREG(SOC_PLLC_1_REGS + PLLC_PLLDIV2) = PLLC_PLLDIV2_D2EN | div2;
        HWREG(SOC_PLLC_1_REGS + PLLC_PLLDIV3) = PLLC_PLLDIV3_D3EN | div3;
    
    
        /*Set the GOSET bit in PLLCMD to 1 to initiate a new divider transition*/
        HWREG(SOC_PLLC_1_REGS + PLLC_PLLCMD) |= PLLC_PLLCMD_GOSET;
    
        while (HWREG(SOC_PLLC_1_REGS + PLLC_PLLSTAT) & PLLC_PLLSTAT_GOSTAT);
        /*Wait for the Gostat bit in PLLSTAT to clear to 0
            ( complition of phase alignment ) */
        Delay(40);
    
        /* set the PLLRST bit in PLLCTL to 1,bring the PLL out of reset  */
        HWREG(SOC_PLLC_1_REGS + PLLC_PLLCTL) |= PLLC_PLLCTL_PLLRST;
        Delay(300);
        /* Removing PLL from bypass mode */
        HWREG(SOC_PLLC_1_REGS + PLLC_PLLCTL) |= PLLC_PLLCTL_PLLEN;
    
        /* set PLL lock bit */
        HWREG(SOC_SYSCFG_0_REGS + SYSCFG0_CFGCHIP3) |=
        (0x1 << SYSCFG_CFGCHIP3_PLL1_MASTER_LOCK_SHIFT)
            & SYSCFG_CFGCHIP3_PLL1_MASTER_LOCK ;
    }
    
    /*
     * \brief This function is used to initialize and configure DDR.
     *
     * \param  none.
     *
     * \return none
    */
    static void DDRInit(void)
    {
        PSCModuleControl(SOC_PSC_1_REGS, HW_PSC_DDR2_MDDR,
                                  0, PSC_MDCTL_NEXT_ENABLE);
        if (HWREG(SOC_SYSCFG_1_REGS + SYSCFG1_VTPIO_CTL) &
                                                    SYSCFG1_VTPIO_CTL_POWERDN)
        {
             /* Set IOPWRDN bit, powerdown enable mode */
            HWREG(SOC_SYSCFG_1_REGS + SYSCFG1_VTPIO_CTL) |=
                                              SYSCFG1_VTPIO_CTL_IOPWRDN;
             /* Clear POWERDN bit (enable VTP) */
            HWREG(SOC_SYSCFG_1_REGS + SYSCFG1_VTPIO_CTL) |=
                                              SYSCFG1_VTPIO_CTL_POWERDN;
             /* Clear CLRZ bit */
    	HWREG(SOC_SYSCFG_1_REGS + SYSCFG1_VTPIO_CTL) &=
                                              ~SYSCFG1_VTPIO_CTL_CLKRZ;
    	/* CLRZ bit should be low at least for 2ns */
            Delay(4);
            /* Set CLRZ bit */
    	HWREG(SOC_SYSCFG_1_REGS + SYSCFG1_VTPIO_CTL) |=
                                               SYSCFG1_VTPIO_CTL_CLKRZ;
            /* Poll ready bit in VTPIO_CTL Untill it is high */
    	while (!(( HWREG(SOC_SYSCFG_1_REGS + SYSCFG1_VTPIO_CTL) &
                                                         VTPIO_CTL_HIGH ) >> 15));
            /* Set Lock bit for static mode */
    	HWREG(SOC_SYSCFG_1_REGS + SYSCFG1_VTPIO_CTL) |= SYSCFG1_VTPIO_CTL_LOCK;
            /* set PWRSAVE bit to save Power */
    	HWREG(SOC_SYSCFG_1_REGS + SYSCFG1_VTPIO_CTL) |=
                                              SYSCFG1_VTPIO_CTL_PWRSAVE;
    	/* VTP Calibration ends */
        }
    
        /* Set BOOTUNLOCK */
        HWREG(SOC_DDR2_0_CTRL_REGS + DDR2_MDDR_SDCR) |= DDR2_MDDR_SDCR_BOOTUNLOCK;
    
        /* Set EXT_STRBEN and PWRDNEN bit of DDR PHY control register,
                                       assign desired value to the RL bit */
        HWREG(SOC_DDR2_0_CTRL_REGS + DDR2_MDDR_DRPYC1R) = 
                                                 DDR2_MDDR_DRPYC1R_EXT_STRBEN |
                                                 DDR2_MDDR_DRPYC1R_PWRDNEN    | 
                                                 DDR2_MDDR_DRPYC1R_READ_LAT;
                                                                     
        HWREG(SOC_DDR2_0_CTRL_REGS + DDR2_MDDR_SDCR) = DDR2_SDCR;
        HWREG(SOC_DDR2_0_CTRL_REGS + DDR2_MDDR_SDTIMR1) = DDR2_SDTIMR1;
        HWREG(SOC_DDR2_0_CTRL_REGS + DDR2_MDDR_SDTIMR2) = DDR2_SDTIMR2;
    
        /* CLEAR TIMINGUNLOCK */
        HWREG(SOC_DDR2_0_CTRL_REGS + DDR2_MDDR_SDCR) &= ~DDR2_MDDR_SDCR_BOOTUNLOCK;
        /*  IBANK_POS set to 0 so this register does not apply */
        HWREG(SOC_DDR2_0_CTRL_REGS + DDR2_MDDR_SDCR2 ) = DDR2_MDDR_SDCR_IBANK_ONE;
        /* SET the refreshing rate */
        HWREG(SOC_DDR2_0_CTRL_REGS + DDR2_MDDR_SDRCR) = DDR2_SDRCR;
    
        /* SyncReset the Clock to SDRAM */
        PSCModuleControl(SOC_PSC_1_REGS, HW_PSC_DDR2_MDDR,
                                  0,PSC_MDSTAT_STATE_SYNCRST);
        /* Enable clock to SDRAM */
        PSCModuleControl(SOC_PSC_1_REGS, HW_PSC_DDR2_MDDR, 0,PSC_MDCTL_NEXT_ENABLE);
        /* Disable Self refresh rate */
        HWREG(SOC_DDR2_0_CTRL_REGS + DDR2_MDDR_SDRCR ) &= ~DDR2_SDRCR_CLEAR;
    
    }
    /******************************************************************************
    **                              END OF FILE
    *******************************************************************************/
    

    If you want to continue to debug your code, I recommend go to View->Registers in the CCS debug view and look at your PLL0 registers and ensure that all your configurations are taking place as expected.

    Regards,

    Rahul

  • Hi Rahul,

    Thanks very much.  Not only was that code very useful, it also helped me find the problem in mine.  Thanks again

    Best Regards,

    James McNeill