summary | shortlog | log | commit | commitdiff | tree
raw | patch | inline | side by side (parent: dfc5c91)
raw | patch | inline | side by side (parent: dfc5c91)
author | Borja Martinez <borja.martinez@gmail.com> | |
Sat, 10 Sep 2016 17:48:13 +0000 (19:48 +0200) | ||
committer | Borja Martinez <borja.martinez@gmail.com> | |
Sat, 10 Sep 2016 17:48:13 +0000 (19:48 +0200) |
Basic-Test-Package/MSP432/Test_MSP432_DebugUART_EchoPC/i3mote.h | [new file with mode: 0644] | patch | blob |
Basic-Test-Package/MSP432/Test_MSP432_DebugUART_EchoPC/main.c | [new file with mode: 0644] | patch | blob |
Basic-Test-Package/MSP432/Test_MSP432_DebugUART_EchoPC/msp432p401r.cmd | [new file with mode: 0644] | patch | blob |
Basic-Test-Package/MSP432/Test_MSP432_DebugUART_EchoPC/startup_msp432p401r_ccs.c | [new file with mode: 0644] | patch | blob |
Basic-Test-Package/MSP432/Test_MSP432_DebugUART_EchoPC/system_msp432p401r.c | [new file with mode: 0644] | patch | blob |
diff --git a/Basic-Test-Package/MSP432/Test_MSP432_DebugUART_EchoPC/i3mote.h b/Basic-Test-Package/MSP432/Test_MSP432_DebugUART_EchoPC/i3mote.h
--- /dev/null
@@ -0,0 +1,25 @@
+/* Rev.B */
+#define HID_PORT GPIO_PORT_P6
+#define LEDR GPIO_PIN2
+#define LEDG GPIO_PIN3
+#define BUTTON GPIO_PIN1
+
+
+/* Rev.A
+#define LED_PORT GPIO_PORT_P8
+#define LEDR GPIO_PIN5
+#define LEDG GPIO_PIN6
+#define BUTTON GPIO_PIN7
+*/
+
+
+/* On Board EEPROM 25xx256*/
+#define EEPROM_SLAVE_ADDRESS 0x50
+
+
+/* Debg UART */
+#define UART_BAUD_115200
+#define UART_PORT GPIO_PORT_P1
+#define UART_TX_PIN GPIO_PIN3
+#define UART_RX_PIN GPIO_PIN2
+
diff --git a/Basic-Test-Package/MSP432/Test_MSP432_DebugUART_EchoPC/main.c b/Basic-Test-Package/MSP432/Test_MSP432_DebugUART_EchoPC/main.c
--- /dev/null
@@ -0,0 +1,146 @@
+/******************************************************************************
+ * MSP432 UART - PC Echo with 12MHz BRCLK
+ *
+ * Description: This demo echoes back characters received via a PC serial port.
+ * SMCLK/DCO is used as a clock source and the device is put in LPM0
+ * The auto-clock enable feature is used by the eUSCI and SMCLK is turned off
+ * when the UART is idle and turned on when a receive edge is detected.
+ * Note that level shifter hardware is needed to shift between RS232 and MSP
+ * voltage levels.
+ *
+ * MSP432P401
+ * -----------------
+ * | |
+ * | |
+ * | |
+ * RST -| P1.3/UCA0TXD|----> PC (echo)
+ * | |
+ * | |
+ * | P1.2/UCA0RXD|<---- PC
+ * | |
+ *
+ * Author: Timothy Logan
+ *
+ * I3Mote Version: B.Martinez
+ *
+ *
+ *
+*******************************************************************************/
+#include "i3mote.h"
+
+/* DriverLib Includes */
+#include "driverlib.h"
+
+
+/* Standard Includes */
+#include <stdint.h>
+#include <stdbool.h>
+
+#define SYSFREQ 12000000
+
+/* UART Configuration Parameter. These are the configuration parameters to
+ * make the eUSCI A UART module to operate with a 9600 baud rate.
+ * These values were calculated using the online calculator that TI provides at:
+ * http://software-dl.ti.com/msp430/msp430_public_sw/mcu/msp430/MSP430BaudRateConverter/index.html
+ */
+
+#ifdef UART_BAUD_9600
+ const eUSCI_UART_Config uartConfig =
+ {
+ EUSCI_A_UART_CLOCKSOURCE_SMCLK, // SMCLK Clock Source
+ 78, // BRDIV = 78
+ 2, // UCxBRF = 2
+ 0, // UCxBRS = 0
+ EUSCI_A_UART_NO_PARITY, // No Parity
+ EUSCI_A_UART_LSB_FIRST, // LSB First
+ EUSCI_A_UART_ONE_STOP_BIT, // One stop bit
+ EUSCI_A_UART_MODE, // UART mode
+ EUSCI_A_UART_OVERSAMPLING_BAUDRATE_GENERATION // Oversampling
+ };
+#endif
+
+#ifdef UART_BAUD_115200
+ const eUSCI_UART_Config uartConfig =
+ {
+ EUSCI_A_UART_CLOCKSOURCE_SMCLK, // SMCLK Clock Source
+ 6, // BRDIV = 6
+ 8, // UCxBRF = 8
+ 32, // UCxBRS = 32
+ EUSCI_A_UART_NO_PARITY, // No Parity
+ EUSCI_A_UART_LSB_FIRST, // LSB First
+ EUSCI_A_UART_ONE_STOP_BIT, // One stop bit
+ EUSCI_A_UART_MODE, // UART mode
+ EUSCI_A_UART_OVERSAMPLING_BAUDRATE_GENERATION // Oversampling
+ };
+#endif
+
+
+
+int main(void)
+{
+
+ /* Halting WDT */
+ MAP_WDT_A_holdTimer();
+
+ /* Selecting P1.2 and P1.3 in UART mode */
+ MAP_GPIO_setAsPeripheralModuleFunctionInputPin(UART_PORT,
+ UART_RX_PIN | UART_TX_PIN, GPIO_PRIMARY_MODULE_FUNCTION);
+
+ /* LEDS Configuring P8.x as output */
+ MAP_GPIO_setAsOutputPin(HID_PORT,LEDG|LEDR);
+ MAP_GPIO_setOutputLowOnPin(HID_PORT,LEDG|LEDR);
+
+ /* Setting DCO to 12MHz */
+ #if SYSFREQ==12000000
+ CS_setDCOCenteredFrequency(CS_DCO_FREQUENCY_12);
+ #else
+ #error "Undefinde CLock Frequency"
+ #endif
+
+ /* Configuring UART Module */
+ MAP_UART_initModule(EUSCI_A0_BASE, &uartConfig);
+
+ /* Enable UART module */
+ MAP_UART_enableModule(EUSCI_A0_BASE);
+
+ /* Enabling UART interrupts */
+ MAP_UART_enableInterrupt(EUSCI_A0_BASE, EUSCI_A_UART_RECEIVE_INTERRUPT);
+ MAP_Interrupt_enableInterrupt(INT_EUSCIA0);
+ MAP_Interrupt_enableSleepOnIsrExit();
+ MAP_Interrupt_enableMaster();
+
+ /* Enable SysTick (Toggle 0.5s) */
+ MAP_SysTick_enableModule();
+ MAP_SysTick_setPeriod(SYSFREQ/2);
+ MAP_SysTick_enableInterrupt();
+
+ /* Enabling MASTER interrupts */
+ MAP_Interrupt_enableMaster();
+
+ while(1)
+ {
+ MAP_PCM_gotoLPM0();
+ }
+}
+
+/* EUSCI A0 UART ISR - Echoes data back to PC host */
+void EUSCIA0_IRQHandler(void)
+{
+ uint32_t status = MAP_UART_getEnabledInterruptStatus(EUSCI_A0_BASE);
+
+ MAP_UART_clearInterruptFlag(EUSCI_A0_BASE, status);
+
+ if(status & EUSCI_A_UART_RECEIVE_INTERRUPT)
+ {
+ MAP_UART_transmitData(EUSCI_A0_BASE, MAP_UART_receiveData(EUSCI_A0_BASE));
+ }
+
+}
+
+void SysTick_Handler(void)
+{
+ MAP_GPIO_toggleOutputOnPin(HID_PORT,LEDG);
+}
+
+
+
diff --git a/Basic-Test-Package/MSP432/Test_MSP432_DebugUART_EchoPC/msp432p401r.cmd b/Basic-Test-Package/MSP432/Test_MSP432_DebugUART_EchoPC/msp432p401r.cmd
--- /dev/null
@@ -0,0 +1,84 @@
+/******************************************************************************
+*
+* Copyright (C) 2012 - 2015 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.
+*
+* Default linker command file for Texas Instruments MSP432P401R
+*
+* File creation date: 2015-09-03
+*
+*****************************************************************************/
+
+--retain=flashMailbox
+
+MEMORY
+{
+ MAIN (RX) : origin = 0x00000000, length = 0x00040000
+ INFO (RX) : origin = 0x00200000, length = 0x00004000
+ SRAM_CODE (RWX): origin = 0x01000000, length = 0x00010000
+ SRAM_DATA (RW) : origin = 0x20000000, length = 0x00010000
+}
+
+/* The following command line options are set as part of the CCS project. */
+/* If you are building using the command line, or for some reason want to */
+/* define them here, you can uncomment and modify these lines as needed. */
+/* If you are using CCS for building, it is probably better to make any such */
+/* modifications in your CCS project and leave this file alone. */
+/* */
+/* A heap size of 1024 bytes is recommended when you plan to use printf() */
+/* for debug output to the console window. */
+/* */
+/* --heap_size=1024 */
+/* --stack_size=512 */
+/* --library=rtsv7M4_T_le_eabi.lib */
+
+/* Section allocation in memory */
+
+SECTIONS
+{
+ .intvecs: > 0x00000000
+ .text : > MAIN
+ .const : > MAIN
+ .cinit : > MAIN
+ .pinit : > MAIN
+ .init_array : > MAIN
+
+ .flashMailbox : > 0x00200000
+
+ .vtable : > 0x20000000
+ .data : > SRAM_DATA
+ .bss : > SRAM_DATA
+ .sysmem : > SRAM_DATA
+ .stack : > SRAM_DATA (HIGH)
+}
+
+/* Symbolic definition of the WDTCTL register for RTS */
+WDTCTL_SYM = 0x4000480C;
+
diff --git a/Basic-Test-Package/MSP432/Test_MSP432_DebugUART_EchoPC/startup_msp432p401r_ccs.c b/Basic-Test-Package/MSP432/Test_MSP432_DebugUART_EchoPC/startup_msp432p401r_ccs.c
--- /dev/null
@@ -0,0 +1,255 @@
+/*
+ * -------------------------------------------
+ * MSP432 DriverLib - v3_10_00_09
+ * -------------------------------------------
+ *
+ * --COPYRIGHT--,BSD,BSD
+ * Copyright (c) 2014, Texas Instruments Incorporated
+ * All rights reserved.
+ *
+ * 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.
+ * --/COPYRIGHT--*/
+//*****************************************************************************
+//
+// Copyright (C) 2012 - 2015 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.
+//
+// MSP432 Family Interrupt Vector Table for CGT
+//
+//****************************************************************************
+
+#include <stdint.h>
+
+/* Forward declaration of the default fault handlers. */
+static void resetISR(void);
+static void nmiISR(void);
+static void faultISR(void);
+static void defaultISR(void);
+
+
+/* External declaration for the reset handler that is to be called when the */
+/* processor is started */
+extern void _c_int00(void);
+
+/* External declaration for system initialization function */
+extern void SystemInit(void);
+
+/* Linker variable that marks the top of the stack. */
+extern unsigned long __STACK_END;
+
+
+/* External declarations for the interrupt handlers used by the application. */
+extern void EUSCIA0_IRQHandler (void);
+extern void SysTick_Handler(void);
+
+
+/* Interrupt vector table. Note that the proper constructs must be placed on this to */
+/* ensure that it ends up at physical address 0x0000.0000 or at the start of */
+/* the program if located at a start address other than 0. */
+#pragma RETAIN(interruptVectors)
+#pragma DATA_SECTION(interruptVectors, ".intvecs")
+void (* const interruptVectors[])(void) =
+{
+ (void (*)(void))((uint32_t)&__STACK_END),
+ /* The initial stack pointer */
+ resetISR, /* The reset handler */
+ nmiISR, /* The NMI handler */
+ faultISR, /* The hard fault handler */
+ defaultISR, /* The MPU fault handler */
+ defaultISR, /* The bus fault handler */
+ defaultISR, /* The usage fault handler */
+ 0, /* Reserved */
+ 0, /* Reserved */
+ 0, /* Reserved */
+ 0, /* Reserved */
+ defaultISR, /* SVCall handler */
+ defaultISR, /* Debug monitor handler */
+ 0, /* Reserved */
+ defaultISR, /* The PendSV handler */
+ SysTick_Handler, /* The SysTick handler */
+ defaultISR, /* PSS ISR */
+ defaultISR, /* CS ISR */
+ defaultISR, /* PCM ISR */
+ defaultISR, /* WDT ISR */
+ defaultISR, /* FPU ISR */
+ defaultISR, /* FLCTL ISR */
+ defaultISR, /* COMP0 ISR */
+ defaultISR, /* COMP1 ISR */
+ defaultISR, /* TA0_0 ISR */
+ defaultISR, /* TA0_N ISR */
+ defaultISR, /* TA1_0 ISR */
+ defaultISR, /* TA1_N ISR */
+ defaultISR, /* TA2_0 ISR */
+ defaultISR, /* TA2_N ISR */
+ defaultISR, /* TA3_0 ISR */
+ defaultISR, /* TA3_N ISR */
+ EUSCIA0_IRQHandler, /* EUSCIA0 ISR */
+ defaultISR, /* EUSCIA1 ISR */
+ defaultISR, /* EUSCIA2 ISR */
+ defaultISR, /* EUSCIA3 ISR */
+ defaultISR, /* EUSCIB0 ISR */
+ defaultISR, /* EUSCIB1 ISR */
+ defaultISR, /* EUSCIB2 ISR */
+ defaultISR, /* EUSCIB3 ISR */
+ defaultISR, /* ADC14 ISR */
+ defaultISR, /* T32_INT1 ISR */
+ defaultISR, /* T32_INT2 ISR */
+ defaultISR, /* T32_INTC ISR */
+ defaultISR, /* AES ISR */
+ defaultISR, /* RTC ISR */
+ defaultISR, /* DMA_ERR ISR */
+ defaultISR, /* DMA_INT3 ISR */
+ defaultISR, /* DMA_INT2 ISR */
+ defaultISR, /* DMA_INT1 ISR */
+ defaultISR, /* DMA_INT0 ISR */
+ defaultISR, /* PORT1 ISR */
+ defaultISR, /* PORT2 ISR */
+ defaultISR, /* PORT3 ISR */
+ defaultISR, /* PORT4 ISR */
+ defaultISR, /* PORT5 ISR */
+ defaultISR, /* PORT6 ISR */
+ defaultISR, /* Reserved 41 */
+ defaultISR, /* Reserved 42 */
+ defaultISR, /* Reserved 43 */
+ defaultISR, /* Reserved 44 */
+ defaultISR, /* Reserved 45 */
+ defaultISR, /* Reserved 46 */
+ defaultISR, /* Reserved 47 */
+ defaultISR, /* Reserved 48 */
+ defaultISR, /* Reserved 49 */
+ defaultISR, /* Reserved 50 */
+ defaultISR, /* Reserved 51 */
+ defaultISR, /* Reserved 52 */
+ defaultISR, /* Reserved 53 */
+ defaultISR, /* Reserved 54 */
+ defaultISR, /* Reserved 55 */
+ defaultISR, /* Reserved 56 */
+ defaultISR, /* Reserved 57 */
+ defaultISR, /* Reserved 58 */
+ defaultISR, /* Reserved 59 */
+ defaultISR, /* Reserved 60 */
+ defaultISR, /* Reserved 61 */
+ defaultISR, /* Reserved 62 */
+ defaultISR /* Reserved 63 */
+};
+
+
+/* This is the code that gets called when the processor first starts execution */
+/* following a reset event. Only the absolutely necessary set is performed, */
+/* after which the application supplied entry() routine is called. Any fancy */
+/* actions (such as making decisions based on the reset cause register, and */
+/* resetting the bits in that register) are left solely in the hands of the */
+/* application. */
+void resetISR(void)
+{
+ SystemInit();
+
+ /* Jump to the CCS C Initialization Routine. */
+ __asm(" .global _c_int00\n"
+ " b.w _c_int00");
+}
+
+/* This is the code that gets called when the processor receives a NMI. This */
+/* simply enters an infinite loop, preserving the system state for examination */
+/* by a debugger. */
+static void nmiISR(void)
+{
+ /* Fault trap exempt from ULP advisor */
+ #pragma diag_push
+ #pragma CHECK_ULP("-2.1")
+
+ /* Enter an infinite loop. */
+ while(1)
+ {
+ }
+
+ #pragma diag_pop
+}
+
+
+/* This is the code that gets called when the processor receives a fault */
+/* interrupt. This simply enters an infinite loop, preserving the system state */
+/* for examination by a debugger. */
+static void faultISR(void)
+{
+ /* Fault trap exempt from ULP advisor */
+ #pragma diag_push
+ #pragma CHECK_ULP("-2.1")
+
+ /* Enter an infinite loop. */
+ while(1)
+ {
+ }
+
+ #pragma diag_pop
+}
+
+
+/* This is the code that gets called when the processor receives an unexpected */
+/* interrupt. This simply enters an infinite loop, preserving the system state */
+/* for examination by a debugger. */
+static void defaultISR(void)
+{
+ /* Fault trap exempt from ULP advisor */
+ #pragma diag_push
+ #pragma CHECK_ULP("-2.1")
+
+ /* Enter an infinite loop. */
+ while(1)
+ {
+ }
+
+ #pragma diag_pop
+}
diff --git a/Basic-Test-Package/MSP432/Test_MSP432_DebugUART_EchoPC/system_msp432p401r.c b/Basic-Test-Package/MSP432/Test_MSP432_DebugUART_EchoPC/system_msp432p401r.c
--- /dev/null
@@ -0,0 +1,434 @@
+/*
+ * -------------------------------------------
+ * MSP432 DriverLib - v3_10_00_09
+ * -------------------------------------------
+ *
+ * --COPYRIGHT--,BSD,BSD
+ * Copyright (c) 2014, Texas Instruments Incorporated
+ * All rights reserved.
+ *
+ * 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.
+ * --/COPYRIGHT--*/
+/**************************************************************************//**
+* @file system_msp432p401r.c
+* @brief CMSIS Cortex-M4F Device Peripheral Access Layer Source File for
+* MSP432P401R
+* @version V1.00
+* @date 20-Oct-2015
+*
+* @note View configuration instructions embedded in comments
+*
+******************************************************************************/
+//*****************************************************************************
+//
+// Copyright (C) 2015 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 <stdint.h>
+#include "msp.h"
+
+/*--------------------- Configuration Instructions ----------------------------
+ 1. If you prefer to halt the Watchdog Timer, set __HALT_WDT to 1:
+ #define __HALT_WDT 1
+ 2. Insert your desired CPU frequency in Hz at:
+ #define __SYSTEM_CLOCK 3000000
+ 3. If you prefer the DC-DC power regulator (more efficient at higher
+ frequencies), set the __REGULATOR to 1:
+ #define __REGULATOR 1
+ *---------------------------------------------------------------------------*/
+
+/*--------------------- Watchdog Timer Configuration ------------------------*/
+// Halt the Watchdog Timer
+// <0> Do not halt the WDT
+// <1> Halt the WDT
+#define __HALT_WDT 1
+
+/*--------------------- CPU Frequency Configuration -------------------------*/
+// CPU Frequency
+// <1500000> 1.5 MHz
+// <3000000> 3 MHz
+// <12000000> 12 MHz
+// <24000000> 24 MHz
+// <48000000> 48 MHz
+#define __SYSTEM_CLOCK 1500000
+
+/*--------------------- Power Regulator Configuration -----------------------*/
+// Power Regulator Mode
+// <0> LDO
+// <1> DC-DC
+#define __REGULATOR 1
+
+/*----------------------------------------------------------------------------
+ Define clocks, used for SystemCoreClockUpdate()
+ *---------------------------------------------------------------------------*/
+#define __VLOCLK 10000
+#define __MODCLK 24000000
+#define __LFXT 32768
+#define __HFXT 48000000
+
+/*----------------------------------------------------------------------------
+ Clock Variable definitions
+ *---------------------------------------------------------------------------*/
+uint32_t SystemCoreClock = __SYSTEM_CLOCK; /*!< System Clock Frequency (Core Clock)*/
+
+/**
+ * Update SystemCoreClock variable
+ *
+ * @param none
+ * @return none
+ *
+ * @brief Updates the SystemCoreClock with current core Clock
+ * retrieved from cpu registers.
+ */
+void SystemCoreClockUpdate(void)
+{
+ uint32_t source, divider;
+ uint8_t dividerValue;
+
+ float dcoConst;
+ int32_t calVal;
+ uint32_t centeredFreq;
+ int16_t dcoTune;
+
+ divider = (CS->CTL1 & CS_CTL1_DIVM_MASK) >> CS_CTL1_DIVM_OFS;
+ dividerValue = 1 << divider;
+ source = CS->CTL1 & CS_CTL1_SELM_MASK;
+
+ switch(source)
+ {
+ case CS_CTL1_SELM__LFXTCLK:
+ if(BITBAND_PERI(CS->IFG, CS_IFG_LFXTIFG_OFS))
+ {
+ // Clear interrupt flag
+ CS->KEY = CS_KEY_VAL;
+ CS->CLRIFG |= CS_CLRIFG_CLR_LFXTIFG;
+ CS->KEY = 1;
+
+ if(BITBAND_PERI(CS->IFG, CS_IFG_LFXTIFG_OFS))
+ {
+ if(BITBAND_PERI(CS->CLKEN, CS_CLKEN_REFOFSEL_OFS))
+ {
+ SystemCoreClock = (128000 / dividerValue);
+ }
+ else
+ {
+ SystemCoreClock = (32000 / dividerValue);
+ }
+ }
+ else
+ {
+ SystemCoreClock = __LFXT / dividerValue;
+ }
+ }
+ else
+ {
+ SystemCoreClock = __LFXT / dividerValue;
+ }
+ break;
+ case CS_CTL1_SELM__VLOCLK:
+ SystemCoreClock = __VLOCLK / dividerValue;
+ break;
+ case CS_CTL1_SELM__REFOCLK:
+ if (BITBAND_PERI(CS->CLKEN, CS_CLKEN_REFOFSEL_OFS))
+ {
+ SystemCoreClock = (128000 / dividerValue);
+ }
+ else
+ {
+ SystemCoreClock = (32000 / dividerValue);
+ }
+ break;
+ case CS_CTL1_SELM__DCOCLK:
+ dcoTune = (CS->CTL0 & CS_CTL0_DCOTUNE_MASK) >> CS_CTL0_DCOTUNE_OFS;
+
+ switch(CS->CTL0 & CS_CTL0_DCORSEL_MASK)
+ {
+ case CS_CTL0_DCORSEL_0:
+ centeredFreq = 1500000;
+ break;
+ case CS_CTL0_DCORSEL_1:
+ centeredFreq = 3000000;
+ break;
+ case CS_CTL0_DCORSEL_2:
+ centeredFreq = 6000000;
+ break;
+ case CS_CTL0_DCORSEL_3:
+ centeredFreq = 12000000;
+ break;
+ case CS_CTL0_DCORSEL_4:
+ centeredFreq = 24000000;
+ break;
+ case CS_CTL0_DCORSEL_5:
+ centeredFreq = 48000000;
+ break;
+ }
+
+ if(dcoTune == 0)
+ {
+ SystemCoreClock = centeredFreq;
+ }
+ else
+ {
+
+ if(dcoTune & 0x1000)
+ {
+ dcoTune = dcoTune | 0xF000;
+ }
+
+ if (BITBAND_PERI(CS->CTL0, CS_CTL0_DCORES_OFS))
+ {
+ dcoConst = *((float *) &TLV->DCOER_CONSTK_RSEL04);
+ calVal = TLV->DCOER_FCAL_RSEL04;
+ }
+ /* Internal Resistor */
+ else
+ {
+ dcoConst = *((float *) &TLV->DCOIR_CONSTK_RSEL04);
+ calVal = TLV->DCOIR_FCAL_RSEL04;
+ }
+
+ SystemCoreClock = (uint32_t) ((centeredFreq)
+ / (1
+ - ((dcoConst * dcoTune)
+ / (8 * (1 + dcoConst * (768 - calVal))))));
+ }
+ break;
+ case CS_CTL1_SELM__MODOSC:
+ SystemCoreClock = __MODCLK / dividerValue;
+ break;
+ case CS_CTL1_SELM__HFXTCLK:
+ if(BITBAND_PERI(CS->IFG, CS_IFG_HFXTIFG_OFS))
+ {
+ // Clear interrupt flag
+ CS->KEY = CS_KEY_VAL;
+ CS->CLRIFG |= CS_CLRIFG_CLR_HFXTIFG;
+ CS->KEY = 1;
+
+ if(BITBAND_PERI(CS->IFG, CS_IFG_HFXTIFG_OFS))
+ {
+ if(BITBAND_PERI(CS->CLKEN, CS_CLKEN_REFOFSEL_OFS))
+ {
+ SystemCoreClock = (128000 / dividerValue);
+ }
+ else
+ {
+ SystemCoreClock = (32000 / dividerValue);
+ }
+ }
+ else
+ {
+ SystemCoreClock = __HFXT / dividerValue;
+ }
+ }
+ else
+ {
+ SystemCoreClock = __HFXT / dividerValue;
+ }
+ break;
+ }
+}
+
+/**
+ * Initialize the system
+ *
+ * @param none
+ * @return none
+ *
+ * @brief Setup the microcontroller system.
+ *
+ * Performs the following initialization steps:
+ * 1. Enables the FPU
+ * 2. Halts the WDT if requested
+ * 3. Enables all SRAM banks
+ * 4. Sets up power regulator and VCORE
+ * 5. Enable Flash wait states if needed
+ * 6. Change MCLK to desired frequency
+ * 7. Enable Flash read buffering
+ */
+void SystemInit(void)
+{
+ // Enable FPU if used
+ #if (__FPU_USED == 1) /* __FPU_USED is defined in core_cm4.h */
+ SCB->CPACR |= ((3UL << 10 * 2) | /* Set CP10 Full Access */
+ (3UL << 11 * 2)); /* Set CP11 Full Access */
+ #endif
+
+ #if (__HALT_WDT == 1)
+ WDT_A->CTL = WDT_A_CTL_PW | WDT_A_CTL_HOLD; // Halt the WDT
+ #endif
+
+ SYSCTL->SRAM_BANKEN = SYSCTL_SRAM_BANKEN_BNK7_EN; // Enable all SRAM banks
+
+ #if (__SYSTEM_CLOCK == 1500000) // 1.5 MHz
+ // Default VCORE is LDO VCORE0 so no change necessary
+
+ // Switches LDO VCORE0 to DCDC VCORE0 if requested
+ #if __REGULATOR
+ while((PCM->CTL1 & PCM_CTL1_PMR_BUSY));
+ PCM->CTL0 = PCM_CTL0_KEY_VAL | PCM_CTL0_AMR_4;
+ while((PCM->CTL1 & PCM_CTL1_PMR_BUSY));
+ #endif
+
+ // No flash wait states necessary
+
+ // DCO = 1.5 MHz; MCLK = source
+ CS->KEY = CS_KEY_VAL; // Unlock CS module for register access
+ CS->CTL0 = CS_CTL0_DCORSEL_0; // Set DCO to 1.5MHz
+ CS->CTL1 &= ~(CS_CTL1_SELM_MASK | CS_CTL1_DIVM_MASK) | CS_CTL1_SELM__DCOCLK; // Select MCLK as DCO source
+ CS->KEY = 0;
+
+ // Set Flash Bank read buffering
+ FLCTL->BANK0_RDCTL &= ~(FLCTL_BANK0_RDCTL_BUFD | FLCTL_BANK0_RDCTL_BUFI);
+ FLCTL->BANK1_RDCTL &= ~(FLCTL_BANK0_RDCTL_BUFD | FLCTL_BANK0_RDCTL_BUFI);
+
+ #elif (__SYSTEM_CLOCK == 3000000) // 3 MHz
+ // Default VCORE is LDO VCORE0 so no change necessary
+
+ // Switches LDO VCORE0 to DCDC VCORE0 if requested
+ #if __REGULATOR
+ while(PCM->CTL1 & PCM_CTL1_PMR_BUSY);
+ PCM->CTL0 = PCM_CTL0_KEY_VAL | PCM_CTL0_AMR_4;
+ while(PCM->CTL1 & PCM_CTL1_PMR_BUSY);
+ #endif
+
+ // No flash wait states necessary
+
+ // DCO = 3 MHz; MCLK = source
+ CS->KEY = CS_KEY_VAL; // Unlock CS module for register access
+ CS->CTL0 = CS_CTL0_DCORSEL_1; // Set DCO to 1.5MHz
+ CS->CTL1 &= ~(CS_CTL1_SELM_MASK | CS_CTL1_DIVM_MASK) | CS_CTL1_SELM__DCOCLK; // Select MCLK as DCO source
+ CS->KEY = 0;
+
+ // Set Flash Bank read buffering
+ FLCTL->BANK0_RDCTL &= ~(FLCTL_BANK0_RDCTL_BUFD | FLCTL_BANK0_RDCTL_BUFI);
+ FLCTL->BANK1_RDCTL &= ~(FLCTL_BANK0_RDCTL_BUFD | FLCTL_BANK0_RDCTL_BUFI);
+
+ #elif (__SYSTEM_CLOCK == 12000000) // 12 MHz
+ // Default VCORE is LDO VCORE0 so no change necessary
+
+ // Switches LDO VCORE0 to DCDC VCORE0 if requested
+ #if __REGULATOR
+ while((PCM->CTL1 & PCM_CTL1_PMR_BUSY));
+ PCM->CTL0 = PCM_CTL0_KEY_VAL | PCM_CTL0_AMR_4;
+ while((PCM->CTL1 & PCM_CTL1_PMR_BUSY));
+ #endif
+
+ // No flash wait states necessary
+
+ // DCO = 12 MHz; MCLK = source
+ CS->KEY = CS_KEY_VAL; // Unlock CS module for register access
+ CS->CTL0 = CS_CTL0_DCORSEL_3; // Set DCO to 12MHz
+ CS->CTL1 &= ~(CS_CTL1_SELM_MASK | CS_CTL1_DIVM_MASK) | CS_CTL1_SELM__DCOCLK; // Select MCLK as DCO source
+ CS->KEY = 0;
+
+ // Set Flash Bank read buffering
+ FLCTL->BANK0_RDCTL &= ~(FLCTL_BANK0_RDCTL_BUFD | FLCTL_BANK0_RDCTL_BUFI);
+ FLCTL->BANK1_RDCTL &= ~(FLCTL_BANK0_RDCTL_BUFD | FLCTL_BANK0_RDCTL_BUFI);
+
+ #elif (__SYSTEM_CLOCK == 24000000) // 24 MHz
+ // Default VCORE is LDO VCORE0 so no change necessary
+
+ // Switches LDO VCORE0 to DCDC VCORE0 if requested
+ #if __REGULATOR
+ while((PCM->CTL1 & PCM_CTL1_PMR_BUSY));
+ PCM->CTL0 = PCM_CTL0_KEY_VAL | PCM_CTL0_AMR_4;
+ while((PCM->CTL1 & PCM_CTL1_PMR_BUSY));
+ #endif
+
+ // 1 flash wait state (BANK0 VCORE0 max is 12 MHz)
+ FLCTL->BANK0_RDCTL &= ~FLCTL_BANK0_RDCTL_WAIT_MASK | FLCTL_BANK0_RDCTL_WAIT_1;
+ FLCTL->BANK1_RDCTL &= ~FLCTL_BANK0_RDCTL_WAIT_MASK | FLCTL_BANK0_RDCTL_WAIT_1;
+
+ // DCO = 24 MHz; MCLK = source
+ CS->KEY = CS_KEY_VAL; // Unlock CS module for register access
+ CS->CTL0 = CS_CTL0_DCORSEL_4; // Set DCO to 24MHz
+ CS->CTL1 &= ~(CS_CTL1_SELM_MASK | CS_CTL1_DIVM_MASK) | CS_CTL1_SELM__DCOCLK; // Select MCLK as DCO source
+ CS->KEY = 0;
+
+ // Set Flash Bank read buffering
+ FLCTL->BANK0_RDCTL |= (FLCTL_BANK0_RDCTL_BUFD | FLCTL_BANK0_RDCTL_BUFI);
+ FLCTL->BANK1_RDCTL &= ~(FLCTL_BANK0_RDCTL_BUFD | FLCTL_BANK0_RDCTL_BUFI);
+
+ #elif (__SYSTEM_CLOCK == 48000000) // 48 MHz
+ // Switches LDO VCORE0 to LDO VCORE1; mandatory for 48 MHz setting
+ while((PCM->CTL1 & PCM_CTL1_PMR_BUSY));
+ PCM->CTL0 = PCM_CTL0_KEY_VAL | PCM_CTL0_AMR_1;
+ while((PCM->CTL1 & PCM_CTL1_PMR_BUSY));
+
+ // Switches LDO VCORE1 to DCDC VCORE1 if requested
+ #if __REGULATOR
+ while((PCM->CTL1 & PCM_CTL1_PMR_BUSY));
+ PCM->CTL0 = PCM_CTL0_KEY_VAL | PCM_CTL0_AMR_5;
+ while((PCM->CTL1 & PCM_CTL1_PMR_BUSY));
+ #endif
+
+ // 2 flash wait states (BANK0 VCORE1 max is 16 MHz, BANK1 VCORE1 max is 32 MHz)
+ FLCTL->BANK0_RDCTL &= ~FLCTL_BANK0_RDCTL_WAIT_MASK | FLCTL_BANK0_RDCTL_WAIT_2;
+ FLCTL->BANK1_RDCTL &= ~FLCTL_BANK1_RDCTL_WAIT_MASK | FLCTL_BANK1_RDCTL_WAIT_2;
+
+ // DCO = 48 MHz; MCLK = source
+ CS->KEY = CS_KEY_VAL; // Unlock CS module for register access
+ CS->CTL0 = CS_CTL0_DCORSEL_5; // Set DCO to 48MHz
+ CS->CTL1 &= ~(CS_CTL1_SELM_MASK | CS_CTL1_DIVM_MASK) | CS_CTL1_SELM__DCOCLK; // Select MCLK as DCO source
+ CS->KEY = 0;
+
+ // Set Flash Bank read buffering
+ FLCTL->BANK0_RDCTL |= (FLCTL_BANK0_RDCTL_BUFD | FLCTL_BANK0_RDCTL_BUFI);
+ FLCTL->BANK1_RDCTL |= (FLCTL_BANK1_RDCTL_BUFD | FLCTL_BANK1_RDCTL_BUFI);
+ #endif
+
+}