This thread has been locked.

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

BOOSTXL-TUSS4470: CCS code port of Energia example code for 1MHz transducer and MSP430F5529

Part Number: BOOSTXL-TUSS4470
Other Parts Discussed in Thread: ENERGIA, , TUSS4470, MSP430F5529

I'm posting this Code Composer Studio (CCS) code I converted from the Energia examples provided here by Texas Instruments for the BOOSTXL-TUSS4470 attached to an MSP430F5529LP evaluation board.  It uses SMCLK and a PWM timer to send 1MHz pulses to a transducer with a 1MHz center frequency and sample the results using DMA to minimize result storage time between samples.  The STEMInc SMD15T21R111WL transducer was used for this example.  The delay_cycles statement on line 314 determines how many pulses will be sent.  I measured 12 pulses during the 40 cycle delay with an SMCLK of 4MHz.  After initialization, the program sleeps until samplingActive is true.  The sample loop is set to collect twenty sets of 125 samples each but can be changed to meet other requirements.  Each sample set is collected in about 900 microseconds.  I tested this program using an 8MHz SMCLK instead of 4MHz which halves the total measured sampling duration for a single sample set.  This can be used to double the sampling resolution and increase the size of the sample set to 250 samples.  The code changes for this are also included below.  The ADC12 reference voltage is set to 2.5V on line 179.  The images below show the timing of the sampling start (purple) and the 1MhZ pulse (blue) and can be observed by attaching oscilliscope probes to pins 8.2 and 2.5 (MSP430 pinout image below) and uncommenting lines 313 and 436.  A probe can be attached to pin 6.5 (VOUT) to view the transducer envelope output.  If anyone has suggestions for improvement or changes, please post them.    

1MHz pulses (blue) and sampling start time (purple)

sampling duration (purple)

4721.tuss4470_energia_ccs_port.c
// code sources:
// A : msp430_driverlib_2_91_13_01\examples\MSP430F5xx_6xx\usci_a_spi/usci_a_spi_ex1_master.c
// B : TUSS4470 examples\examples\VOUT_ADC_Processing\TUSS44x0_ultrasonic.cpp
// C : msp430_driverlib_2_91_13_01\examples\MSP430F5xx_6xx\adc12_a/adc12_a_ex5_repeatedSingle.c

#include "driverlib.h"
#include <stdio.h>

// Prototypes
unsigned int BitShiftCombine( unsigned char x_high, unsigned char x_low);
void blinkLED(uint8_t blinkCount);
void executeTOFandSample();
void initialize();
void init_GPIO();
void initTimer();
void initClocks();
void initTUSS4470();
void initSPI();
void initADC12(); 
void initDMA();
uint8_t parity16(unsigned int ino);
void sampleLoop();
uint8_t * tuss44x0_regAddParity(uint8_t addr, uint8_t data);
uint8_t tuss44x0_parity(uint8_t * spi16Val);
void writeRegTUSS4470 (uint8_t address, uint8_t value);

// SPI Variables
#define SPICLK	500000
uint8_t SPIInitReturnValue = 0;

// Clock/UCS variables
uint16_t NMIstatus;
#define LF_CRYSTAL_FREQUENCY_IN_HZ     32768
#define HF_CRYSTAL_FREQUENCY_IN_HZ     4000000
#define MCLK_DESIRED_FREQUENCY         4000000   // 4 MHz
#define MCLK_FLLREF_RATIO   MCLK_DESIRED_FREQUENCY / UCS_REFOCLK_FREQUENCY 
uint32_t myACLK  = 0;
uint32_t mySMCLK = 0;
uint32_t myMCLK  = 0;

// TOF Variables
uint8_t sampleSetLoopCount = 0;
bool samplingActive = false;

// ADC variables
#define ADC12_Num_of_Indexes 20
#define ADC12_Num_of_Results 125
volatile uint8_t ADC12_results_index1 = 0;
volatile uint8_t ADC12_results_index2 = 0;
int ADCValuesCounterResults = 0;
int ADCValuesCounterIndex = 0;
volatile uint16_t ADC12_results[ADC12_Num_of_Indexes][ADC12_Num_of_Results] = {};

// DMA variables
#define ANALOG_DMA_CHANNEL  DMA_CHANNEL_0
#define ANALOG_INPUT        ADC12_A_INPUT_A5
#define ANALOG_MEMORY       ADC12_A_MEMORY_0
const uint8_t ANALOG_DMA_SIZE = 125;
uint16_t analog_buffer[ANALOG_DMA_SIZE];

void main(void)
{
    initialize();
    while(1) {
        if (samplingActive == true) sampleLoop();
        __bis_SR_register(LPM3_bits | GIE); // Enter LPM3 w/interrupt (lowest current consumption)
      __delay_cycles(12000);  // delay 3ms @ 4MHZ SMCLK
    }
}

void sampleLoop()
{
    int arrayCopyLoop = 0;
    memset(ADC12_results, 0, sizeof ADC12_results); // clear ADC12_results array
    for (sampleSetLoopCount = 0; sampleSetLoopCount < ADC12_Num_of_Indexes; sampleSetLoopCount++) {
        memset(analog_buffer, 0, sizeof analog_buffer);  // clear analog buffer
        __delay_cycles(24000);  // delay 6ms between each sample set
        executeTOFandSample(); // TUSS4470 - excite transducer and MSP430 ADC12 - sample output
        for (arrayCopyLoop = 0; arrayCopyLoop < ANALOG_DMA_SIZE; arrayCopyLoop++) {
            ADC12_results[sampleSetLoopCount][arrayCopyLoop] = analog_buffer[arrayCopyLoop];
        }
    }
    samplingActive = false;
    return;
}

//// Initialization /////

void initialize() {
    __enable_interrupt();  // enable interrupts
    WDT_A_hold(WDT_A_BASE); // stop watchdog timer
    P1DIR |= 00000001;  // prepare LED communication
    blinkLED(3);  // blink LED 3 times at startup

    initClocks(); // initialize MSP430 clocks
    initTimer(); // initialize timer for 1MHz pulse
    init_GPIO();  // assign ports and physical pins
    initSPI();  // initialize SPI communication for MSP430 -> TUSS4470
    initDMA();  // initialize DMA for storage of ADC12 results
    initADC12();  // initialize ADC12 A/D converter in MSP430F5529
    initTUSS4470();  // initialize/configure TUSS4470
}

void init_GPIO() {
    GPIO_setAsPeripheralModuleFunctionInputPin(GPIO_PORT_P6, GPIO_PIN5);  //  configure Pin 6.5 as input for A/D channel A5 - connected to physical TUSS4470 pin 2 / a.k.a VOUT
    GPIO_setAsPeripheralModuleFunctionOutputPin(GPIO_PORT_P2, GPIO_PIN5);  // MSP430 PIN 2.5 a.k.a 40 / TUSS4470 IO2
    GPIO_setAsOutputPin(GPIO_PORT_P8, GPIO_PIN2); // oscilliscope timing test
    GPIO_setOutputLowOnPin(GPIO_PORT_P8,GPIO_PIN2);  // oscilliscope timing test
}

void initClocks() {

    PMM_setVCore(PMM_CORE_LEVEL_3);

    UCS_setExternalClockSource(LF_CRYSTAL_FREQUENCY_IN_HZ, HF_CRYSTAL_FREQUENCY_IN_HZ);

    // Setup ACLK to use REFO as its oscillator source
    UCS_initClockSignal(UCS_ACLK,                        // Clock you're configuring
            UCS_REFOCLK_SELECT,                          // Clock source
            UCS_CLOCK_DIVIDER_1                          // Divide down clock source by this much
    );

    // Set the FLL's clock reference clock source
    UCS_initClockSignal(UCS_FLLREF,                      // Clock you're configuring
            UCS_REFOCLK_SELECT,    						 // Clock source
            UCS_CLOCK_DIVIDER_1                         // Divide down clock source by this much
    );

    // Configure the FLL's frequency and set MCLK & SMCLK to use the FLL as their source
    UCS_initFLLSettle(MCLK_DESIRED_FREQUENCY, MCLK_FLLREF_RATIO);              // MCLK frequency, Ratio between MCLK and FLL's reference clock source

    myACLK  = UCS_getACLK();
    mySMCLK = UCS_getSMCLK();
    myMCLK  = UCS_getMCLK();  // verify 4MHZ master clock speed
}

//// Timer Initialization ////
// PWM timer - generate 1MHz transducer pulses - SMCLK must be 4 MHz

void initTimer() {

    // Timer A
    // initialize 1MHz PWM timer for  pulses on MSP430 PIN 2.5 a.k.a 40 / TUSS4470 IO2
    Timer_A_outputPWMParam outputPWMParam = {0};
    outputPWMParam.clockSource = TIMER_A_CLOCKSOURCE_SMCLK;
    outputPWMParam.clockSourceDivider = TIMER_A_CLOCKSOURCE_DIVIDER_1;
    outputPWMParam.timerPeriod = 3;
    outputPWMParam.compareRegister = TIMER_A_CAPTURECOMPARE_REGISTER_2;
    outputPWMParam.compareOutputMode = TIMER_A_OUTPUTMODE_RESET_SET;
    outputPWMParam.dutyCycle = 0;
    Timer_A_outputPWM(TIMER_A2_BASE, &outputPWMParam);  // start timer
    Timer_A_setCompareValue(TIMER_A2_BASE, TIMER_A_CAPTURECOMPARE_REGISTER_2, 2);
    Timer_A_stop (TIMER_A2_BASE);

}

//// ADC Initialization ////
// code source: C

void initADC12() {
    // ADC clock source is configured as SMCLK
    // SMCLK and MCLK = 4MHZ
    // Calculate minimum required sample time
    // calculation source: MSP430 User guide section 28.2.5.3 'Sample Timing Considerations'
    // The resistance of the source RS and RI affect tsample. The following equation can be used to calculate the
    // minimum sampling time tsample for a n-bit conversion, where n equals the bits of resolution:
    // t.sample > (RS + RI) * ln(2n+1) * CI + 800 ns
    // Substituting the values for RI and CI given above, the equation becomes:
    // t.sample > (RS + 1.8 KOhm) * ln(2n+1) * 25 pF + 800 ns
    // For example, for 12-bit resolution, if RS is 10 KOhm, t.sample must be greater than 3.46 uS.
    // using measurement of 4.2 KOhms output resistance of TUSS4470
    // sample > (4.2 Kohm + 1.8 KOhm) * ln(2 ^ (12 + 1)) * 25 + 800ns
    // sample > 2.151 us
    // minimum sample time = 2.15 uS
    // if ADC clock = 4MHZ, 1 cycle = 0.25 uS, a minimum of 9 cycles (2.25 uS) is required to meet minimum sample time of 2.15 us (16 cycles or 3.2 uS is closest driverlib option)

    // configure REF (reference voltage) module
    while(REF_ACTIVE == Ref_isRefGenBusy(REF_BASE));
    Ref_setReferenceVoltage(REF_BASE, REF_VREF2_5V);
    Ref_enableReferenceVoltage(REF_BASE);
    __delay_cycles(100);

    ADC12_A_init(ADC12_A_BASE, ADC12_A_SAMPLEHOLDSOURCE_SC, ADC12_A_CLOCKSOURCE_SMCLK, ADC12_A_CLOCKDIVIDER_1);  // higher ADC12_A_CLOCKDIVIDER will increase sampling duration
    ADC12_A_setupSamplingTimer(ADC12_A_BASE, ADC12_A_CYCLEHOLD_16_CYCLES, ADC12_A_CYCLEHOLD_16_CYCLES, ADC12_A_MULTIPLESAMPLESENABLE);  // sample time = 16 Cycles ~ 3.2 uS at 5MHZ ADC clock
    ADC12_A_setResolution(ADC12_A_BASE, ADC12_A_RESOLUTION_12BIT);

    ADC12_A_configureMemoryParam param = {0};  //Configure Memory Buffer
    param.memoryBufferControlIndex = ADC12_A_MEMORY_0;  // Base address of the ADC12_A Module
    param.inputSourceSelect = ADC12_A_INPUT_A5; // Map input A5 to memory buffer 0
    param.positiveRefVoltageSourceSelect = ADC12_A_VREFPOS_INT;
    param.negativeRefVoltageSourceSelect = ADC12_A_VREFNEG_AVSS;  // Vref- = AVss
    param.endOfSequence = ADC12_A_NOTENDOFSEQUENCE; // Memory buffer 0 is not the end of a sequence
    ADC12_A_configureMemory(ADC12_A_BASE, &param);
    ADC12_A_enable(ADC12_A_BASE);
}

void initDMA()
{
    DMA_initParam DMA_init_Param = {0};
    DMA_disableTransferDuringReadModifyWrite();
    DMA_init_Param.channelSelect = DMA_CHANNEL_0;
    DMA_init_Param.transferModeSelect = DMA_TRANSFER_REPEATED_SINGLE;
    DMA_init_Param.transferSize = ANALOG_DMA_SIZE;
    DMA_init_Param.triggerSourceSelect = DMA_TRIGGERSOURCE_24; // ADC conversion ended trigger
    DMA_init_Param.transferUnitSelect = DMA_SIZE_SRCWORD_DSTWORD;
    DMA_init_Param.triggerTypeSelect = DMA_TRIGGER_HIGH;
    DMA_init(&DMA_init_Param);

    // configure DMA channel source and destination address
    DMA_setSrcAddress(ANALOG_DMA_CHANNEL, ADC12_A_getMemoryAddressForDMA(ADC12_A_BASE, ADC12_A_MEMORY_0), DMA_DIRECTION_UNCHANGED);
    DMA_setDstAddress(ANALOG_DMA_CHANNEL, (uint32_t)(uintptr_t)&analog_buffer, DMA_DIRECTION_INCREMENT);
    DMA_clearInterrupt(ANALOG_DMA_CHANNEL);
    DMA_enableInterrupt(ANALOG_DMA_CHANNEL);
    DMA_enableTransfers(ANALOG_DMA_CHANNEL);
}

//// SPI Initialization ////

// code source: A
 
void initSPI() {
    GPIO_setAsOutputPin(GPIO_PORT_P2, GPIO_PIN7); // CS
    GPIO_setOutputHighOnPin(GPIO_PORT_P2,GPIO_PIN7); //Set P2.7 for slave reset
    GPIO_setAsPeripheralModuleFunctionInputPin(GPIO_PORT_P3, GPIO_PIN0);  // MOSI
    GPIO_setAsPeripheralModuleFunctionInputPin(GPIO_PORT_P3, GPIO_PIN1);  // MISO
    GPIO_setAsPeripheralModuleFunctionInputPin(GPIO_PORT_P3, GPIO_PIN2);  // CLK

    //Initialize Master
    USCI_B_SPI_initMasterParam param = {0};
    param.selectClockSource = USCI_B_SPI_CLOCKSOURCE_SMCLK;
    param.clockSourceFrequency = UCS_getSMCLK();

    param.desiredSpiClock = SPICLK;
    param.msbFirst = USCI_B_SPI_MSB_FIRST;
    // TUSS4470 : use SPI_MODE1 ~ CPOL=0, CPHA=1 - from Energia code example - code source B //
    param.clockPhase = USCI_B_SPI_PHASE_DATA_CAPTURED_ONFIRST_CHANGED_ON_NEXT;   // CPHA=1
    param.clockPolarity = USCI_B_SPI_CLOCKPOLARITY_INACTIVITY_LOW;   // CPOL=0
    SPIInitReturnValue =  USCI_B_SPI_initMaster(USCI_B0_BASE, &param);

    if (STATUS_FAIL == SPIInitReturnValue){
        return;
    }
}

//// TUSS4470 Initialization ////

void initTUSS4470()
{
    // recommended TUSS4470 register settings from INDUS_REG_USER_MEMSPACE_447-StemincTDCXDCR_Optimized.txt
    // https://e2e.ti.com/support/sensors/f/1023/t/927400

    writeRegTUSS4470(0x10 ,0x5F); // (BPF_CONFIG_1)
    writeRegTUSS4470(0x11 ,0x00); // (BPF_CONFIG_2)
    writeRegTUSS4470(0x12 ,0x1C); // (DEV_CTRL_1)
    writeRegTUSS4470(0x13 ,0xC1); // DEV_CTRL_2)
    writeRegTUSS4470(0x14 ,0x00); // (DEV_CTRL_3)
    writeRegTUSS4470(0x15 ,0x00); // (DEV_CTRL_4)
    writeRegTUSS4470(0x16 ,0x40); // (VDRV_CTRL)
    writeRegTUSS4470(0x17 ,0x07); // (ECHO_INT_CONFIG)
    writeRegTUSS4470(0x18 ,0x14); //  (ZC_CONFIG)
    writeRegTUSS4470(0x19 ,0x00); //  (XFMR_DRV_LIM)
    writeRegTUSS4470(0x1A ,0x08); //  (BURST_PULSE)
    writeRegTUSS4470(0x1B ,0x02); //  (TOF_CONFIG)
    writeRegTUSS4470(0x1C ,0x08); //  (DEV_STAT)
    writeRegTUSS4470(0x1D ,0xB9); //  (DEVICE_ID)
    writeRegTUSS4470(0x1E ,0x02); //  (REV_ID)
    writeRegTUSS4470(0x1F ,0x00); //  (DEV_TI_UNLOCK)
}


// code source: B
//// write register values to TUSS4470 over SPI bus ////
void writeRegTUSS4470 (uint8_t address, uint8_t value)  {
    uint8_t *regValPtr;
    uint8_t tuss4470regWriteArray[2];

    regValPtr = tuss44x0_regAddParity(address, value);
    tuss4470regWriteArray[0] = *regValPtr;
    tuss4470regWriteArray[1] = *(regValPtr + 1);  // increment pointer 1 byte

    //Enable SPI module
    USCI_B_SPI_enable(USCI_B0_BASE);

    //Wait for slave to initialize
    __delay_cycles(100);

    //USCI_B0 TX buffer ready?
    while (!USCI_B_SPI_getInterruptStatus(USCI_B0_BASE, USCI_B_SPI_TRANSMIT_INTERRUPT)) ;

    GPIO_setOutputLowOnPin (GPIO_PORT_P2,GPIO_PIN7); // set CS LOW to signal transfer ready to begin
    USCI_A_SPI_transmitData(USCI_B0_BASE,tuss4470regWriteArray[0]);
    while(USCI_B_SPI_isBusy(USCI_B0_BASE));
    USCI_A_SPI_transmitData(USCI_B0_BASE,tuss4470regWriteArray[1]);
    while(USCI_B_SPI_isBusy(USCI_B0_BASE));
    GPIO_setOutputHighOnPin (GPIO_PORT_P2,GPIO_PIN7);  // set CS HIGH to signal transfer & receive complete
}

// code source: B
//// Execute Time of Flight and Sample ////

 void executeTOFandSample() {
    ADC12_A_enable(ADC12_A_BASE);
    ADC12_A_clearInterrupt(ADC12_A_BASE, ADC12IFG0);    // clear ADC12 interrupt flags
    DMA_clearInterrupt(ANALOG_DMA_CHANNEL);
    DMA_enableInterrupt(ANALOG_DMA_CHANNEL);
    DMA_enableTransfers(ANALOG_DMA_CHANNEL);
    writeRegTUSS4470(0x1B, 0x00);   // TOF_CONFIG's CMD_TRIGGER to 0
    writeRegTUSS4470(0x1B, 0x01);   // TOF_CONFIG's CMD_TRIGGER to 1 (enable burst mode)

   // ADC12 sample and convert
    ADC12_A_startConversion(ADC12_A_BASE, ADC12_A_MEMORY_0, ADC12_A_REPEATED_SINGLECHANNEL);
    TA2CTL |= MC_1;  // start 1 MHz pulses on MSP430 PIN 2.5 a.k.a 40 / TUSS4470 IO2
//    P8OUT |= BIT2;  // set pin 8.2 high - for oscilloscope timing tests
    __delay_cycles(40);  // 40 cycle delay produces ~ 12 to 14 pulses at 1MHz if SMCLK = 4 MHz
    TA2CTL &= ~MC_1;  // stop 1 MHz pulses on MSP430 PIN 2.5 a.k.a 40 / TUSS4470 IO2
    writeRegTUSS4470(0x1B, 0x00);   // TOF_CONFIG's CMD_TRIGGER to 0 (disable burst mode)
    GPIO_setOutputLowOnPin(GPIO_PORT_P2,GPIO_PIN5);   // reset PIN 2.5
 }

// code source: B
/*------------------------------------------------- tuss44x0_regAddParity -----
 |  Function tuss44x0_regAddParity
 |
 |  Purpose:  Modify addr byte, Calculate Parity bit and return array pointer.
 |
 |  Parameters:
 |  		addr (IN) -- valid register address byte between 0x10 to 0x1E
 |  		data (IN) -- valid register data byte between 0x00 to 0xFF
 |
 |  Returns:  none
 *-------------------------------------------------------------------*/
uint8_t * tuss44x0_regAddParity(uint8_t addr, uint8_t data)
{  
  uint8_t regByteArr[2];
  regByteArr[0] = (addr & 0x3F) << 1;          // shift addr to MSB position
  regByteArr[1] = data;                        // null data byte during read
  regByteArr[0] |= tuss44x0_parity(regByteArr); // apply parity bit
  return regByteArr;
}

// code source: B
/*------------------------------------------------- tuss44x0_parity -----
 |  Function tuss44x0_parity
 |
 |  Purpose:  Calculates odd parity bit for given SPI data.
 |
 |  Parameters:
 |      spi16Val (IN) -- 16 bit SPI data byte array
 |
 |  Returns:  byte representation of SPI data array element 0's LSB
 |          containing calculated parity bit value
 *-------------------------------------------------------------------*/
uint8_t tuss44x0_parity(uint8_t * spi16Val)
{
  // SPI frame comprised of: 1 RW bit, 6 bits for the register address, 1 ODD parity bit for entire SPI frame, 8 bits for data
  return parity16(BitShiftCombine(spi16Val[0],spi16Val[1]));
}

// code source: B
/*------------------------------------------------- tuss44x0_parity -----
 |  Function tuss44x0_parity
 |
 |  Purpose:  Determines the number of ones in a given unsigned integer
 |          to return odd parity bit result.
 |
 |  Parameters:
 |      ino (IN) -- 16 bit unsigned integer
 |  Returns:  parity bit value
 *-------------------------------------------------------------------*/
uint8_t parity16(unsigned int ino)
{
  int i = 0;
  uint8_t noofones = 0;
  for(i = 0; i < 16; i++)
  {
    if(((ino>>i) & 1) == 1)
    {
      noofones++;
    }
  }
  // if remainder of one, add one to parity bit field
  return ((noofones+1) % 2);
}

// code source: B
/*------------------------------------------------- BitShiftCombine -----
 |  Function BitShiftCombine
 |
 |  Purpose:  Combines two byte values into a single unsigned integer value.
 |
 |  Parameters:
 |      x_high (IN) -- MSB input byte
  |     x_low (IN) -- LSB input byte
 |
 |  Returns:  unsigned integer of combined MSB and LSB bytes
 *-------------------------------------------------------------------*/
unsigned int BitShiftCombine( unsigned char x_high, unsigned char x_low)
{
  unsigned int combined;
  combined = x_high;              // send x_high to rightmost 8 bits
  combined = combined<<8;         // shift x_high over to leftmost 8 bits
  combined |= x_low;              // logical OR keeps x_high intact in combined and fills in rightmost 8 bits
  return combined;
}

//// LED Indicator ////

void blinkLED(uint8_t blinkCount) {
    int k = 0;
    int l = 0;
    for (k = 0; k < blinkCount; k++)
    {
        P1OUT ^= 0x01;                      // Toggle P1.0 using exclusive-OR operation (^=)
                                            // P1OUT is another register which holds the status of the LED.
                                            // '1' specifies that it's ON or HIGH, while '0' specifies that it's OFF or LOW
                                            // Since our LED is tied to P1.0, we will toggle the 0 bit of the P1OUT register

        for(l=0; l < 20000; l++) {}            // Delay between LED toggles. This for-loop will run until the condition is met.
                                            //In this case, it will loop until the variable i increments to 200.
    }
    P1OUT = 0x00;
}


//// Interrupt Service Routines ////

// DMA interrupt vector service routine
#if defined(__TI_COMPILER_VERSION__) || defined(__IAR_SYSTEMS_ICC__)
#pragma vector = DMA_VECTOR
__interrupt
#elif defined(__GNUC__)
__attribute__((interrupt(DMA_VECTOR)))
#endif
void DMA_ISR (void)
{
//    P8OUT &=~ BIT2;  // set pin 8.2 low - for oscilloscope timing tests
    switch (__even_in_range(DMAIV, 16))
    {
        case 0: break;  //None
        case 2:         //DMA0IFG = DMA Channel 0
        {
            ADC12_A_disableConversions(ADC12_A_BASE, ADC12_A_PREEMPTCONVERSION); // disable ADC conversions after DMA analog_buffer size is reached
            break;
        }
        case 4: break;  //DMA1IFG = DMA Channel 1
        case 6: break;  //DMA2IFG = DMA Channel 2
        case 8: break;  //DMA3IFG = DMA Channel 3
        case 10: break; //DMA4IFG = DMA Channel 4
        case 12: break; //DMA5IFG = DMA Channel 5
        case 14: break; //DMA6IFG = DMA Channel 6
        case 16: break; //DMA7IFG = DMA Channel 7
        default: break;
    }
}

// NMI interrupt vector service routine
__interrupt void NMI_ISR(void)
{
        do {
                // If it still can't clear the oscillator fault flags after the timeout,
                // trap and wait here.
            NMIstatus = UCS_clearAllOscFlagsWithTimeout(1000);
        } while (NMIstatus != 0);
}


code changes for doubling the sampling resolution :

34     #define HF_CRYSTAL_FREQUENCY_IN_HZ     8000000
35     #define MCLK_DESIRED_FREQUENCY 8000000 // 8 MHz
46     #define ADC12_Num_of_Indexes 10 // MSP430F5529 limited to 6KB storage
47     #define ADC12_Num_of_Results 250
58     const uint8_t ANALOG_DMA_SIZE = 250;
146   outputPWMParam.clockSourceDivider = TIMER_A_CLOCKSOURCE_DIVIDER_2;
314   __delay_cycles(80);

MSP430F5529LP pinout diagram (User guide pg. 26)