2017 VNA Design Notes

From Class Wiki
Jump to navigation Jump to search
The printable version is no longer supported and may have rendering errors. Please update your browser bookmarks and please use the default browser print function instead.

These are notes so I don't forget what I needed to do to get things working for the software on the 2017 VNA project. This is not how you should write up your project! The purpose of this page is to give you an idea how a design is done. As you go along, you learn and the design gets better. In your write up you should describe the finished product, not how you there. The purpose of this page is to show you how the design process went. An you design, ideas occur to you, and you investigate them. Some work, and some don't. So DO NOT write your project up like this!

Hardware

The test circuit is the Etherkit SI5351 Breakout Board. The I2C pins SDA (P6.4) and SCL (P6.5) on the MSP432 Launchpad are used to communicate with the SI5351A. The jumpers J2 and J3 are set for 3.3V operation like this. Test circuit.jpgThe pinout for the MSP-EXP432P401R for Energia (arduino) applications on using this launchpad on this page helped me figure this out. The I2C pins are the same on our board's design. The results can be seen here: Lo results.jpg

Software

The signal processing VNA diagram is shown below: VNA Software Diagram.png

Non Simultaneous Sampling Problem

The A/D converters don't sample at the same instant. This is a problem because the signal processing assumes it. The first attempt to fix the problem was to use an FIR filter to delay the signals to be simultaneous. It would have worked if the delay was much longer, but the errors introduced were worse than ignoring the small delay. This was modeled in octave. The script that shows how that worked is below:

% This script is to make sure the DSP in the 2017 VNA is correct.
% The A/D converters are not synchronized so the Q is delayed by
% Td from the I signal.  From this it appears I can't do anything
% with FIR filters to improve the sampling error, it is so small. 

pkg load signal;
clear all;
close all;

T=1/8000; % Sample rate.  In real life 1/8000.
ADC14CLK = 48e6;  % In real life 48e6.
Td = 16/ADC14CLK

N=200;
ti=0:T:(N-1)*T;
tq=Td:T:(N-1)*T+Td;
t=0:T/10:(N-1)*T;

fIF = 200;
theta = 0;

via = cos(2*pi*fIF*t+theta);
vi = cos(2*pi*fIF*ti+theta);
vq = sin(2*pi*fIF*(tq-Td)+theta);
vqa = sin(2*pi*fIF*t+theta);

% Compensate for delay here.
f = -1/2/T:1/N/T:(N-1)/2/N/T;

H = exp(j*2*pi*f*Td);%.*kaiser(N)';
Hsh = fftshift(H);
h=real(ifft(Hsh));
h(1)= 1;
%h = h.*kaiser(N)';

vqs = filter(h,1,vq);

plot(tq,vq,'r*',t,vqa)


The FIR filter did not work because the delay was too small. So I tried another way:

%  This script is to investigate a time delay due to having on multiplexed A/D
%  on the MSP432.  The upshot is that shifting the sine in the down conversion
%  signal by Td makes it almost perfect.

pkg load signal;
clear all;
close all;

T=1/8000; % Sample rate.  In real life 1/8000.
ADC14CLK = 48e6;  % In real life 48e6.
Td = 16/ADC14CLK

N=2000;
ti=0:T:(N-1)*T;
tq=Td:T:(N-1)*T+Td;
t=0:T/10:(N-1)*T;

fIF = 3500;
theta = pi/6;
thetad = theta*180/pi

vin = cos(2*pi*fIF*t+theta)+j*sin(2*pi*fIF*(t-Td)+theta);
vin1 = cos(2*pi*fIF*t+theta)+j*sin(2*pi*fIF*(t)+theta);
dc=cos(2*pi*fIF*t)-j*sin(2*pi*fIF*(t-Td));
x=dc.*vin;
x1 = exp(-j*2*pi*fIF*t).*vin1;
temp1=mean(x1)
temp=mean(x)
mag1=abs(temp1)
mag=abs(temp)
ang=angle(temp);
ang1=angle(temp1);
angd1=ang1*180/pi
angd=ang*180/pi

This worked much better. Instead of multiplying by we multiply by .

Notes on ADC14

The examples were helpful, but I needed a TA0 triggered multiple sequence convert. The last problem to get fixed was toggling the AD14ENC bit after each sequence. Here is a copy of my experimental test program. It does a multi-sequence convert each time TA0CCR1 trips it. This is what we need because we will be converting the reference and test signals, both in phase and quadrature, which makes four signals.

/*
 * -------------------------------------------
 *    MSP432 DriverLib - v4_00_00_11 
 * -------------------------------------------
 *
 * --COPYRIGHT--,BSD,BSD
 * Copyright (c) 2017, 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--*/
/*******************************************************************************
 * MSP432 ADC14 - Multiple Channel Sample without Repeat
 *
 * Description: In this code example, the feature of being able to scan multiple
 * ADC channels is demonstrated by the user a the DriverLib APIs.  Conversion
 * memory registers ADC_MEM0 - ADC_MEM7 are configured to read conversion
 * results from A0-A7 respectively. Conversion is enabled and then sampling is
 * toggled using a software toggle. Repeat mode is not enabled and sampling only
 * occurs once (and it is expected that the user pauses the debugger to observe
 * the results). Once the final sample has been taken, the interrupt for
 * ADC_MEM7 is triggered and the result is stored in the resultsBuffer buffer.
 *
 *                MSP432P401
 *             ------------------
 *         /|\|                  |
 *          | |                  |
 *          --|RST         P5.5  |<--- A0 (Analog Input)
 *            |            P5.4  |<--- A1 (Analog Input)
 *            |            P5.3  |<--- A2 (Analog Input)
 *            |            P5.2  |<--- A3 (Analog Input)
 *            |            P5.1  |<--- A4 (Analog Input)
 *            |            P5.0  |<--- A5 (Analog Input)
 *            |            P4.7  |<--- A6 (Analog Input)
 *            |            P4.6  |<--- A7 (Analog Input)
 *            |                  |
 *            |                  |
 *
 *            4.1, 4.3, 4.5, 4.7 are the eventual pins needed.
 *
 * Author: Timothy Logan
 * This was modified by Rob Frohne to do multiple ADC at 8 kHz sample rate.
 ******************************************************************************/

/* DriverLib Includes */
#include <ti/devices/msp432p4xx/driverlib/driverlib.h>

/* Standard Includes */
#include <stdint.h>

#include <string.h>
#include <stdio.h>

#define SMCLK_FREQUENCY     48000000
#define SAMPLE_FREQUENCY    8000

#define SAMPLE_LENGTH       512

/*
 Timer_A PWM Configuration Parameter
Timer_A_PWMConfig pwmConfig =
{
        TIMER_A_CLOCKSOURCE_SMCLK,
        TIMER_A_CLOCKSOURCE_DIVIDER_1,
        (SMCLK_FREQUENCY/SAMPLE_FREQUENCY),
        TIMER_A_CAPTURECOMPARE_REGISTER_1,
        TIMER_A_OUTPUTMODE_SET_RESET,
        (SMCLK_FREQUENCY/SAMPLE_FREQUENCY)/2
};
*/

/* Timer_A Continuous Mode Configuration Parameter */
const Timer_A_UpModeConfig upModeConfig =
{
        TIMER_A_CLOCKSOURCE_SMCLK,           // SMCLK Clock Source
        TIMER_A_CLOCKSOURCE_DIVIDER_1,       // SMCLK/1 = 48MHz
        (SMCLK_FREQUENCY/SAMPLE_FREQUENCY),  // Number of counts
        TIMER_A_TAIE_INTERRUPT_DISABLE,      // Disable Timer ISR
        TIMER_A_CCIE_CCR0_INTERRUPT_DISABLE, // Disable CCR0
        TIMER_A_DO_CLEAR                     // Clear Counter
};

/* Timer_A Compare Configuration Parameter */
const Timer_A_CompareModeConfig compareConfig =
{
        TIMER_A_CAPTURECOMPARE_REGISTER_1,          // Use CCR1
        TIMER_A_CAPTURECOMPARE_INTERRUPT_DISABLE,   // Disable CCR interrupt
        TIMER_A_OUTPUTMODE_SET_RESET,               // Toggle output bit
        (SMCLK_FREQUENCY/SAMPLE_FREQUENCY)
};


static uint16_t resultsBuffer[8];
static uint16_t chan0[SAMPLE_LENGTH];

int main(void)
{
    int i;
    /* Halting WDT  */
    MAP_WDT_A_holdTimer();
    MAP_Interrupt_enableSleepOnIsrExit();

    /* Configuring debugging pins as output */
    MAP_GPIO_setAsOutputPin(GPIO_PORT_P4, GPIO_PIN1);
    MAP_GPIO_setAsOutputPin(GPIO_PORT_P1, GPIO_PIN0);

    /* Set to Vcore1 */
    MAP_PCM_setCoreVoltageLevel(PCM_VCORE1);

    /* Set to use DCDC */
    MAP_PCM_setPowerState(PCM_AM_DCDC_VCORE1);

    /* Initializes Clock System */
    CS_setDCOCenteredFrequency(CS_DCO_FREQUENCY_48);
    CS_initClockSignal(CS_MCLK, CS_DCOCLK_SELECT, CS_CLOCK_DIVIDER_1 );
    CS_initClockSignal(CS_HSMCLK, CS_DCOCLK_SELECT, CS_CLOCK_DIVIDER_1 );
    CS_initClockSignal(CS_SMCLK, CS_DCOCLK_SELECT, CS_CLOCK_DIVIDER_1 );
    CS_initClockSignal(CS_ACLK, CS_REFOCLK_SELECT, CS_CLOCK_DIVIDER_1);

    /* Zero-filling buffer */
    memset(resultsBuffer, 0x00, 8);

    /* Setting reference voltage to 2.5  and enabling reference */
    MAP_REF_A_setReferenceVoltage(REF_A_VREF2_5V);
    MAP_REF_A_enableReferenceVoltage();

    /* Initializing ADC (MCLK/1/1) */
    MAP_ADC14_enableModule();
    MAP_ADC14_initModule(ADC_CLOCKSOURCE_MCLK, ADC_PREDIVIDER_1, ADC_DIVIDER_1,
            0);

    /* Configuring GPIOs for Analog In */
    GPIO_setAsPeripheralModuleFunctionInputPin(GPIO_PORT_P5,
            GPIO_PIN5 | GPIO_PIN4 | GPIO_PIN3 | GPIO_PIN2 | GPIO_PIN1
                    | GPIO_PIN0, GPIO_TERTIARY_MODULE_FUNCTION);
    MAP_GPIO_setAsPeripheralModuleFunctionInputPin(GPIO_PORT_P4,
            GPIO_PIN7 | GPIO_PIN6, GPIO_TERTIARY_MODULE_FUNCTION);


    /* Configuring ADC Memory (ADC_MEM0 - ADC_MEM7 (A0 - A7)  with no repeat)
     * with internal 2.5v reference */
    MAP_ADC14_configureMultiSequenceMode(ADC_MEM0, ADC_MEM7, false);
    MAP_ADC14_configureConversionMemory(ADC_MEM0,
            ADC_VREFPOS_INTBUF_VREFNEG_VSS,
            ADC_INPUT_A0, false);
    MAP_ADC14_configureConversionMemory(ADC_MEM1,
            ADC_VREFPOS_INTBUF_VREFNEG_VSS,
            ADC_INPUT_A1, false);
    MAP_ADC14_configureConversionMemory(ADC_MEM2,
            ADC_VREFPOS_INTBUF_VREFNEG_VSS,
            ADC_INPUT_A2, false);
    MAP_ADC14_configureConversionMemory(ADC_MEM3,
            ADC_VREFPOS_INTBUF_VREFNEG_VSS,
            ADC_INPUT_A3, false);
    MAP_ADC14_configureConversionMemory(ADC_MEM4,
            ADC_VREFPOS_INTBUF_VREFNEG_VSS,
            ADC_INPUT_A4, false);
    MAP_ADC14_configureConversionMemory(ADC_MEM5,
            ADC_VREFPOS_INTBUF_VREFNEG_VSS,
            ADC_INPUT_A5, false);
    MAP_ADC14_configureConversionMemory(ADC_MEM6,
            ADC_VREFPOS_INTBUF_VREFNEG_VSS,
            ADC_INPUT_A6, false);
    MAP_ADC14_configureConversionMemory(ADC_MEM7,
            ADC_VREFPOS_INTBUF_VREFNEG_VSS,
            ADC_INPUT_A7, false);

    /* Enabling the interrupt when a conversion on channel 7 (end of sequence)
     *  is complete and enabling conversions */
    MAP_ADC14_enableInterrupt(ADC_INT7);

    ADC14_setSampleHoldTime(ADC_PULSE_WIDTH_128, ADC_PULSE_WIDTH_4);

/*     Configuring Timer_A to have a period of approximately 500ms and
     * an initial duty cycle of 10% of that (3200 ticks)
    Timer_A_generatePWM(TIMER_A0_BASE, &pwmConfig);*/

    /* Configuring Timer_A in continuous mode as setup in upModeConfig above */
    MAP_Timer_A_configureUpMode(TIMER_A0_BASE, &upModeConfig);

    /* Configuring Timer_A0 in CCR1 to trigger as set in compareConfig above */
    MAP_Timer_A_initCompare(TIMER_A0_BASE, &compareConfig);

    /* Configuring the sample trigger to be sourced from Timer_A0  and setting it
     * to automatic iteration after it is triggered*/
    MAP_ADC14_setSampleHoldTrigger(ADC_TRIGGER_SOURCE1, false);

    /* Setting up the sample timer to automatically step through the sequence
     * convert.
     */
    MAP_ADC14_enableSampleTimer(ADC_AUTOMATIC_ITERATION);

    //MAP_ADC14_toggleConversionTrigger();

    /* Enabling Interrupts */
    MAP_Interrupt_enableInterrupt(INT_ADC14);
    MAP_Interrupt_enableMaster();

    /* Triggering the start of the sample */
    MAP_ADC14_enableConversion();

    /* Starting the Timer */
    MAP_Timer_A_startCounter(TIMER_A0_BASE, TIMER_A_UP_MODE);

    for (i=0; i<SAMPLE_LENGTH; i++)
    {
        chan0[i] = 0;
    }

    GPIO_setOutputHighOnPin(GPIO_PORT_P1, GPIO_PIN0);
    /* Going to sleep */
    while (1)
    {
/*        for(i=0;i<10000;i++)
        {
            GPIO_toggleOutputOnPin(GPIO_PORT_P4, GPIO_PIN1);
        }*/
        for(i=0;i<SAMPLE_LENGTH; i++)
            if(chan0[i]!=0)
            {
                i=i;
                //printf("i is: %d for chan0[i] is: %d\n",chan0[i],i);
            }
        //MAP_PCM_gotoLPM0();
    }
}

/* This interrupt is fired whenever a conversion is completed and placed in
 * ADC_MEM7. This signals the end of conversion and the results array is
 * grabbed and placed in resultsBuffer */
void ADC14_IRQHandler(void)
{
    uint64_t status;
    static int i = 0;

    status = MAP_ADC14_getEnabledInterruptStatus();
    MAP_ADC14_clearInterruptFlag(status);

    if(status & ADC_INT7)
    {
        MAP_ADC14_getMultiSequenceResult(resultsBuffer);
        chan0[i] = *resultsBuffer;
        i=(i+1)%SAMPLE_LENGTH;
    }

    ADC14_disableConversion();

    //if(!ADC14_toggleConversionTrigger())
    {
        GPIO_setOutputLowOnPin(GPIO_PORT_P1, GPIO_PIN0);
    }
    //else
    {
        GPIO_toggleOutputOnPin(GPIO_PORT_P4, GPIO_PIN1);
    }
    ADC14_enableConversion();
}

There was about 100/16384*2.5 volts (15 mV) noise when I grounded the input. It was quite a bit worse with the signal generator on a sign wave. and looked worse than the oscilloscope which is only eight bits. The sample rate was correct at 8 KHz. There was no alias filter.

Notes on the SI5351A

I decided to use the Energia tools and the Arduino Etherkit SI5351A library to more quickly get the embedded software going. I think I will be able to combine this with a library I write for the ADC14 so that the users can just manipulate .ino files. One thing I found out that may be a problem at low frequencies is that to get 90 degrees phase difference, the lowest frequency is 4.6875 MHz. It would be nice to have that lower, but this comes from 600/128 MHz, and 128 is the largest number you can use and 600 MHz is the smallest PLL frequency you can use. One way to get around this limitation is to allow the image frequency (assuming we use high side injection, which means the local oscillator is and not use a quadrature mixing scheme below 4.6875 MHz. This is probably not a big issue unless using on an antenna where that frequency is present. It might be interesting to test and see if using both mixers could be used to lessen the probability of an image, by letting one local oscillator be high side injection on one, and low side on the other (the local oscillator frequency is: ), or perhaps just letting them both be high side and averaging the results. This will require some Octave testing. At this low frequency setting, the frequencies are rather discrete, the next highest one is 601 MHz/128 = 4.6963 MHz, etc. There are some detailed notes in the application note AN619. Testing needs to be done to determine how important the image reject mixer is. It may be cheaper and easier to just use one mixer (no image rejection) in future versions.

Code Composer Studio Setup for Energia on Ubuntu 17.04 (64 Bit)

I downloaded the energia package using the CCS App center. Then I had to run the energia software (not from CCS) and use the Tools->Board->Boards Manager to install the MSP432 energia arduino libraries. I downloaded both MSP432 (red and black) libraries. Then, because energia was compiled for 32 bit machines, I had to:

sudo apt-get install libc6:i386 libx11-6:i386 libasound2:i386 libatk1.0-0:i386 libcairo2:i386 libcups2:i386 libdbus-glib-1-2:i386 libgconf-2-4:i386 libgdk-pixbuf2.0-0:i386 libgtk-3-0:i386 libice6:i386 libncurses5:i386 libsm6:i386 liborbit2:i386 libudev1:i386 libusb-0.1-4:i386 libstdc++6:i386 libxt6:i386 libxtst6:i386 libgnomeui-0:i386 libusb-1.0-0-dev:i386 libcanberra-gtk-module:i386

I was then able to program and load the Blink example on the MSP432 board with energia. Lastly I had to in CCSV7, go to Window->Preferences->Code Composer Studio->Build->Compilers and Add a link to the compiler which was at: ~/.energia15/packages/energia/tools/arm-none-eabi-gcc/4.8.4-20140725/bin After that I was able to use CCSV7, which allows debugging.

Setting up a CCSV7 Project

I found it is not easy to change back and forth between the GNU tools and TI's tools. The makefile seems to get messed up. It is easiest to import an example into CCS. Sometimes you need to use more than one set of libraries. For example, I need the Energia libraries, and the SimpleLink ones. After you import a new project from the Resource center go into the Build Settings->General->Products, and select what you the other library you need. I selected Energia and SimpleLink (for Driverlib). Then you need to go add the include path for the new library. It is best if you use the variable for the install path as a base for the include path. This will make your code compile on another machine, and is useful if you plan to share it on github or elsewhere. You also may need to do a similar thing for the linker's libraries. There are some very useful discussions on changing to the GNU tools here on the CCS Wiki. Some of the difficulties I had getting GNU tools projects to work with the SimpleLink SDK are described in my E2E posts here. The summary is that you need to check if COM_TI_SIMPLELINK_MSP432_SDK_INCLUDE_PATH and COM_TI_SIMPLELINK_MSP432_SDK_LIBRARY_PATH were set to point to the correct locations. You can set them under Build Settings->Build->Variables. Check the compiler output console to see that you got them right.

Using Energia with Driverlib

Energia uses TI-RTOS and so registering interrupts is not done in the startup C file, but using the Hwi object (See Section 3.4 and following). I made the Blink_INT_Test project to test this. This uses Driverlib and Energia, incorporating Timer_A interrupts that blink an LED. The .ino file is:

/*
  Blink
  The basic Energia example.
  Turns on an LED on for one second, then off for one second, repeatedly.
  Change the LED define to blink other LEDs.
  
  Hardware Required:
  * LaunchPad with an LED
  
  This example code is in the public domain.
*/
extern "C"{
#include "ta_up.h"
};
// most launchpads have a red LED
#define LED RED_LED

//see pins_energia.h for more LED definitions
//#define LED GREEN_LED
  
// the setup routine runs once when you press reset:
void setup() {                
  // initialize the digital pin as an output.
  pinMode(LED, OUTPUT);
  ta_up_main();
}

// the loop routine runs over and over again forever:
void loop() {
  //digitalWrite(LED, HIGH);   // turn the LED on (HIGH is the voltage level)
  delay(1000);               // wait for a second
  digitalWrite(LED, LOW);    // turn the LED off by making the voltage LOW
  delay(1000);               // wait for a second
}
 and the ta_up.h file is:
/*
 * ta_up.h
 *
 *  Created on: May 3, 2017
 *      Author: frohro
 */

#ifndef TA_UP_H_
#define TA_UP_H_

#include <ti/sysbios/family/arm/m3/Hwi.h>
int ta_up_main(void);

#endif /* TA_UP_H_ */
 

and the ta_up.c file is:

/*
 * ta_up.c
 *
 *  Created on: May 3, 2017
 *      Author: frohro
 */

/*
 * -------------------------------------------
 *    MSP432 DriverLib - v4_00_00_11
 * -------------------------------------------
 *
 * --COPYRIGHT--,BSD,BSD
 * Copyright (c) 2017, 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--*/
/*******************************************************************************
 * MSP432 PWM TA1.1-2, Up/Down Mode, DCO SMCLK
 *
 * Description: Toggle P1.0 using software and TA_0 ISR. Timer0_A is
 * configured for up mode, thus the timer overflows when TAR counts
 * to CCR0. In this example, CCR0 is loaded with 0x2DC6 which makes the LED
 * toggle every half a second..
 * ACLK = n/a, MCLK = SMCLK = default DCO ~1MHz
 * TACLK = SMCLK/64
 *
 *         MSP432P401
 *      -------------------
 *  /|\|                   |
 *   | |                   |
 *   --|RST                |
 *     |                   |
 *     |               P1.0|-->LED
 *     |                   |
 *
 * Author: Timothy Logan
*******************************************************************************/
/* DriverLib Includes */
#include <ti/devices/msp432p4xx/driverlib/driverlib.h>

#include "ta_up.h"

void TA1_0_IRQHandler(void)
{
    MAP_GPIO_toggleOutputOnPin(GPIO_PORT_P1, GPIO_PIN0);
    MAP_Timer_A_clearCaptureCompareInterrupt(TIMER_A1_BASE,
            TIMER_A_CAPTURECOMPARE_REGISTER_0);
}


/* Application Defines  */
#define TIMER_PERIOD    0x2DC6

/* Timer_A UpMode Configuration Parameter */
const Timer_A_UpModeConfig upConfig =
{
        TIMER_A_CLOCKSOURCE_SMCLK,              // SMCLK Clock Source
        TIMER_A_CLOCKSOURCE_DIVIDER_64,          // SMCLK/1 = 3MHz
        TIMER_PERIOD,                           // 5000 tick period
        TIMER_A_TAIE_INTERRUPT_DISABLE,         // Disable Timer interrupt
        TIMER_A_CCIE_CCR0_INTERRUPT_ENABLE ,    // Enable CCR0 interrupt
        TIMER_A_DO_CLEAR                        // Clear value
};

int ta_up_main(void)
{
    Hwi_Params params;

    /* Stop WDT  */
    MAP_WDT_A_holdTimer();

    // Register interrupt
    Hwi_Params_init(&params);
    Hwi_create(INT_TA1_0, TA1_0_IRQHandler, &params, 0);

    /* Configuring P1.0 as output */
    MAP_GPIO_setAsOutputPin(GPIO_PORT_P1, GPIO_PIN0);
    MAP_GPIO_setOutputLowOnPin(GPIO_PORT_P1, GPIO_PIN0);

    /* Configuring Timer_A1 for Up Mode */
    MAP_Timer_A_configureUpMode(TIMER_A1_BASE, &upConfig);

    /* Enabling interrupts and starting the timer */
    MAP_Interrupt_enableSleepOnIsrExit();
    MAP_Interrupt_enableInterrupt(INT_TA1_0);
    MAP_Timer_A_startCounter(TIMER_A1_BASE, TIMER_A_UP_MODE);

    /* Enabling MASTER interrupts */
    MAP_Interrupt_enableMaster();

    /* Sleeping when not in use */
    //while (1)
    {
        //MAP_PCM_gotoLPM0();
    }
    return 1;
}
  

This shows how to incorporate the Hwi_create(), etc. to set up the interrupt vectors.

Energia is multi threaded, executing up to four .ino files separately. The example MultiTaskSerial was helpful to understand this, and for serial communication dubugging. Using it I found the Energia serial monitor/port on my Linux box is /dev/ttyACM0 (usually). I was able to make an example project that used code from the SimpleLink DriverLib for toggling a GPIO to turn on and off a LED on P1.0 work with a .ino file. To include a C header file in a .ino source file, you need to use:

extern "C"{#include "file.h"}

I actually may not need to use this, because the Arduino Serial object will be used in place of the backchannel UART software I was using, and the ADC14 is not using any interrupt subroutine, but is being fired automatically by TimerA. A future version, however, may use DMA, and that will probably require an interrupt subroutine. You have to be careful when you are using Driverlib with the Energia software that in your Driverlib stuff you don't mess something up that Energia needs. The routine adc14.c was setting the clocks to go as fast as possible, to make the delay between the ADC channels as little as possible. Making the bare metal driverlib ADC14 multiple channel conversion compatible with Energia took a while. The final thing was setting the interrupt priority at 60. Here is example code that shows the ADC14 multichannel converter working in concert with Energia.

#include "Arduino.h"
#include "Wire.h"
#include "si5351.h"

extern "C"{
#include <copy2_adc14.h>
};

Si5351 si5351;

// the setup routine runs once when you press reset:
void setup() {
  Serial.begin(115200);
  si5351.init(SI5351_CRYSTAL_LOAD_8PF, 0, 0); // Needs hardware plugged in!
  adc14_();
  ADC14_enableConversion();
}

// the loop routine runs over and over again forever:
void loop() {
    static int i=0;
    //delay(500);
    Serial.print(i++);
    Serial.print(":  ");
    Serial.print(TA3R);
    Serial.print("  ");
    Serial.println("Hello from Copy (2) of ADC14_!");
}

Here is the header file:

/*
 * adc14_.h
 *
 *  Created on: May 12, 2017
 *      Author: frohro
 */

#ifndef COPY2_ADC14_H_
#define COPY2_ADC14_H_

/* DriverLib Includes */
#include <ti/devices/msp432p4xx/driverlib/driverlib.h>
#include <ti/sysbios/family/arm/m3/Hwi.h>

/* Standard Includes */
#include <stdint.h>

#include <stdbool.h>
#define SMCLK_FREQ 12000000
#define SAMPLE_FREQ 8000
//Timer_A Continuous Mode Configuration Parameter
const Timer_A_UpModeConfig upModeConfig = // This DOES work
{
        TIMER_A_CLOCKSOURCE_SMCLK,           // SM Clock Source
        TIMER_A_CLOCKSOURCE_DIVIDER_1,       // SMCLK/1 = 24MHz
        (SMCLK_FREQ/SAMPLE_FREQ),
        TIMER_A_TAIE_INTERRUPT_DISABLE,      // Disable Timer ISR
        TIMER_A_CCIE_CCR0_INTERRUPT_DISABLE, // Disable CCR0
        TIMER_A_DO_CLEAR                     // Clear Counter
};

/* Timer_A Compare Configuration Parameter */
const Timer_A_CompareModeConfig compareConfig =
{
        TIMER_A_CAPTURECOMPARE_REGISTER_1,          // Use CCR1
        TIMER_A_CAPTURECOMPARE_INTERRUPT_DISABLE,   // Disable CCR interrupt
        TIMER_A_OUTPUTMODE_SET_RESET,               // Toggle output but
        (SMCLK_FREQ/SAMPLE_FREQ)                    // Should be 8 kHz sample rate
};

/* Statics */
static volatile uint_fast16_t resultsBuffer[UINT8_MAX];
static volatile uint8_t resPos;

int adc14_(void);
void ADC14_IRQHandler(void);
void startSampling(void);




#endif /* COPY2_ADC14_H_ */

and here is the .c file that does the analog to digital conversion.

/*
 * -------------------------------------------
 *    MSP432 DriverLib - v4_00_00_11
 * -------------------------------------------
 *
 * --COPYRIGHT--,BSD,BSD
 * Copyright (c) 2017, 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--*/
 /* MSP432 ADC14 - Multiple Channel Sample without Repeat
 *
 * Description: In this code example, the feature of being able to scan multiple
 * ADC channels is demonstrated by the user a the DriverLib APIs.  Conversion
 * memory registers ADC_MEM0 - ADC_MEM3 are configured to read conversion
 * results from A6, A12, A10, A8 respectively. Conversion is enabled and then sampling is
 * toggled using a software toggle. Repeat mode is not enabled and sampling only
 * occurs once (and it is expected that the user pauses the debugger to observe
 * the results). Once the final sample has been taken, the interrupt for
 * ADC_MEM3 is triggered and the result is stored in the resultsBuffer buffer.
 *
 *                MSP432P401
 *             ------------------
 *         /|\|                  |
 *          | |                  |
 *          --|RST         P4.7  |<--- A6 (Analog Input, Measured, Real)
 *            |            P4.1  |<--- A12 (Analog Input, Measured, Imaginary)
 *            |            P4.3  |<--- A10 (Analog Input, Reference Real)
 *            |            P4.5  |<--- A8 (Analog Input, Reference Imaginary)
 *            |                  |
 *            |                  |
 *
 *            4.1, 4.3, 4.5, 4.7 are the eventual pins needed.
 *
 * Author: Timothy Logan
 * This was modified by Rob Frohne to do multiple ADC at 8 kHz sample rate.
 ******************************************************************************/
#include <copy2_adc14.h>
#define SAMPLE_LENGTH 128

uint16_t refRe[SAMPLE_LENGTH];
uint16_t refIm[SAMPLE_LENGTH];
uint16_t measRe[SAMPLE_LENGTH];
uint16_t measIm[SAMPLE_LENGTH];
extern volatile bool doneADC;
bool sendMeasurement = false;
int numberFrequenciestoMeasure, frequencyIndex;
float  refSum, measSum;
volatile bool doneADC = false;

void ADC14_IRQHandler(void);

int adc14_(void)
{

    // Register interrupt
    Hwi_Params params;
    Hwi_Params_init(&params);
    Hwi_create(INT_ADC14, ADC14_IRQHandler, &params, 0);
    Hwi_setPriority(INT_ADC14, 60);

    //Interrupt_enableSleepOnIsrExit();
    resPos = 0;

    /* Initializing ADC (MCLK/1/1) */
    ADC14_enableModule();
    ADC14_initModule(ADC_CLOCKSOURCE_MCLK, ADC_PREDIVIDER_1, ADC_DIVIDER_1,
                         0);

    // Configuring debugging pins as output for debugging...
    GPIO_setAsOutputPin(GPIO_PORT_P5, GPIO_PIN5);
    GPIO_setAsOutputPin(GPIO_PORT_P1, GPIO_PIN0);

    //Configuring GPIOs for Analog In
    GPIO_setAsPeripheralModuleFunctionInputPin(GPIO_PORT_P4,
        GPIO_PIN1 | GPIO_PIN3 | GPIO_PIN5 | GPIO_PIN7, GPIO_TERTIARY_MODULE_FUNCTION);

    // Configuring ADC Memory (ADC_MEM0 - ADC_MEM3 (A6, A12, A10, A8)  with no repeat)
    // with internal 2.5v reference
    ADC14_configureMultiSequenceMode(ADC_MEM0, ADC_MEM3, false); // No repeat mode.
    ADC14_configureConversionMemory(ADC_MEM0,
                                        ADC_VREFPOS_INTBUF_VREFNEG_VSS,
                                        ADC_INPUT_A6, ADC_NONDIFFERENTIAL_INPUTS);
    ADC14_configureConversionMemory(ADC_MEM1,
                                        ADC_VREFPOS_INTBUF_VREFNEG_VSS,
                                        ADC_INPUT_A12, ADC_NONDIFFERENTIAL_INPUTS);
    ADC14_configureConversionMemory(ADC_MEM2,
                                        ADC_VREFPOS_INTBUF_VREFNEG_VSS,
                                        ADC_INPUT_A10, ADC_NONDIFFERENTIAL_INPUTS);
    ADC14_configureConversionMemory(ADC_MEM3,
                                        ADC_VREFPOS_INTBUF_VREFNEG_VSS,
                                        ADC_INPUT_A8, ADC_NONDIFFERENTIAL_INPUTS);

    /* Configuring Timer_A*/
    Timer_A_configureUpMode(TIMER_A0_BASE, &upModeConfig);

    /* Configuring TIMER_A3 in CCR1 */
    Timer_A_initCompare(TIMER_A0_BASE, &compareConfig);

    /* Configuring the sample trigger to be sourced from TIMER_A3  and setting it
     * to automatic iteration after it is triggered*/
    ADC14_setSampleHoldTrigger(ADC_TRIGGER_SOURCE1, false);

    /* Setting up the sample timer to automatically step through the sequence
     * convert.
     */
    ADC14_enableSampleTimer(ADC_AUTOMATIC_ITERATION);

    /* Enabling the interrupt when a conversion on channel 3 is complete*/
    ADC14_enableInterrupt(ADC_INT3);
    //ADC14_enableConversion(); // Not needed because we enable it in .ino.

    /* Enabling Interrupts */
    Interrupt_enableInterrupt(INT_ADC14);
    Interrupt_enableMaster();

    /* Starting the Timer */
    Timer_A_startCounter(TIMER_A0_BASE, TIMER_A_UP_MODE);
    //Hwi_enable();

    return 1;
}


void ADC14_IRQHandler(void)
{
    uint64_t status;
    static int i = 0;
    status = ADC14_getEnabledInterruptStatus();
    ADC14_clearInterruptFlag(status);

    if(status & ADC_INT3)
    {
        ADC14_disableConversion();
        doneADC = false;
        ADC14_getMultiSequenceResult(resultsBuffer);
        measRe[i] = resultsBuffer[0];
        measIm[i] = resultsBuffer[1];
        refRe[i] = resultsBuffer[2];
        refIm[i] = resultsBuffer[3];
        GPIO_toggleOutputOnPin(GPIO_PORT_P5, GPIO_PIN5);
        if (i!=SAMPLE_LENGTH)
        {
            i++;
            ADC14_enableConversion();
        }
        else
        {
            i=0;
            doneADC = true;
            ADC14_enableConversion();
        }
    }
}

I like this solution, because it is easy to use most any Arduino library (that doesn't conflict with our use of the ADC14 and TimerA0). You also can trigger the ADC14 on TimerA1, TimerA2, or TimerA3. See the MSP432 datasheet for details on which CCR to use.

Number of Measurements to Process

The width of a Hanning averaging filter of N points at a sampling rate of Hz is Hz. For 8 KHz sampling rate, and 128 points this comes to about 63 Hz. The time to sample 500 points at this rate is eight seconds, neglecting serial port time. The ASCII for eight digits of frequency, magnitude and phase could be sent in about the same time at 115200 baud.

Serial Protocol

The Touchstone S1P looks interesting, however, it has no protocol for sending S21 or S12 by themselves, and to the analyzer, it makes no difference if it is S11 or S21. The amount of data to be sent is considerably diminished if I send binary data. Last time I did it that way, so it is already set up that way with qvna. The drawback is that it isn't easy to read the data as it goes by.

Serial Communication Testing with GNU Octave

For initial testing I am using octave with the instrument control package. In octave:

>> pkg install --forge instrument-contorl gets you the ability to send and receive data from the serial port.  This paper describes how it works.  I am using ASCII text to send the data for now.
Testing Serial Communications

To be able to see what octave is sending and receiving I'm using:

$ sudo socat -d -d pty,raw,echo=0 pty,raw,echo=0 

Then I get back something like this:

2017/05/10 08:49:50 socat[14265] N PTY is /dev/pts/3
2017/05/10 08:49:50 socat[14265] N PTY is /dev/pts/5
2017/05/10 08:49:50 socat[14265] N starting data transfer loop with FDs [5,5] and [7,7]

I don't want to use su powers with these virtual serial ports so I change the write permissions:

sudo chmod a+rw /dev/pts/3

and likewise for 5. Then I can connect to each side with minicom to test the virtual serial ports like this:

minicom -p /dev/pts/3

and likewise for 5. Then anything typed in 5's minicom shows up in 3's minicom. I will use this with octave connecting in place of a minicom and be able to interact by hand like my MSP432 program is supposed to. I find in minicom it is handy to turn on local echo, so I can see what I'm typing as well as what I'm receiving. You do that by CTRL-A Z E. It was also not always clear what keys send what with minicom, so I used the serial port sniffer program to see that LF was a CTRL-J (0x0A). This is the termination character I was sending from the MSP432. The serial port sniffer may also be handy snooping on the communications between octave and the MSP432. The way I used it to look at the pseudo tty was:

$ jpnevulator -a --tty /dev/pts/2 --read

After looking at jpnevulator a bit, I decided it was difficult to use compared to interceptty which I just compiled from source. This program creates a virtual terminal that you connect to with the octave script and will show all the data passing to the serial port and the direction it is going. You don't need to use all kinds of complicated switches to use it for this purpose, though there are switches if you need them. I just did this:

$ interceptty /dev/ttyACM0 /tmp/ttyDUMMY

Then I connected the octave program with this using:

s1 = serial("/tmp/ttyDUMMY")

Here is an octave program I used to get swept frequency measurements.

% VNA 2017 test script.
% Rob Frohne, May 2017.

clc; clear;

fMin = 1e6;
fMax = 1e6;
nFreq = 1;

Sum = zeros(nFreq,2);
% Load the package
pkg load instrument-control
% Check if serial support exists
if (exist("serial") != 3)
  disp("No Serial Support");
endif
% Instantiate the Serial Port
% Naturally, set the COM port # to match your device
% Use this crazy notation for any COM port number: 1 - 255
%s1 = serial("/dev/pts/2");
s1 = serial("/tmp/ttyDUMMY"); % $ interceptty /dev/ttyACM0 /tmp/ttyDUMMY
pause(1); % Wait a second as it takes some ports a while to wake up
% Set the port parameters
set(s1,'baudrate', 115200);
set(s1,'bytesize', 8);
set(s1,'parity', 'n');
set(s1,'stopbits', 1);
set(s1,'timeout', 255); % 12.3 Seconds as an example here
% Optional commands, these can be 'on' or 'off'
%set(s1, 'requesttosend', 'on');
 % Sets the RTS line
%set(s1, 'dataterminalready', 'on'); % Sets the DTR line
% Optional - Flush input and output buffers
srl_flush(s1);
string_to_send = strcat("Testing! ^SWEEP,",num2str(uint64(fMin)),","...
                  ,num2str(uint64(fMax)),",",num2str(uint64(nFreq)),"$\n")
srl_write(s1,string_to_send);
for i=1:nFreq
  Sum(i,:) = str2num(ReadToTermination(s1, 10))
  %String = ReadToTermination(s1,10)
endfor
% Finally, Close the port
fclose(s1);