From da19497e87298884e6b7c23b2892bb25cb12ef82 Mon Sep 17 00:00:00 2001 From: patacongo Date: Sat, 21 May 2011 16:30:18 +0000 Subject: Completes coding portion of basic PIC32 port git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@3637 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/arch/mips/src/pic32mx/Make.defs | 4 +- nuttx/arch/mips/src/pic32mx/pic32mx-bmx.h | 166 ++++++++++++++++++++++ nuttx/arch/mips/src/pic32mx/pic32mx-che.h | 33 +++-- nuttx/arch/mips/src/pic32mx/pic32mx-clockconfig.c | 93 ------------ nuttx/arch/mips/src/pic32mx/pic32mx-internal.h | 11 -- nuttx/arch/mips/src/pic32mx/pic32mx-lowinit.c | 149 ++++++++++++++++--- 6 files changed, 315 insertions(+), 141 deletions(-) create mode 100755 nuttx/arch/mips/src/pic32mx/pic32mx-bmx.h delete mode 100644 nuttx/arch/mips/src/pic32mx/pic32mx-clockconfig.c (limited to 'nuttx/arch/mips') diff --git a/nuttx/arch/mips/src/pic32mx/Make.defs b/nuttx/arch/mips/src/pic32mx/Make.defs index 193834974..3a46c3078 100755 --- a/nuttx/arch/mips/src/pic32mx/Make.defs +++ b/nuttx/arch/mips/src/pic32mx/Make.defs @@ -61,8 +61,8 @@ endif # Required PIC32MX files CHIP_ASRCS = -CHIP_CSRCS = pic32mx-irq.c pic32mx-clockconfig.c pic32mx-decodeirq.c pic32mx-dobev.c \ - pic32mx-lowconsole.c pic32mx-lowinit.c pic32mx-serial.c pic32mx-timerisr.c +CHIP_CSRCS = pic32mx-irq.c pic32mx-decodeirq.c pic32mx-dobev.c pic32mx-lowconsole.c \ + pic32mx-lowinit.c pic32mx-serial.c pic32mx-timerisr.c # Configuration-dependent PIC32MX files diff --git a/nuttx/arch/mips/src/pic32mx/pic32mx-bmx.h b/nuttx/arch/mips/src/pic32mx/pic32mx-bmx.h new file mode 100755 index 000000000..1135627f3 --- /dev/null +++ b/nuttx/arch/mips/src/pic32mx/pic32mx-bmx.h @@ -0,0 +1,166 @@ +/******************************************************************************************** + * arch/mips/src/pic32mx/pic32mx-bmx.h + * + * Copyright (C) 2011 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. + * + ********************************************************************************************/ + +#ifndef __ARCH_MIPS_SRC_PIC32MX_PIC32MX_BMX_H +#define __ARCH_MIPS_SRC_PIC32MX_PIC32MX_BMX_H + +/******************************************************************************************** + * Included Files + ********************************************************************************************/ + +#include + +#include "pic32mx-memorymap.h" + +/******************************************************************************************** + * Pre-Processor Definitions + ********************************************************************************************/ +/* Register Offsets *************************************************************************/ + +#define PIC32MX_BMX_CON_OFFSET 0x0000 /* Configuration Register */ +#define PIC32MX_BMX_CONCLR_OFFSET 0x0000 /* Configuration Clear Register */ +#define PIC32MX_BMX_CONSET_OFFSET 0x0004 /* Configuration Set Register */ +#define PIC32MX_BMX_CONINV_OFFSET 0x0008 /* Configuration Invert Register */ +#define PIC32MX_BMX_DKPBA_OFFSET 0x001c /* Data RAM Kernel Program Base Address Register */ +#define PIC32MX_BMX_DKPBACLR_OFFSET 0x0010 /* Data RAM Kernel Program Base Address Clear Register */ +#define PIC32MX_BMX_DKPBASET_OFFSET 0x0014 /* Data RAM Kernel Program Base Address Set Register */ +#define PIC32MX_BMX_DKPBAINV_OFFSET 0x0018 /* Data RAM Kernel Program Base Address Invert Register */ +#define PIC32MX_BMX_DUDBA_OFFSET 0x002c /* Data RAM User Data Base Address Register */ +#define PIC32MX_BMX_DUDBACLR_OFFSET 0x0020 /* Data RAM User Data Base Address Clear Register */ +#define PIC32MX_BMX_DUDBASET_OFFSET 0x0024 /* Data RAM User Data Base Address Set Register */ +#define PIC32MX_BMX_DUDBAINV_OFFSET 0x0028 /* Data RAM User Data Base Address Invert Register */ +#define PIC32MX_BMX_DUPBA_OFFSET 0x003c /* Data RAM User Program Base Address Register */ +#define PIC32MX_BMX_DUPBACLR_OFFSET 0x0030 /* Data RAM User Program Base Address Clear Register */ +#define PIC32MX_BMX_DUPBASET_OFFSET 0x0034 /* Data RAM User Program Base Address Set Register */ +#define PIC32MX_BMX_DUPBAINV_OFFSET 0x0038 /* Data RAM User Program Base Address Invert Register */ +#define PIC32MX_BMX_DRMSZ_OFFSET 0x0040 /* Data RAM Size Register */ +#define PIC32MX_BMX_PUPBA_OFFSET 0x0050 /* Program Flash (PFM) User Program Base Address Register */ +#define PIC32MX_BMX_PUPBACLR_OFFSET 0x0054 /* Program Flash (PFM) User Program Base Address Clear Register */ +#define PIC32MX_BMX_PUPBASET_OFFSET 0x0058 /* Program Flash (PFM) User Program Base Address Set Register */ +#define PIC32MX_BMX_PUPBINVA_OFFSET 0x005c /* Program Flash (PFM) User Program Base Address Invert Register */ +#define PIC32MX_BMX_PFMSZ_OFFSET 0x0060 /* Program Flash Size Register */ +#define PIC32MX_BMX_BOOTSZ_OFFSET 0x0070 /* Boot Flash Size Register */ + +/* Register Addresses ***********************************************************************/ + +#define PIC32MX_BMX_CON (PIC32MX_BMX_K1BASE+PIC32MX_BMX_CON_OFFSET) +#define PIC32MX_BMX_CONCLR (PIC32MX_BMX_K1BASE+PIC32MX_BMX_CONCLR_OFFSET) +#define PIC32MX_BMX_CONSET (PIC32MX_BMX_K1BASE+PIC32MX_BMX_CONSET_OFFSET) +#define PIC32MX_BMX_CONINV (PIC32MX_BMX_K1BASE+PIC32MX_BMX_CONINV_OFFSET) +#define PIC32MX_BMX_DKPBA (PIC32MX_BMX_K1BASE+PIC32MX_BMX_DKPBA_OFFSET) +#define PIC32MX_BMX_DKPBACLR (PIC32MX_BMX_K1BASE+PIC32MX_BMX_DKPBACLR_OFFSET) +#define PIC32MX_BMX_DKPBASET (PIC32MX_BMX_K1BASE+PIC32MX_BMX_DKPBASET_OFFSET) +#define PIC32MX_BMX_DKPBAINV (PIC32MX_BMX_K1BASE+PIC32MX_BMX_DKPBAINV_OFFSET) +#define PIC32MX_BMX_DUDBA (PIC32MX_BMX_K1BASE+PIC32MX_BMX_DUDBA_OFFSET) +#define PIC32MX_BMX_DUDBACLR (PIC32MX_BMX_K1BASE+PIC32MX_BMX_DUDBACLR_OFFSET) +#define PIC32MX_BMX_DUDBASET (PIC32MX_BMX_K1BASE+PIC32MX_BMX_DUDBASET_OFFSET) +#define PIC32MX_BMX_DUDBAINV (PIC32MX_BMX_K1BASE+PIC32MX_BMX_DUDBAINV_OFFSET) +#define PIC32MX_BMX_DUPBA (PIC32MX_BMX_K1BASE+PIC32MX_BMX_DUPBA_OFFSET) +#define PIC32MX_BMX_DUPBACLR (PIC32MX_BMX_K1BASE+PIC32MX_BMX_DUPBACLR_OFFSET) +#define PIC32MX_BMX_DUPBASET (PIC32MX_BMX_K1BASE+PIC32MX_BMX_DUPBASET_OFFSET) +#define PIC32MX_BMX_DUPBAINV (PIC32MX_BMX_K1BASE+PIC32MX_BMX_DUPBAINV_OFFSET) +#define PIC32MX_BMX_DRMSZ (PIC32MX_BMX_K1BASE+PIC32MX_BMX_DRMSZ_OFFSET) +#define PIC32MX_BMX_PUPBA (PIC32MX_BMX_K1BASE+PIC32MX_BMX_PUPBA_OFFSET) +#define PIC32MX_BMX_PUPBACLR (PIC32MX_BMX_K1BASE+PIC32MX_BMX_PUPBACLR_OFFSET) +#define PIC32MX_BMX_PUPBASET (PIC32MX_BMX_K1BASE+PIC32MX_BMX_PUPBASET_OFFSET) +#define PIC32MX_BMX_PUPBINVA (PIC32MX_BMX_K1BASE+PIC32MX_BMX_PUPBINVA_OFFSET) +#define PIC32MX_BMX_PFMSZ (PIC32MX_BMX_K1BASE+PIC32MX_BMX_PFMSZ_OFFSET) +#define PIC32MX_BMX_BOOTSZ (PIC32MX_BMX_K1BASE+PIC32MX_BMX_BOOTSZ_OFFSET) + +/* Register Bit-Field Definitions ***********************************************************/ + +/* Configuration Register */ + +#define BMX_CON_BMXARB_SHIFT (0) /* Bits 0-2: : Bus matrix arbitration mode */ +#define BMX_CON_BMXARB_MASK (7 << BMX_CON_BMXARB_SHIFT) +# define BMX_CON_BMXARB(n) ((n) << BMX_CON_BMXARB_SHIFT) /* Mode n, n=0,1,2 */ +#define BMX_CON_BMXWSDRM (1 << 6) /* Bit 6: CPU Instruction or data access from data RAM wait state */ +#define BMX_CON_BMXERRIS (1 << 16) /* Bit 16: Bus error from CPU instruction access */ +#define BMX_CON_BMXERRDS (1 << 17) /* Bit 17: Bus error from CPU data access */ +#define BMX_CON_BMXERRDMA (1 << 18) /* Bit 18: Bus error from DMA */ +#define BMX_CON_BMXERRICD (1 << 19) /* Bit 19: Enable bus error from ICD debug unit */ +#define BMX_CON_BMXERRIXI (1 << 20) /* Bit 20: Enable bus error from IXI */ +#define BMX_CON_BMXCHEDMA (1 << 26) /* Bit 26: BMX PFM cacheability for DMA accesses */ + +/* Data RAM Kernel Program Base Address Register */ + +#define BMX_DKPBA_MASK 0x0000ffff /* Bits 0-15 */ + +/* Data RAM User Data Base Address Register */ + +#define BMX_DUDBA_MASK 0x0000ffff /* Bits 0-15 */ + +/* Data RAM User Program Base Address Register */ + +#define BMX_DUPBA_MASK 0x0000ffff /* Bits 0-15 */ + +/* Data RAM Size Register -- 32-bit size value */ + +/* Program Flash (PFM) User Program Base Address Register */ + +#define BMX_PUPBA_MASK 0x000fffff /* Bits 0-19 */ + +/* Program Flash Size Register -- 32-bit size value */ + +/* Boot Flash Size Register -- 32-bit size value */ + +/******************************************************************************************** + * Public Types + ********************************************************************************************/ + +#ifndef __ASSEMBLY__ + +/******************************************************************************************** + * Inline Functions + ********************************************************************************************/ + +/******************************************************************************************** + * Public Function Prototypes + ********************************************************************************************/ + +#ifdef __cplusplus +#define EXTERN extern "C" +extern "C" { +#else +#define EXTERN extern +#endif + +#undef EXTERN +#ifdef __cplusplus +} +#endif + +#endif /* __ASSEMBLY__ */ +#endif /* __ARCH_MIPS_SRC_PIC32MX_PIC32MX_BMX_H */ diff --git a/nuttx/arch/mips/src/pic32mx/pic32mx-che.h b/nuttx/arch/mips/src/pic32mx/pic32mx-che.h index 3eadccf2a..c4b0913a2 100755 --- a/nuttx/arch/mips/src/pic32mx/pic32mx-che.h +++ b/nuttx/arch/mips/src/pic32mx/pic32mx-che.h @@ -106,32 +106,41 @@ /* Pre-fetch cache control register */ -#define CHE_CON_PFMWS_SHIFT (0) /* Bits 0-2: xx */ +#define CHE_CON_PFMWS_SHIFT (0) /* Bits 0-2: PFM access time (SYSCLK wait states) */ #define CHE_CON_PFMWS_MASK (7 << CHE_CON_PFMWS_SHIFT) -#define CHE_CON_PREFEN_SHIFT (4) /* Bits 4-5: xx */ +# define CHE_CON_PFMWS(n) ((n) << CHE_CON_PFMWS_SHIFT) /* n wait states, n=0-7 */ +#define CHE_CON_PREFEN_SHIFT (4) /* Bits 4-5: Predictive pre-fetch cache enable */ #define CHE_CON_PREFEN_MASK (3 << CHE_CON_PREFEN_SHIFT) -#define CHE_CON_DCSZ_SHIFT (8) /* Bits 8-9: xx */ +# define CHE_CON_PREFEN_DISABLE (0 << CHE_CON_PREFEN_SHIFT) /* Disable predictive pre-fetch cache */ +# define CHE_CON_PREFEN_CACHE (1 << CHE_CON_PREFEN_SHIFT) /* Enable for cacheable regions only */ +# define CHE_CON_PREFEN_NONCACHE (2 << CHE_CON_PREFEN_SHIFT) /* Enable for non-cacheable regions only */ +# define CHE_CON_PREFEN_ALL (3 << CHE_CON_PREFEN_SHIFT) /* Enable for both regions */ +#define CHE_CON_DCSZ_SHIFT (8) /* Bits 8-9: Data cache size (lines) */ #define CHE_CON_DCSZ_MASK (3 << CHE_CON_DCSZ_SHIFT) -#define CHE_CON_CHECOH (1 << 16) /* Bit 16: xx */ +# define CHE_CON_DCSZ_DISABLE (0 << CHE_CON_DCSZ_SHIFT) /* Disable data caching */ +# define CHE_CON_DCSZ_1LINE (1 << CHE_CON_DCSZ_SHIFT) /* Enable with size of 1 line */ +# define CHE_CON_DCSZ_2LINES (2 << CHE_CON_DCSZ_SHIFT) /* Enable with size of 2 lines */ +# define CHE_CON_DCSZ_4LINES (3 << CHE_CON_DCSZ_SHIFT) /* Enable with size of 4 lines */ +#define CHE_CON_CHECOH (1 << 16) /* Bit 16: Cache coherency setting */ /* Pre-fetch cache access register */ -#define CHE_ACC_CHEIDX_SHIFT (0) /* Bits 0-3: xx */ +#define CHE_ACC_CHEIDX_SHIFT (0) /* Bits 0-3: Cache line index */ #define CHE_ACC_CHEIDX_MASK (15 << CHE_ACC_CHEIDX_SHIFT) -#define CHE_ACC_CHEWEN (1 << 31) /* Bit 31: xx */ +#define CHE_ACC_CHEWEN (1 << 31) /* Bit 31: Cache access enable */ /* Pre-fetch cache tag register */ -#define CHE_TAG_LTYPE (1 << 1) /* Bit 1: xx */ -#define CHE_TAG_LLOCK (1 << 2) /* Bit 2: xx */ -#define CHE_TAG_LVALID (1 << 3) /* Bit 3: xx */ -#define CHE_TAG_LTAG_SHIFT (4) /* Bits 4-23: xx */ +#define CHE_TAG_LTYPE (1 << 1) /* Bit 1: Line type */ +#define CHE_TAG_LLOCK (1 << 2) /* Bit 2: Line lock */ +#define CHE_TAG_LVALID (1 << 3) /* Bit 3: Line valid */ +#define CHE_TAG_LTAG_SHIFT (4) /* Bits 4-23: Line tag address */ #define CHE_TAG_LTAG_MASK (0x000fffff << CHE_TAG_LTAG_SHIFT) -#define CHE_TAG_LTAGBOOT (1 << 31) /* Bit 31: xx */ +#define CHE_TAG_LTAGBOOT (1 << 31) /* Bit 31: Line tag address boot */ /* Pre-fetch cache tag mask register */ -#define CHE_MSK_SHIFT (5) /* Bits 5-15: xx */ +#define CHE_MSK_SHIFT (5) /* Bits 5-15: Line mask */ #define CHE_MSK_MASK (0x7ff << CHE_MSK_SHIFT) /* Cache word 0-3 register -- 32-bit cache line data */ diff --git a/nuttx/arch/mips/src/pic32mx/pic32mx-clockconfig.c b/nuttx/arch/mips/src/pic32mx/pic32mx-clockconfig.c deleted file mode 100644 index de2bc8dc2..000000000 --- a/nuttx/arch/mips/src/pic32mx/pic32mx-clockconfig.c +++ /dev/null @@ -1,93 +0,0 @@ -/************************************************************************** - * arch/mips/src/pic32mx/pic32mx-clockconfig.c - * - * Copyright (C) 2011 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 "up_arch.h" -#include "up_internal.h" - -#include "pic32mx-config.h" -#include "pic32mx-internal.h" - -/************************************************************************** - * Private Definitions - **************************************************************************/ - -/************************************************************************** - * Private Types - **************************************************************************/ - -/************************************************************************** - * Private Function Prototypes - **************************************************************************/ - -/************************************************************************** - * Global Variables - **************************************************************************/ - -/************************************************************************** - * Private Variables - **************************************************************************/ - -/************************************************************************** - * Private Functions - **************************************************************************/ - -/************************************************************************** - * Public Functions - **************************************************************************/ - -/************************************************************************** - * Name: pic32mx_clockconfig - * - * Description: - * Called by pic32mx_lowinitto initialize the PIC32MX clocking using the - * settings in board.h. - * - **************************************************************************/ - -void pic32mx_clockconfig(void) -{ -# warning "Missing logic" -} - - - diff --git a/nuttx/arch/mips/src/pic32mx/pic32mx-internal.h b/nuttx/arch/mips/src/pic32mx/pic32mx-internal.h index 45bfaf11a..0c3392b30 100755 --- a/nuttx/arch/mips/src/pic32mx/pic32mx-internal.h +++ b/nuttx/arch/mips/src/pic32mx/pic32mx-internal.h @@ -129,17 +129,6 @@ extern "C" { EXTERN void pic32mx_lowinit(void); -/************************************************************************************ - * Name: pic32mx_clockconfig - * - * Description: - * Called by pic32mx_lowinit to initialize the PIC32MX clocking using the settings - * in board.h. - * - ************************************************************************************/ - -EXTERN void pic32mx_clockconfig(void); - /************************************************************************************ * Name: pic32mx_lowsetup * diff --git a/nuttx/arch/mips/src/pic32mx/pic32mx-lowinit.c b/nuttx/arch/mips/src/pic32mx/pic32mx-lowinit.c index f4fd904ad..ad2b8bf1f 100644 --- a/nuttx/arch/mips/src/pic32mx/pic32mx-lowinit.c +++ b/nuttx/arch/mips/src/pic32mx/pic32mx-lowinit.c @@ -1,4 +1,4 @@ -/************************************************************************** +/**************************************************************************** * arch/mips/src/pic32/pic32mx-lowinit.c * * Copyright (C) 2011 Gregory Nutt. All rights reserved. @@ -31,58 +31,161 @@ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. * - **************************************************************************/ + ****************************************************************************/ -/************************************************************************** +/**************************************************************************** * Included Files - **************************************************************************/ + ****************************************************************************/ #include +#include + +#include + #include "up_internal.h" +#include "up_arch.h" + #include "pic32mx-internal.h" +#include "pic32mx-bmx.h" +#include "pic32mx-che.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ +/* Maximum Frequencies ******************************************************/ + +#define MAX_FLASH_HZ 30000000 /* Maximum FLASH speed (Hz) */ +#define MAX_PBCLOCK 80000000 /* Max peripheral bus speed (Hz) */ + +/* Sanity checks ************************************************************/ + +/* Make sure that the selected clock parameters are sane */ + +#define CALC_SYSCLOCK (((BOARD_POSC_FREQ / BOARD_PLL_IDIV) * BOARD_PLL_MULT) / BOARD_PLL_ODIV) +#if CALC_SYSCLOCK != BOARD_CPU_CLOCK +# error "Bad BOARD_CPU_CLOCK calculcation in board.h" +#endif + +#define CALC_PBCLOCK (CALC_SYSCLOCK / BOARD_PBDIV) +#if CALC_PBCLOCK != BOARD_PBCLOCK +# error "Bad BOARD_PBCLOCK calculcation in board.h" +#endif -/************************************************************************** - * Private Definitions - **************************************************************************/ +#if CALC_PBCLOCK > MAX_PBCLOCK +# error "PBCLOCK exceeds maximum value" +#endif -/************************************************************************** +/**************************************************************************** * Private Types - **************************************************************************/ + ****************************************************************************/ -/************************************************************************** +/**************************************************************************** * Private Function Prototypes - **************************************************************************/ + ****************************************************************************/ -/************************************************************************** +/**************************************************************************** * Global Variables - **************************************************************************/ + ****************************************************************************/ -/************************************************************************** +/**************************************************************************** * Private Variables - **************************************************************************/ + ****************************************************************************/ -/************************************************************************** +/**************************************************************************** * Private Functions - **************************************************************************/ + ****************************************************************************/ + +/**************************************************************************** + * Name: pic32mx_waitstates + * + * Description: + * Configure the optimal number of FLASH wait states. + * + * Assumptions: + * Interrupts are disabled. + * + ****************************************************************************/ + +static inline void pic32mx_waitstates(void) +{ + unsigned int nwaits; + unsigned int residual; + + /* Disable DRM wait states */ -/************************************************************************** + putreg32(BMX_CON_BMXWSDRM, PIC32MX_BMX_CONCLR); + + /* Configure pre-fetch cache FLASH wait states */ + + residual = BOARD_CPU_CLOCK; + nwaits = 0; + + while(residual > MAX_FLASH_HZ) + { + nwaits++; + residual -= MAX_FLASH_HZ; + } + DEBUGASSERT(nwaits < 8); + + /* Set the FLASH wait states -- clearing all other bits! */ + + putreg32(nwaits, PIC32MX_CHE_CON); +} + +/**************************************************************************** + * Name: pic32mx_cache + * + * Description: + * Enable caching. + * + * Assumptions: + * Interrupts are disabled. + * + ****************************************************************************/ + +static inline void pic32mx_cache(void) +{ + register uint32_t regval; + + /* Enable caching on all regions */ + + regval = getreg32(PIC32MX_CHE_CON); + regval |= CHE_CON_PREFEN_ALL; + putreg32(regval, PIC32MX_CHE_CON); + + /* Enable cache on KSEG 0 in the CP0 CONFIG register*/ + + asm("\tmfc0 %0,$16,0\n" : "=r"(regval)); + regval &= ~CP0_CONFIG_K23_MASK; + regval |= CP0_CONFIG_K23_CACHEABLE; + asm("\tmtc0 %0,$16,0\n" : : "r" (regval)); +} + +/**************************************************************************** * Public Functions - **************************************************************************/ + ****************************************************************************/ -/************************************************************************** +/**************************************************************************** * Name: pic32mx_lowinit * * Description: * This performs basic low-level initialization of the system. * - **************************************************************************/ + * Assumptions: + * Interrupts have not yet been enabled. + * + ****************************************************************************/ void pic32mx_lowinit(void) { - /* Initialize MCU clocking */ + /* Initialize FLASH wait states */ + + pic32mx_waitstates(); + + /* Enable caching */ - pic32mx_clockconfig(); + pic32mx_cache();; /* Initialize a console (probably a serial console) */ -- cgit v1.2.3