Min 7 年之前
当前提交
ea396ed269
共有 8 个文件被更改,包括 976 次插入0 次删除
  1. 206 0
      ccs/startup_msp432p401r_ccs.c
  2. 81 0
      descrambler.c
  3. 24 0
      descrambler.h
  4. 127 0
      main.c
  5. 112 0
      msp432p401r.cmd
  6. 401 0
      system_msp432p401r.c
  7. 16 0
      targetConfigs/MSP432P401R.ccxml
  8. 9 0
      targetConfigs/readme.txt

+ 206 - 0
ccs/startup_msp432p401r_ccs.c

@@ -0,0 +1,206 @@
+/******************************************************************************
+* 
+*  Copyright (C) 2012 - 2018 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.  
+* 
+*  MSP432P401R Interrupt Vector Table
+* 
+*****************************************************************************/
+
+#include <stdint.h>
+
+/* Linker variable that marks the top of the stack. */
+extern unsigned long __STACK_END;
+
+/* 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);
+
+/* Forward declaration of the default fault handlers. */
+void Default_Handler            (void) __attribute__((weak));
+extern void Reset_Handler       (void) __attribute__((weak));
+
+/* Cortex-M4 Processor Exceptions */
+extern void NMI_Handler         (void) __attribute__((weak, alias("Default_Handler")));
+extern void HardFault_Handler   (void) __attribute__((weak, alias("Default_Handler")));
+extern void MemManage_Handler   (void) __attribute__((weak, alias("Default_Handler")));
+extern void BusFault_Handler    (void) __attribute__((weak, alias("Default_Handler")));
+extern void UsageFault_Handler  (void) __attribute__((weak, alias("Default_Handler")));
+extern void SVC_Handler         (void) __attribute__((weak, alias("Default_Handler")));
+extern void DebugMon_Handler    (void) __attribute__((weak, alias("Default_Handler")));
+extern void PendSV_Handler      (void) __attribute__((weak, alias("Default_Handler")));
+
+/* device specific interrupt handler */
+extern void SysTick_Handler     (void) __attribute__((weak,alias("Default_Handler")));
+extern void PSS_IRQHandler      (void) __attribute__((weak,alias("Default_Handler")));
+extern void CS_IRQHandler       (void) __attribute__((weak,alias("Default_Handler")));
+extern void PCM_IRQHandler      (void) __attribute__((weak,alias("Default_Handler")));
+extern void WDT_A_IRQHandler    (void) __attribute__((weak,alias("Default_Handler")));
+extern void FPU_IRQHandler      (void) __attribute__((weak,alias("Default_Handler")));
+extern void FLCTL_IRQHandler    (void) __attribute__((weak,alias("Default_Handler")));
+extern void COMP_E0_IRQHandler  (void) __attribute__((weak,alias("Default_Handler")));
+extern void COMP_E1_IRQHandler  (void) __attribute__((weak,alias("Default_Handler")));
+extern void TA0_0_IRQHandler    (void) __attribute__((weak,alias("Default_Handler")));
+extern void TA0_N_IRQHandler    (void) __attribute__((weak,alias("Default_Handler")));
+extern void TA1_0_IRQHandler    (void) __attribute__((weak,alias("Default_Handler")));
+extern void TA1_N_IRQHandler    (void) __attribute__((weak,alias("Default_Handler")));
+extern void TA2_0_IRQHandler    (void) __attribute__((weak,alias("Default_Handler")));
+extern void TA2_N_IRQHandler    (void) __attribute__((weak,alias("Default_Handler")));
+extern void TA3_0_IRQHandler    (void) __attribute__((weak,alias("Default_Handler")));
+extern void TA3_N_IRQHandler    (void) __attribute__((weak,alias("Default_Handler")));
+extern void EUSCIA0_IRQHandler  (void) __attribute__((weak,alias("Default_Handler")));
+extern void EUSCIA1_IRQHandler  (void) __attribute__((weak,alias("Default_Handler")));
+extern void EUSCIA2_IRQHandler  (void) __attribute__((weak,alias("Default_Handler")));
+extern void EUSCIA3_IRQHandler  (void) __attribute__((weak,alias("Default_Handler")));
+extern void EUSCIB0_IRQHandler  (void) __attribute__((weak,alias("Default_Handler")));
+extern void EUSCIB1_IRQHandler  (void) __attribute__((weak,alias("Default_Handler")));
+extern void EUSCIB2_IRQHandler  (void) __attribute__((weak,alias("Default_Handler")));
+extern void EUSCIB3_IRQHandler  (void) __attribute__((weak,alias("Default_Handler")));
+extern void ADC14_IRQHandler    (void) __attribute__((weak,alias("Default_Handler")));
+extern void T32_INT1_IRQHandler (void) __attribute__((weak,alias("Default_Handler")));
+extern void T32_INT2_IRQHandler (void) __attribute__((weak,alias("Default_Handler")));
+extern void T32_INTC_IRQHandler (void) __attribute__((weak,alias("Default_Handler")));
+extern void AES256_IRQHandler   (void) __attribute__((weak,alias("Default_Handler")));
+extern void RTC_C_IRQHandler    (void) __attribute__((weak,alias("Default_Handler")));
+extern void DMA_ERR_IRQHandler  (void) __attribute__((weak,alias("Default_Handler")));
+extern void DMA_INT3_IRQHandler (void) __attribute__((weak,alias("Default_Handler")));
+extern void DMA_INT2_IRQHandler (void) __attribute__((weak,alias("Default_Handler")));
+extern void DMA_INT1_IRQHandler (void) __attribute__((weak,alias("Default_Handler")));
+extern void DMA_INT0_IRQHandler (void) __attribute__((weak,alias("Default_Handler")));
+extern void PORT1_IRQHandler    (void) __attribute__((weak,alias("Default_Handler")));
+extern void PORT2_IRQHandler    (void) __attribute__((weak,alias("Default_Handler")));
+extern void PORT3_IRQHandler    (void) __attribute__((weak,alias("Default_Handler")));
+extern void PORT4_IRQHandler    (void) __attribute__((weak,alias("Default_Handler")));
+extern void PORT5_IRQHandler    (void) __attribute__((weak,alias("Default_Handler")));
+extern void PORT6_IRQHandler    (void) __attribute__((weak,alias("Default_Handler")));
+
+/* 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 */
+    Reset_Handler,                         /* The reset handler         */
+    NMI_Handler,                           /* The NMI handler           */
+    HardFault_Handler,                     /* The hard fault handler    */
+    MemManage_Handler,                     /* The MPU fault handler     */
+    BusFault_Handler,                      /* The bus fault handler     */
+    UsageFault_Handler,                    /* The usage fault handler   */
+    0,                                     /* Reserved                  */
+    0,                                     /* Reserved                  */
+    0,                                     /* Reserved                  */
+    0,                                     /* Reserved                  */
+    SVC_Handler,                           /* SVCall handler            */
+    DebugMon_Handler,                      /* Debug monitor handler     */
+    0,                                     /* Reserved                  */
+    PendSV_Handler,                        /* The PendSV handler        */
+    SysTick_Handler,                       /* The SysTick handler       */
+    PSS_IRQHandler,                        /* PSS Interrupt             */
+    CS_IRQHandler,                         /* CS Interrupt              */
+    PCM_IRQHandler,                        /* PCM Interrupt             */
+    WDT_A_IRQHandler,                      /* WDT_A Interrupt           */
+    FPU_IRQHandler,                        /* FPU Interrupt             */
+    FLCTL_IRQHandler,                      /* Flash Controller Interrupt*/
+    COMP_E0_IRQHandler,                    /* COMP_E0 Interrupt         */
+    COMP_E1_IRQHandler,                    /* COMP_E1 Interrupt         */
+    TA0_0_IRQHandler,                      /* TA0_0 Interrupt           */
+    TA0_N_IRQHandler,                      /* TA0_N Interrupt           */
+    TA1_0_IRQHandler,                      /* TA1_0 Interrupt           */
+    TA1_N_IRQHandler,                      /* TA1_N Interrupt           */
+    TA2_0_IRQHandler,                      /* TA2_0 Interrupt           */
+    TA2_N_IRQHandler,                      /* TA2_N Interrupt           */
+    TA3_0_IRQHandler,                      /* TA3_0 Interrupt           */
+    TA3_N_IRQHandler,                      /* TA3_N Interrupt           */
+    EUSCIA0_IRQHandler,                    /* EUSCIA0 Interrupt         */
+    EUSCIA1_IRQHandler,                    /* EUSCIA1 Interrupt         */
+    EUSCIA2_IRQHandler,                    /* EUSCIA2 Interrupt         */
+    EUSCIA3_IRQHandler,                    /* EUSCIA3 Interrupt         */
+    EUSCIB0_IRQHandler,                    /* EUSCIB0 Interrupt         */
+    EUSCIB1_IRQHandler,                    /* EUSCIB1 Interrupt         */
+    EUSCIB2_IRQHandler,                    /* EUSCIB2 Interrupt         */
+    EUSCIB3_IRQHandler,                    /* EUSCIB3 Interrupt         */
+    ADC14_IRQHandler,                      /* ADC14 Interrupt           */
+    T32_INT1_IRQHandler,                   /* T32_INT1 Interrupt        */
+    T32_INT2_IRQHandler,                   /* T32_INT2 Interrupt        */
+    T32_INTC_IRQHandler,                   /* T32_INTC Interrupt        */
+    AES256_IRQHandler,                     /* AES256 Interrupt          */
+    RTC_C_IRQHandler,                      /* RTC_C Interrupt           */
+    DMA_ERR_IRQHandler,                    /* DMA_ERR Interrupt         */
+    DMA_INT3_IRQHandler,                   /* DMA_INT3 Interrupt        */
+    DMA_INT2_IRQHandler,                   /* DMA_INT2 Interrupt        */
+    DMA_INT1_IRQHandler,                   /* DMA_INT1 Interrupt        */
+    DMA_INT0_IRQHandler,                   /* DMA_INT0 Interrupt        */
+    PORT1_IRQHandler,                      /* Port1 Interrupt           */
+    PORT2_IRQHandler,                      /* Port2 Interrupt           */
+    PORT3_IRQHandler,                      /* Port3 Interrupt           */
+    PORT4_IRQHandler,                      /* Port4 Interrupt           */
+    PORT5_IRQHandler,                      /* Port5 Interrupt           */
+    PORT6_IRQHandler                       /* Port6 Interrupt           */
+};
+
+/* Forward declaration of the default fault handlers. */
+/* 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 Reset_Handler(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 an unexpected  */
+/* interrupt.  This simply enters an infinite loop, preserving the system state */
+/* for examination by a debugger.                                               */
+void Default_Handler(void)
+{
+    /* Fault trap exempt from ULP advisor */
+    #pragma diag_push
+    #pragma CHECK_ULP("-2.1")
+
+	/* Enter an infinite loop. */
+	while(1)
+	{
+	}
+
+	#pragma diag_pop
+}

+ 81 - 0
descrambler.c

@@ -0,0 +1,81 @@
+/*
+ * Academic License - for use in teaching, academic research, and meeting
+ * course requirements at degree granting institutions only.  Not for
+ * government, commercial, or other organizational use.
+ *
+ * descrambler.c
+ *
+ * Code generation for function 'descrambler'
+ *
+ */
+
+/* Include files */
+#include <math.h>
+#include <string.h>
+#include "descrambler.h"
+
+/* Function Definitions */
+void descramble(double *value, double t, const double B1[9], const double A1[9],
+                 const double B2[19], const double A2[19], double Z1[8], double
+                 Z2[18])
+{
+  double b[9];
+  double a[9];
+  double a1;
+  int k;
+  double zf[8];
+  double b_b[19];
+  double b_a[19];
+  double b_zf[18];
+
+  /*  Filter to remove 8kHz tone */
+  memcpy(&b[0], &B1[0], 9U * sizeof(double));
+  memcpy(&a[0], &A1[0], 9U * sizeof(double));
+  a1 = A1[0];
+  if ((!(A1[0] == 0.0)) && (A1[0] != 1.0)) {
+    for (k = 0; k < 9; k++) {
+      b[k] /= a1;
+    }
+    for (k = 0; k < 8; k++) {
+      a[k + 1] /= a1;
+    }
+    a[0] = 1.0;
+  }
+
+  memset(&zf[0], 0, sizeof(double) << 3);
+  a1 = Z1[0] + *value * b[0];
+  for (k = 0; k < 7; k++) {
+    zf[k] = Z1[k + 1];
+  }
+
+  for (k = 0; k < 8; k++) {
+    Z1[k] = (zf[k] + *value * b[k + 1]) + -a1 * a[k + 1];
+  }
+
+  /*  Shifting by 7kHz */
+  *value = a1 * 2.0 * sin(6.2831853071795862 * t * 7000.0);
+
+  /*  Low pass filter */
+  memcpy(&b_b[0], &B2[0], 19U * sizeof(double));
+  memcpy(&b_a[0], &A2[0], 19U * sizeof(double));
+  a1 = A2[0];
+  if ((!(A2[0] == 0.0)) && (A2[0] != 1.0)) {
+    for (k = 0; k < 19; k++) {
+      b_b[k] /= a1;
+    }
+    for (k = 0; k < 18; k++) {
+      b_a[k + 1] /= a1;
+    }
+    b_a[0] = 1.0;
+  }
+
+  memset(&b_zf[0], 0, 18U * sizeof(double));
+  a1 = Z2[0] + *value * b_b[0];
+  memcpy(&b_zf[0], &Z2[1], 17U * sizeof(double));
+  for (k = 0; k < 18; k++) {
+    Z2[k] = (b_zf[k] + *value * b_b[k + 1]) + -a1 * b_a[k + 1];
+  }
+  *value = a1;
+}
+
+/* End of code generation (descrambler.c) */

+ 24 - 0
descrambler.h

@@ -0,0 +1,24 @@
+/*
+ * Academic License - for use in teaching, academic research, and meeting
+ * course requirements at degree granting institutions only.  Not for
+ * government, commercial, or other organizational use.
+ *
+ * descrambler.h
+ *
+ * Code generation for function 'descrambler'
+ *
+ */
+
+#ifndef DESCRAMBLER_H
+#define DESCRAMBLER_H
+
+/* Include files */
+
+/* Function Declarations */
+extern void descramble(double *value, double t, const double B1[9], const
+  double A1[9], const double B2[19], const double A2[19], double Z1[8], double
+  Z2[18]);
+
+#endif
+
+/* End of code generation (descrambler.h) */

+ 127 - 0
main.c

@@ -0,0 +1,127 @@
+/* DriverLib Includes */
+#include <ti/devices/msp432p4xx/driverlib/driverlib.h>
+
+/* Standard Includes */
+#include <stdint.h>
+#include <math.h>
+#include <descrambler.h>
+
+// Sampling frequency
+const int fs = 48000;
+
+
+// Timer for calculate sine wave
+static double Timer = 0;
+// Coefficients for bandstop filter
+const double B1[] = {0.7755, -2.5985, 6.3671, -9.6188, 11.5650, -9.6188, 6.3671, -2.5985, 0.7755};
+const double A1[] = {1.0000, -3.1835, 7.4065, -10.6464, 12.1861, -9.6677, 6.1083, -2.3849, 0.6809};
+// Coefficients for lowpass filter
+const double B2[] = {0.0000, 0.0001, 0.0005, 0.0025, 0.0093, 0.0260, 0.0564, 0.0967, 0.1330, 0.1477, 0.1330, 0.0967, 0.0564, 0.0260, 0.0093, 0.0025, 0.0005, 0.0001, 0.0000};
+const double A2[] = {0.0001, -0.0014, 0.0096, -0.0423, 0.1340, -0.3250, 0.6243, -0.9708, 1.2386, -1.3057, 1.1399, -0.8221, 0.4862, -0.2326, 0.0881, -0.0255, 0.0053, -0.0007, 0.0000};
+// Time delays for both filters
+static double Z1[8];
+static double Z2[18];
+
+int main(void){
+    /* Halting the Watchdog */
+    MAP_WDT_A_holdTimer();
+    
+    //![Simple CS Config]
+    /* Configuring pins for peripheral/crystal usage */
+    MAP_GPIO_setAsPeripheralModuleFunctionOutputPin(GPIO_PORT_PJ,
+            GPIO_PIN3 | GPIO_PIN2, GPIO_PRIMARY_MODULE_FUNCTION);
+
+    /* Configure P5.6 and P5.7 to their analog functions to output VREF */
+    P5SEL0 |= BIT6 | BIT7;
+    P5SEL1 |= BIT6 | BIT7;
+
+    REFCTL0 |= REFON;                     // Turn on reference module
+    REFCTL0 |= REFOUT;                    // Output reference voltage to a pin
+
+     /* Output VREF = 1.2V */
+    REFCTL0 &= ~(REFVSEL_3);              // Clear existing VREF voltage level setting
+    REFCTL0 |= REFVSEL_0;                 // Set VREF = 1.2V
+    while (REFCTL0 & REFGENBUSY);       // Wait until the reference generation is settled
+
+
+    /* Configuring pins for HFXT crystal */
+    MAP_GPIO_setAsPeripheralModuleFunctionInputPin(GPIO_PORT_PJ,
+            GPIO_PIN2 | GPIO_PIN3, GPIO_PRIMARY_MODULE_FUNCTION);
+
+    /* Set P6.0 as output */
+    MAP_GPIO_setAsOutputPin(GPIO_PORT_P1, GPIO_PIN0);
+
+    /* Set all 8 pins of P2 as output */
+    MAP_GPIO_setAsOutputPin(GPIO_PORT_P2, GPIO_PIN0 | GPIO_PIN1 | GPIO_PIN2 | GPIO_PIN3 | GPIO_PIN4 | GPIO_PIN5 | GPIO_PIN6 | GPIO_PIN7);
+
+    /* Configuring GPIOs (4.3 MCLK) */
+    MAP_GPIO_setAsPeripheralModuleFunctionOutputPin(GPIO_PORT_P4, GPIO_PIN3,
+    GPIO_PRIMARY_MODULE_FUNCTION);
+
+    /* Setting the external clock frequency. This API is optional, but will
+     * come in handy if the user ever wants to use the getMCLK/getACLK/etc
+     * functions
+     */
+    CS_setExternalClockSourceFrequency(32000,48000000);
+
+    /* Starting HFXT in non-bypass mode without a timeout. Before we start
+     * we have to change VCORE to 1 to support the 48MHz frequency */
+    MAP_PCM_setCoreVoltageLevel(PCM_VCORE1);
+    MAP_FlashCtl_setWaitState(FLASH_BANK0, 2);
+    MAP_FlashCtl_setWaitState(FLASH_BANK1, 2);
+    CS_startHFXT(false);
+
+    /* Initialising MCLK to HFXT (effectively 48MHz) */
+    MAP_CS_initClockSignal(CS_MCLK, CS_HFXTCLK_SELECT, CS_CLOCK_DIVIDER_1);
+
+    /* Set SysTick to 48MHz/1000=48kHz*/
+    MAP_SysTick_enableModule();
+    MAP_SysTick_setPeriod(1000);
+    MAP_Interrupt_enableSleepOnIsrExit();
+    MAP_SysTick_enableInterrupt();
+
+    /* Initialising ADC (MCLK/1//1) */
+    MAP_ADC14_enableModule();
+    MAP_ADC14_initModule(ADC_CLOCKSOURCE_MCLK, ADC_PREDIVIDER_1, ADC_DIVIDER_1, 0);
+
+    /* Configuring GPIOs (P5.0 (A5) as the ADC input pin) */
+    MAP_GPIO_setAsPeripheralModuleFunctionInputPin(GPIO_PORT_P5, GPIO_PIN0, GPIO_TERTIARY_MODULE_FUNCTION);
+
+    /* Configure ADC Resolution */
+    ADC14_setResolution(ADC_10BIT);
+
+    /* Configuring ADC Memory */
+    MAP_ADC14_configureSingleSampleMode(ADC_MEM0, true);
+    MAP_ADC14_configureConversionMemory(ADC_MEM0, ADC_VREFPOS_INTBUF_VREFNEG_VSS, ADC_INPUT_A5, false);
+
+    /* Configuring Sample Timer */
+    MAP_ADC14_enableSampleTimer(ADC_MANUAL_ITERATION);
+
+     /* Enabling MASTER interrupts */
+    MAP_Interrupt_enableMaster();
+
+    while (1){
+        //MAP_PCM_gotoLPM0();
+    }
+}
+
+void SysTick_Handler(void)
+{
+    double buffer = ADC14_getResult(ADC_MEM0);  //Get the conversion result.
+
+    descramble(&buffer, Timer, B1, A1, B2, A2, Z1, Z2);
+
+    Timer += 1/fs;
+    P2OUT = buffer / 4;  //We do this because the ADC is set to use 10 bits but P2OUT is only 8 bits.
+
+    /* Enabling/Toggling Conversion */
+    MAP_ADC14_enableConversion();
+    MAP_ADC14_toggleConversionTrigger();
+    MAP_ADC14_toggleConversionTrigger();
+}
+
+void ADC14_IRQHandler(void)
+{
+    uint64_t status = MAP_ADC14_getEnabledInterruptStatus();
+    MAP_ADC14_clearInterruptFlag(status);
+}

+ 112 - 0
msp432p401r.cmd

@@ -0,0 +1,112 @@
+/******************************************************************************
+*
+* Copyright (C) 2012 - 2018 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: 01/26/18
+*
+*****************************************************************************/
+
+--retain=flashMailbox
+
+MEMORY
+{
+    MAIN       (RX) : origin = 0x00000000, length = 0x00040000
+    INFO       (RX) : origin = 0x00200000, length = 0x00004000
+#ifdef  __TI_COMPILER_VERSION__
+#if     __TI_COMPILER_VERSION__ >= 15009000
+    ALIAS
+    {
+    SRAM_CODE  (RWX): origin = 0x01000000
+    SRAM_DATA  (RW) : origin = 0x20000000
+    } length = 0x00010000
+#else
+    /* Hint: If the user wants to use ram functions, please observe that SRAM_CODE             */
+    /* and SRAM_DATA memory areas are overlapping. You need to take measures to separate       */
+    /* data from code in RAM. This is only valid for Compiler version earlier than 15.09.0.STS.*/ 
+    SRAM_CODE  (RWX): origin = 0x01000000, length = 0x00010000
+    SRAM_DATA  (RW) : origin = 0x20000000, length = 0x00010000
+#endif
+#endif
+}
+
+/* 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
+    .binit        : {}  > MAIN
+
+    /* The following sections show the usage of the INFO flash memory        */
+    /* INFO flash memory is intended to be used for the following            */
+    /* device specific purposes:                                             */
+    /* Flash mailbox for device security operations                          */
+    .flashMailbox : > 0x00200000
+    /* TLV table for device identification and characterization              */
+    .tlvTable     : > 0x00201000
+    /* BSL area for device bootstrap loader                                  */
+    .bslArea      : > 0x00202000
+
+    .vtable :   > 0x20000000
+    .data   :   > SRAM_DATA
+    .bss    :   > SRAM_DATA
+    .sysmem :   > SRAM_DATA
+    .stack  :   > SRAM_DATA (HIGH)
+
+#ifdef  __TI_COMPILER_VERSION__
+#if     __TI_COMPILER_VERSION__ >= 15009000
+    .TI.ramfunc : {} load=MAIN, run=SRAM_CODE, table(BINIT)
+#endif
+#endif
+}
+
+/* Symbolic definition of the WDTCTL register for RTS */
+WDTCTL_SYM = 0x4000480C;
+

+ 401 - 0
system_msp432p401r.c

@@ -0,0 +1,401 @@
+/******************************************************************************
+* @file     system_msp432p401r.c
+* @brief    CMSIS Cortex-M4F Device Peripheral Access Layer Source File for
+*           MSP432P401R
+* @version  3.231
+* @date     01/26/18
+*
+* @note     View configuration instructions embedded in comments
+*
+******************************************************************************/
+//*****************************************************************************
+//
+// Copyright (C) 2015 - 2018 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 <ti/devices/msp432p4xx/inc/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   12000000
+   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    3000000
+
+/*--------------------- Power Regulator Configuration -----------------------*/
+//  Power Regulator Mode
+//     <0> LDO
+//     <1> DC-DC
+#define __REGULATOR        0
+
+/*----------------------------------------------------------------------------
+   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 = 0, divider = 0, dividerValue = 0, centeredFreq = 0, calVal = 0;
+    int16_t dcoTune = 0;
+    float dcoConst = 0.0;
+
+    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 = *((volatile const float *) &TLV->DCOER_CONSTK_RSEL04);
+                calVal = TLV->DCOER_FCAL_RSEL04;
+            }
+            /* Internal Resistor */
+            else
+            {
+                dcoConst = *((volatile const 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 & ~(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 & ~(FLCTL_BANK0_RDCTL_BUFD | FLCTL_BANK0_RDCTL_BUFI);
+    FLCTL->BANK1_RDCTL = FLCTL->BANK1_RDCTL & ~(FLCTL_BANK1_RDCTL_BUFD | FLCTL_BANK1_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 & ~(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 & ~(FLCTL_BANK0_RDCTL_BUFD | FLCTL_BANK0_RDCTL_BUFI);
+    FLCTL->BANK1_RDCTL = FLCTL->BANK1_RDCTL & ~(FLCTL_BANK1_RDCTL_BUFD | FLCTL_BANK1_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 & ~(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 & ~(FLCTL_BANK0_RDCTL_BUFD | FLCTL_BANK0_RDCTL_BUFI);
+    FLCTL->BANK1_RDCTL = FLCTL->BANK1_RDCTL & ~(FLCTL_BANK1_RDCTL_BUFD | FLCTL_BANK1_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 & ~FLCTL_BANK0_RDCTL_WAIT_MASK) | FLCTL_BANK0_RDCTL_WAIT_1;
+    FLCTL->BANK1_RDCTL = (FLCTL->BANK1_RDCTL & ~FLCTL_BANK1_RDCTL_WAIT_MASK) | FLCTL_BANK1_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 & ~(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 | (FLCTL_BANK0_RDCTL_BUFD | FLCTL_BANK0_RDCTL_BUFI);
+    FLCTL->BANK1_RDCTL = FLCTL->BANK1_RDCTL & ~(FLCTL_BANK1_RDCTL_BUFD | FLCTL_BANK1_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
+
+    // 1 flash wait states (BANK0 VCORE1 max is 16 MHz, BANK1 VCORE1 max is 32 MHz)
+    FLCTL->BANK0_RDCTL = (FLCTL->BANK0_RDCTL & ~FLCTL_BANK0_RDCTL_WAIT_MASK) | FLCTL_BANK0_RDCTL_WAIT_1;
+    FLCTL->BANK1_RDCTL = (FLCTL->BANK1_RDCTL & ~FLCTL_BANK1_RDCTL_WAIT_MASK) | FLCTL_BANK1_RDCTL_WAIT_1;
+
+    // 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 & ~(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 | (FLCTL_BANK0_RDCTL_BUFD | FLCTL_BANK0_RDCTL_BUFI);
+    FLCTL->BANK1_RDCTL = FLCTL->BANK1_RDCTL | (FLCTL_BANK1_RDCTL_BUFD | FLCTL_BANK1_RDCTL_BUFI);
+    #endif
+
+}
+
+

+ 16 - 0
targetConfigs/MSP432P401R.ccxml

@@ -0,0 +1,16 @@
+<?xml version="1.0" encoding="UTF-8" standalone="no"?>
+<configurations XML_version="1.2" id="configurations_0">
+    <configuration XML_version="1.2" id="configuration_0">
+        <instance XML_version="1.2" desc="Texas Instruments XDS110 USB Debug Probe" href="connections/TIXDS110_Connection.xml" id="Texas Instruments XDS110 USB Debug Probe" xml="TIXDS110_Connection.xml" xmlpath="connections"/>
+        <connection XML_version="1.2" id="Texas Instruments XDS110 USB Debug Probe">
+            <instance XML_version="1.2" href="drivers/tixds510cs_dap.xml" id="drivers" xml="tixds510cs_dap.xml" xmlpath="drivers"/>
+            <instance XML_version="1.2" href="drivers/tixds510cortexM.xml" id="drivers" xml="tixds510cortexM.xml" xmlpath="drivers"/>
+            <property Type="choicelist" Value="2" id="SWD Mode Settings">
+                <choice Name="SWD Mode - Aux COM port is target TDO pin" value="nothing"/>
+            </property>
+            <platform XML_version="1.2" id="platform_0">
+                <instance XML_version="1.2" desc="MSP432P401R" href="devices/msp432p401r.xml" id="MSP432P401R" xml="msp432p401r.xml" xmlpath="devices"/>
+            </platform>
+        </connection>
+    </configuration>
+</configurations>

+ 9 - 0
targetConfigs/readme.txt

@@ -0,0 +1,9 @@
+The 'targetConfigs' folder contains target-configuration (.ccxml) files, automatically generated based
+on the device and connection settings specified in your project on the Properties > General page.
+
+Please note that in automatic target-configuration management, changes to the project's device and/or
+connection settings will either modify an existing or generate a new target-configuration file. Thus,
+if you manually edit these auto-generated files, you may need to re-apply your changes. Alternatively,
+you may create your own target-configuration file for this project and manage it manually. You can
+always switch back to automatic target-configuration management by checking the "Manage the project's
+target-configuration automatically" checkbox on the project's Properties > General page.