Test the CCS4 demo project to CCS5 and make a minor change to ensure the power supplied is adequate for the CPU speed.

This commit is contained in:
Richard Barry 2012-04-02 09:20:45 +00:00
parent ab1aa67b08
commit bb708957a9
12 changed files with 1162 additions and 17 deletions

View file

@ -0,0 +1,248 @@
/*******************************************************************************
*
* HAL_PMM.c
* Power Management Module Library for MSP430F5xx/6xx family
*
*
* Copyright (C) 2010 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 "msp430.h"
#include "HAL_PMM.h"
/*******************************************************************************
* \brief Increase Vcore by one level
*
* \param level Level to which Vcore needs to be increased
* \return status Success/failure
******************************************************************************/
static uint16_t SetVCoreUp(uint8_t level)
{
uint16_t PMMRIE_backup, SVSMHCTL_backup, SVSMLCTL_backup;
// The code flow for increasing the Vcore has been altered to work around
// the erratum FLASH37.
// Please refer to the Errata sheet to know if a specific device is affected
// DO NOT ALTER THIS FUNCTION
// Open PMM registers for write access
PMMCTL0_H = 0xA5;
// Disable dedicated Interrupts
// Backup all registers
PMMRIE_backup = PMMRIE;
PMMRIE &= ~(SVMHVLRPE | SVSHPE | SVMLVLRPE | SVSLPE | SVMHVLRIE |
SVMHIE | SVSMHDLYIE | SVMLVLRIE | SVMLIE | SVSMLDLYIE);
SVSMHCTL_backup = SVSMHCTL;
SVSMLCTL_backup = SVSMLCTL;
// Clear flags
PMMIFG = 0;
// Set SVM highside to new level and check if a VCore increase is possible
SVSMHCTL = SVMHE | SVSHE | (SVSMHRRL0 * level);
// Wait until SVM highside is settled
while ((PMMIFG & SVSMHDLYIFG) == 0) ;
// Clear flag
PMMIFG &= ~SVSMHDLYIFG;
// Check if a VCore increase is possible
if ((PMMIFG & SVMHIFG) == SVMHIFG){ // -> Vcc is too low for a Vcore increase
// recover the previous settings
PMMIFG &= ~SVSMHDLYIFG;
SVSMHCTL = SVSMHCTL_backup;
// Wait until SVM highside is settled
while ((PMMIFG & SVSMHDLYIFG) == 0) ;
// Clear all Flags
PMMIFG &= ~(SVMHVLRIFG | SVMHIFG | SVSMHDLYIFG | SVMLVLRIFG | SVMLIFG | SVSMLDLYIFG);
PMMRIE = PMMRIE_backup; // Restore PMM interrupt enable register
PMMCTL0_H = 0x00; // Lock PMM registers for write access
return PMM_STATUS_ERROR; // return: voltage not set
}
// Set also SVS highside to new level
// Vcc is high enough for a Vcore increase
SVSMHCTL |= (SVSHRVL0 * level);
// Wait until SVM highside is settled
while ((PMMIFG & SVSMHDLYIFG) == 0) ;
// Clear flag
PMMIFG &= ~SVSMHDLYIFG;
// Set VCore to new level
PMMCTL0_L = PMMCOREV0 * level;
// Set SVM, SVS low side to new level
SVSMLCTL = SVMLE | (SVSMLRRL0 * level) | SVSLE | (SVSLRVL0 * level);
// Wait until SVM, SVS low side is settled
while ((PMMIFG & SVSMLDLYIFG) == 0) ;
// Clear flag
PMMIFG &= ~SVSMLDLYIFG;
// SVS, SVM core and high side are now set to protect for the new core level
// Restore Low side settings
// Clear all other bits _except_ level settings
SVSMLCTL &= (SVSLRVL0 + SVSLRVL1 + SVSMLRRL0 + SVSMLRRL1 + SVSMLRRL2);
// Clear level settings in the backup register,keep all other bits
SVSMLCTL_backup &= ~(SVSLRVL0 + SVSLRVL1 + SVSMLRRL0 + SVSMLRRL1 + SVSMLRRL2);
// Restore low-side SVS monitor settings
SVSMLCTL |= SVSMLCTL_backup;
// Restore High side settings
// Clear all other bits except level settings
SVSMHCTL &= (SVSHRVL0 + SVSHRVL1 + SVSMHRRL0 + SVSMHRRL1 + SVSMHRRL2);
// Clear level settings in the backup register,keep all other bits
SVSMHCTL_backup &= ~(SVSHRVL0 + SVSHRVL1 + SVSMHRRL0 + SVSMHRRL1 + SVSMHRRL2);
// Restore backup
SVSMHCTL |= SVSMHCTL_backup;
// Wait until high side, low side settled
while (((PMMIFG & SVSMLDLYIFG) == 0) && ((PMMIFG & SVSMHDLYIFG) == 0)) ;
// Clear all Flags
PMMIFG &= ~(SVMHVLRIFG | SVMHIFG | SVSMHDLYIFG | SVMLVLRIFG | SVMLIFG | SVSMLDLYIFG);
PMMRIE = PMMRIE_backup; // Restore PMM interrupt enable register
PMMCTL0_H = 0x00; // Lock PMM registers for write access
return PMM_STATUS_OK;
}
/*******************************************************************************
* \brief Decrease Vcore by one level
*
* \param level Level to which Vcore needs to be decreased
* \return status Success/failure
******************************************************************************/
static uint16_t SetVCoreDown(uint8_t level)
{
uint16_t PMMRIE_backup, SVSMHCTL_backup, SVSMLCTL_backup;
// The code flow for decreasing the Vcore has been altered to work around
// the erratum FLASH37.
// Please refer to the Errata sheet to know if a specific device is affected
// DO NOT ALTER THIS FUNCTION
// Open PMM registers for write access
PMMCTL0_H = 0xA5;
// Disable dedicated Interrupts
// Backup all registers
PMMRIE_backup = PMMRIE;
PMMRIE &= ~(SVMHVLRPE | SVSHPE | SVMLVLRPE | SVSLPE | SVMHVLRIE |
SVMHIE | SVSMHDLYIE | SVMLVLRIE | SVMLIE | SVSMLDLYIE);
SVSMHCTL_backup = SVSMHCTL;
SVSMLCTL_backup = SVSMLCTL;
// Clear flags
PMMIFG &= ~(SVMHIFG | SVSMHDLYIFG | SVMLIFG | SVSMLDLYIFG);
// Set SVM, SVS high & low side to new settings in normal mode
SVSMHCTL = SVMHE | (SVSMHRRL0 * level) | SVSHE | (SVSHRVL0 * level);
SVSMLCTL = SVMLE | (SVSMLRRL0 * level) | SVSLE | (SVSLRVL0 * level);
// Wait until SVM high side and SVM low side is settled
while ((PMMIFG & SVSMHDLYIFG) == 0 || (PMMIFG & SVSMLDLYIFG) == 0) ;
// Clear flags
PMMIFG &= ~(SVSMHDLYIFG + SVSMLDLYIFG);
// SVS, SVM core and high side are now set to protect for the new core level
// Set VCore to new level
PMMCTL0_L = PMMCOREV0 * level;
// Restore Low side settings
// Clear all other bits _except_ level settings
SVSMLCTL &= (SVSLRVL0 + SVSLRVL1 + SVSMLRRL0 + SVSMLRRL1 + SVSMLRRL2);
// Clear level settings in the backup register,keep all other bits
SVSMLCTL_backup &= ~(SVSLRVL0 + SVSLRVL1 + SVSMLRRL0 + SVSMLRRL1 + SVSMLRRL2);
// Restore low-side SVS monitor settings
SVSMLCTL |= SVSMLCTL_backup;
// Restore High side settings
// Clear all other bits except level settings
SVSMHCTL &= (SVSHRVL0 + SVSHRVL1 + SVSMHRRL0 + SVSMHRRL1 + SVSMHRRL2);
// Clear level settings in the backup register, keep all other bits
SVSMHCTL_backup &= ~(SVSHRVL0 + SVSHRVL1 + SVSMHRRL0 + SVSMHRRL1 + SVSMHRRL2);
// Restore backup
SVSMHCTL |= SVSMHCTL_backup;
// Wait until high side, low side settled
while (((PMMIFG & SVSMLDLYIFG) == 0) && ((PMMIFG & SVSMHDLYIFG) == 0)) ;
// Clear all Flags
PMMIFG &= ~(SVMHVLRIFG | SVMHIFG | SVSMHDLYIFG | SVMLVLRIFG | SVMLIFG | SVSMLDLYIFG);
PMMRIE = PMMRIE_backup; // Restore PMM interrupt enable register
PMMCTL0_H = 0x00; // Lock PMM registers for write access
return PMM_STATUS_OK; // Return: OK
}
uint16_t SetVCore(uint8_t level)
{
uint16_t actlevel;
uint16_t status = 0;
level &= PMMCOREV_3; // Set Mask for Max. level
actlevel = (PMMCTL0 & PMMCOREV_3); // Get actual VCore
// step by step increase or decrease
while ((level != actlevel) && (status == 0)) {
if (level > actlevel){
status = SetVCoreUp(++actlevel);
}
else {
status = SetVCoreDown(--actlevel);
}
}
return status;
}

View file

@ -0,0 +1,113 @@
/*******************************************************************************
*
* HAL_PMM.h
* Power Management Module Library for MSP430F5xx/6xx family
*
*
* Copyright (C) 2010 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.
*
******************************************************************************/
#ifndef HAL_PMM_H
#define HAL_PMM_H
#include <stdint.h>
#include "HAL_MACROS.h"
/*******************************************************************************
* Macros
******************************************************************************/
#define ENABLE_SVSL() st(PMMCTL0_H = 0xA5; SVSMLCTL |= SVSLE; PMMCTL0_H = 0x00; )
#define DISABLE_SVSL() st(PMMCTL0_H = 0xA5; SVSMLCTL &= ~SVSLE; PMMCTL0_H = 0x00; )
#define ENABLE_SVML() st(PMMCTL0_H = 0xA5; SVSMLCTL |= SVMLE; PMMCTL0_H = 0x00; )
#define DISABLE_SVML() st(PMMCTL0_H = 0xA5; SVSMLCTL &= ~SVMLE; PMMCTL0_H = 0x00; )
#define ENABLE_SVSH() st(PMMCTL0_H = 0xA5; SVSMHCTL |= SVSHE; PMMCTL0_H = 0x00; )
#define DISABLE_SVSH() st(PMMCTL0_H = 0xA5; SVSMHCTL &= ~SVSHE; PMMCTL0_H = 0x00; )
#define ENABLE_SVMH() st(PMMCTL0_H = 0xA5; SVSMHCTL |= SVMHE; PMMCTL0_H = 0x00; )
#define DISABLE_SVMH() st(PMMCTL0_H = 0xA5; SVSMHCTL &= ~SVMHE; PMMCTL0_H = 0x00; )
#define ENABLE_SVSL_SVML() st(PMMCTL0_H = 0xA5; SVSMLCTL |= (SVSLE + SVMLE); PMMCTL0_H = 0x00; )
#define DISABLE_SVSL_SVML() st(PMMCTL0_H = 0xA5; SVSMLCTL &= ~(SVSLE + SVMLE); PMMCTL0_H = 0x00; )
#define ENABLE_SVSH_SVMH() st(PMMCTL0_H = 0xA5; SVSMHCTL |= (SVSHE + SVMHE); PMMCTL0_H = 0x00; )
#define DISABLE_SVSH_SVMH() st(PMMCTL0_H = 0xA5; SVSMHCTL &= ~(SVSHE + SVMHE); PMMCTL0_H = 0x00; )
#define ENABLE_SVSL_RESET() st(PMMCTL0_H = 0xA5; PMMRIE |= SVSLPE; PMMCTL0_H = 0x00; )
#define DISABLE_SVSL_RESET() st(PMMCTL0_H = 0xA5; PMMRIE &= ~SVSLPE; PMMCTL0_H = 0x00; )
#define ENABLE_SVML_INTERRUPT() st(PMMCTL0_H = 0xA5; PMMRIE |= SVMLIE; PMMCTL0_H = 0x00; )
#define DISABLE_SVML_INTERRUPT() st(PMMCTL0_H = 0xA5; PMMRIE &= ~SVMLIE; PMMCTL0_H = 0x00; )
#define ENABLE_SVSH_RESET() st(PMMCTL0_H = 0xA5; PMMRIE |= SVSHPE; PMMCTL0_H = 0x00; )
#define DISABLE_SVSH_RESET() st(PMMCTL0_H = 0xA5; PMMRIE &= ~SVSHPE; PMMCTL0_H = 0x00; )
#define ENABLE_SVMH_INTERRUPT() st(PMMCTL0_H = 0xA5; PMMRIE |= SVMHIE; PMMCTL0_H = 0x00; )
#define DISABLE_SVMH_INTERRUPT() st(PMMCTL0_H = 0xA5; PMMRIE &= ~SVMHIE; PMMCTL0_H = 0x00; )
#define CLEAR_PMM_IFGS() st(PMMCTL0_H = 0xA5; PMMIFG = 0; PMMCTL0_H = 0x00; )
// These settings use SVSH/LACE = 0
#define SVSL_ENABLED_IN_LPM_FAST_WAKE() st( \
PMMCTL0_H = 0xA5; SVSMLCTL |= (SVSLFP + SVSLMD); SVSMLCTL &= ~SVSMLACE; PMMCTL0_H = 0x00; )
#define SVSL_ENABLED_IN_LPM_SLOW_WAKE() st(PMMCTL0_H = 0xA5; SVSMLCTL |= SVSLMD; SVSMLCTL &= \
~(SVSLFP + SVSMLACE); PMMCTL0_H = 0x00; )
#define SVSL_DISABLED_IN_LPM_FAST_WAKE() st(PMMCTL0_H = 0xA5; SVSMLCTL |= SVSLFP; SVSMLCTL &= \
~(SVSLMD + SVSMLACE); PMMCTL0_H = 0x00; )
#define SVSL_DISABLED_IN_LPM_SLOW_WAKE() st(PMMCTL0_H = 0xA5; SVSMLCTL &= \
~(SVSLFP + SVSMLACE + SVSLMD); PMMCTL0_H = 0x00; )
#define SVSH_ENABLED_IN_LPM_NORM_PERF() st(PMMCTL0_H = 0xA5; SVSMHCTL |= SVSHMD; SVSMHCTL &= \
~(SVSMHACE + SVSHFP); PMMCTL0_H = 0x00; )
#define SVSH_ENABLED_IN_LPM_FULL_PERF() st( \
PMMCTL0_H = 0xA5; SVSMHCTL |= (SVSHMD + SVSHFP); SVSMHCTL &= ~SVSMHACE; PMMCTL0_H = 0x00; )
#define SVSH_DISABLED_IN_LPM_NORM_PERF() st(PMMCTL0_H = 0xA5; SVSMHCTL &= \
~(SVSMHACE + SVSHFP + SVSHMD); PMMCTL0_H = 0x00; )
#define SVSH_DISABLED_IN_LPM_FULL_PERF() st(PMMCTL0_H = 0xA5; SVSMHCTL |= SVSHFP; SVSMHCTL &= \
~(SVSMHACE + SVSHMD); PMMCTL0_H = 0x00; )
// These setting use SVSH/LACE = 1
#define SVSL_OPTIMIZED_IN_LPM_FAST_WAKE() st(PMMCTL0_H = 0xA5; SVSMLCTL |= \
(SVSLFP + SVSLMD + SVSMLACE); PMMCTL0_H = 0x00; )
#define SVSH_OPTIMIZED_IN_LPM_FULL_PERF() st(PMMCTL0_H = 0xA5; SVSMHCTL |= \
(SVSHMD + SVSHFP + SVSMHACE); PMMCTL0_H = 0x00; )
/*******************************************************************************
* Defines
******************************************************************************/
#define PMM_STATUS_OK 0
#define PMM_STATUS_ERROR 1
/*******************************************************************************
* \brief Set Vcore to expected level
*
* \param level Level to which Vcore needs to be increased/decreased
* \return status Success/failure
******************************************************************************/
extern uint16_t SetVCore(uint8_t level);
#endif /* HAL_PMM_H */

View file

@ -1,6 +1,6 @@
/*
FreeRTOS V7.1.0 - Copyright (C) 2011 Real Time Engineers Ltd.
***************************************************************************
* *
@ -53,8 +53,8 @@
/* The following #error directive is to remind users that a batch file must be
* executed prior to this project being built. The batch file *cannot* be
* executed from within CCS4! Once it has been executed, re-open or refresh
* executed prior to this project being built. The batch file *cannot* be
* executed from within CCS4! Once it has been executed, re-open or refresh
* the CCS4 project and remove the #error line below.
*/
//#error Ensure CreateProjectDirectoryStructure.bat has been executed before building. See comment immediately above.
@ -78,7 +78,8 @@
#define configUSE_PREEMPTION 1
#define configUSE_IDLE_HOOK 1
#define configUSE_TICK_HOOK 1
#define configCPU_CLOCK_HZ ( 25000000UL )
#define configCPU_CLOCK_HZ ( 25000000UL )
#define configLFXT_CLOCK_HZ ( 32768L )
#define configTICK_RATE_HZ ( ( portTickType ) 1000 )
#define configMAX_PRIORITIES ( ( unsigned portBASE_TYPE ) 5 )
#define configTOTAL_HEAP_SIZE ( ( size_t ) ( 10 * 1024 ) )
@ -128,8 +129,8 @@ vector for the chosen tick interrupt source. This implementation of
vApplicationSetupTimerInterrupt() generates the tick from timer A0, so in this
case configTICK_VECTOR is set to TIMER0_A0_VECTOR. */
#define configTICK_VECTOR TIMER0_A0_VECTOR
#define configASSERT( x ) if( ( x ) == 0 ) { taskDISABLE_INTERRUPTS(); for( ;; ); }
#define configASSERT( x ) if( ( x ) == 0 ) { taskDISABLE_INTERRUPTS(); for( ;; ); }
#endif /* FREERTOS_CONFIG_H */

View file

@ -23,5 +23,6 @@ in order to use MSP-EXP430F5438 HAL.
//#include "hal_rf.h"
//#include "hal_rtc.h"
//#include "hal_tlv.h"
#include "hal_pmm.h"
#endif /* HAL_MSP_EXP430F5438_H */

View file

@ -66,3 +66,43 @@ void halBoardInit(void)
PJDIR = 0xFF;
P11SEL = 0;
}
/**********************************************************************//**
* @brief Set function for MCLK frequency.
*
*
* @return none
*************************************************************************/
void hal430SetSystemClock(unsigned long req_clock_rate, unsigned long ref_clock_rate)
{
/* Convert a Hz value to a KHz value, as required
* by the Init_FLL_Settle() function. */
unsigned long ulCPU_Clock_KHz = req_clock_rate / 1000UL;
//Make sure we aren't overclocking
if(ulCPU_Clock_KHz > 25000L)
{
ulCPU_Clock_KHz = 25000L;
}
//Set VCore to a level sufficient for the requested clock speed.
if(ulCPU_Clock_KHz <= 8000L)
{
SetVCore(PMMCOREV_0);
}
else if(ulCPU_Clock_KHz <= 12000L)
{
SetVCore(PMMCOREV_1);
}
else if(ulCPU_Clock_KHz <= 20000L)
{
SetVCore(PMMCOREV_2);
}
else
{
SetVCore(PMMCOREV_3);
}
//Set the DCO
Init_FLL_Settle( ( unsigned short )ulCPU_Clock_KHz, req_clock_rate / ref_clock_rate );
}

View file

@ -27,5 +27,6 @@ static void halBoardGetSystemClockSettings(unsigned char systemClockSpeed,
extern void halBoardOutputSystemClock(void);
extern void halBoardStopOutputSystemClock(void);
extern void halBoardInit(void);
void hal430SetSystemClock(unsigned long req_clock_rate, unsigned long ref_clock_rate);
#endif /* HAL_BOARD_H */

View file

@ -528,10 +528,6 @@ static xQueueMessage xStatusMessage = { mainMESSAGE_STATUS, pdPASS };
static void prvSetupHardware( void )
{
/* Convert a Hz value to a KHz value, as required by the Init_FLL_Settle()
function. */
unsigned long ulCPU_Clock_KHz = ( configCPU_CLOCK_HZ / 1000UL );
taskDISABLE_INTERRUPTS();
/* Disable the watchdog. */
@ -540,7 +536,7 @@ unsigned long ulCPU_Clock_KHz = ( configCPU_CLOCK_HZ / 1000UL );
halBoardInit();
LFXT_Start( XT1DRIVE_0 );
Init_FLL_Settle( ( unsigned short ) ulCPU_Clock_KHz, 488 );
hal430SetSystemClock( configCPU_CLOCK_HZ, configLFXT_CLOCK_HZ );
halButtonsInit( BUTTON_ALL );
halButtonsInterruptEnable( BUTTON_SELECT );