Progress on distance measurer so far

This commit is contained in:
Jonathan Chan 2018-02-06 17:05:26 -08:00
parent 1d925b0e52
commit eb9ef28540
14 changed files with 2673 additions and 0 deletions

18
lab5/distance/Makefile Executable file
View File

@ -0,0 +1,18 @@
OBJECTS=main.o
DEVICE = msp430g2553
INSTALL_DIR=$(HOME)/ti/msp430_gcc
GCC_DIR = $(INSTALL_DIR)/bin
SUPPORT_FILE_DIRECTORY = $(INSTALL_DIR)/include
CC = $(GCC_DIR)/msp430-elf-gcc
GDB = $(GCC_DIR)/msp430-elf-gdb
CFLAGS = -I $(SUPPORT_FILE_DIRECTORY) -mmcu=$(DEVICE) -O2 -g
LFLAGS = -L $(SUPPORT_FILE_DIRECTORY) -T $(DEVICE).ld
all: ${OBJECTS}
$(CC) $(CFLAGS) $(LFLAGS) $? -o main.elf
debug: all
$(GDB) main.elf

293
lab5/distance/main.c Normal file
View File

@ -0,0 +1,293 @@
/*
* main.c
*
* MSP-EXP430G2-LaunchPad User Experience Application
*
* Copyright (C) 2011 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.
*
* Heavily modified: Nov, 2013 Carl Michal
* Even more so, February, 2014
* This version modified to use the Hardware UART on MSP430G2553
* see code at https://bennthomsen.wordpress.com/engineering-toolbox/ti-msp430-launchpad/msp430g2553-hardware-uart/
* jumpers for TX/RX on Launchpad board must be rotated 90 degrees
* for hardware UART used here!!
* This may not work on all revisions of the board?
*/
/******************************************************************************
* MSP-EXP430G2-LaunchPad User Experience Application
*
* 1. Device starts up in LPM3 + blinking LED to indicate device is alive
* + Upon first button press, device transitions to application mode
* 2. Application Mode
* + Continuously sample ADC Temp Sensor channel
*
* + Transmit temperature value via TimerA UART to PC
*
*
* Texas Instruments, Inc.
******************************************************************************/
#include "msp430.h"
#define LED1 BIT0
#define LED2 BIT6
#define TRIG BIT4
#define ECHO BIT5
#define BUTTON BIT3
#define TXD BIT2 // TXD on P1.2
#define RXD BIT1 // RXD on P1.1
#define PreAppMode 0
#define RunningMode 1
unsigned int TXByte;
volatile unsigned int Mode;
void InitializeButton(void);
void PreApplicationMode(void);
void main(void)
{
long tempMeasured;
WDTCTL = WDTPW + WDTHOLD; // Stop WDT
/* next three lines to use internal calibrated 1MHz clock: */
BCSCTL1 = CALBC1_1MHZ; // Set range
DCOCTL = CALDCO_1MHZ;
BCSCTL2 &= ~(DIVS_3); // SMCLK = DCO = 1MHz
InitializeButton();
// setup port for leds:
P1DIR |= LED1 + LED2;
P1OUT &= ~(LED1 + LED2);
P1DIR |= TXD;
P1OUT |= TXD;
Mode = PreAppMode;
PreApplicationMode(); // Blinks LEDs, waits for button press
/* Configure ADC Temp Sensor Channel */
ADC10CTL1 = INCH_10 + ADC10DIV_3; // Temp Sensor ADC10CLK/4
ADC10CTL0 = SREF_1 + ADC10SHT_3 + REFON + ADC10ON + ADC10IE;
__delay_cycles(1000); // Wait for ADC Ref to settle
__enable_interrupt(); // Enable interrupts.
/* Configure hardware UART */
P1SEL = BIT1 + BIT2 ; // P1.1 = RXD, P1.2=TXD
P1SEL2 = BIT1 + BIT2 ; // P1.1 = RXD, P1.2=TXD
UCA0CTL1 |= UCSSEL_2; // Use SMCLK
UCA0BR0 = 104; // Set baud rate to 9600 with 1MHz clock (Data Sheet 15.3.13)
UCA0BR1 = 0; // Set baud rate to 9600 with 1MHz clock
UCA0MCTL = UCBRS0; // Modulation UCBRSx = 1
UCA0CTL1 &= ~UCSWRST; // Initialize USCI state machine
/* if we were going to receive, we would also:
IE2 |= UCA0RXIE; // Enable USCI_A0 RX interrupt
*/
/* Main Application Loop */
while(1)
{
/*
ADC10CTL0 |= ENC + ADC10SC; // Sampling and conversion start
__bis_SR_register(CPUOFF + GIE); // LPM0 with interrupts enabled turns cpu off.
// an interrupt is triggered when the ADC result is ready.
// The interrupt handler restarts the cpu.
// store result
tempMeasured = ADC10MEM;
// convert to farenheit and send to host computer
TXByte = (unsigned char)( ((tempMeasured - 630) * 761) / 1024 );
while (! (IFG2 & UCA0TXIFG)); // wait for TX buffer to be ready for new data
UCA0TXBUF = TXByte;
P1OUT ^= LED1; // toggle the light every time we make a measurement.
// set up timer to wake us in a while:
TACCR0 = 2400; // period
TACTL = TASSEL_1 | MC_1; // TACLK = ACLK, Up mode.
TACCR1 = 2400; // interrupt at end
TACCTL1 = CCIE; // TACCTL0
// go to sleep, wait till timer expires to do another measurement.
__bis_SR_register(LPM3_bits + GIE); // LPM0 with interrupts enabled turns cpu off.
// could have just done this - but low power mode is nicer.
// __delay_cycles(500000);
*/
P1IE |= ECHO; // set echo input as interrupt
P1OUT |= TRIG; // start trigger signal
__delay_cycles(10); // we need a 10 us pulse but one clock cycle is 1 us
P1OUT &= ~TRIG; // end trigger signal
TACTL = TACLR;
TACTL = TASSEL_2 | ID_3 | MC_2; // set timer to count up
unsigned int start = TAR;
__bis_SR_register(LPM0_bits + GIE); // low-power mode 0 (SMCLK still on)
unsigned int stop = TAR;
TXByte = stop - start;
while (! (IFG2 & UCA0TXIFG)); // wait for TX buffer to be ready for new data
UCA0TXBUF = TXByte;
P1OUT ^= LED1;
__delay_cycles(10000); // wait 10 ms before measuring again
}
}
void PreApplicationMode(void)
{
P1DIR |= LED1 + LED2;
P1OUT |= LED1; // To enable the LED toggling effect
P1OUT &= ~LED2;
/* these next two lines configure the ACLK signal to come from
a secondary oscillator source, called VLO */
BCSCTL1 |= DIVA_1; // ACLK is half the speed of the source (VLO)
BCSCTL3 |= LFXT1S_2; // ACLK = VLO
/* here we're setting up a timer to fire an interrupt periodically.
When the timer 1 hits its limit, the interrupt will toggle the lights
We're using ACLK as the timer source, since it lets us go into LPM3
(where SMCLK and MCLK are turned off). */
TACCR0 = 1200; // period
TACTL = TASSEL_1 | MC_1; // TACLK = ACLK, Up mode.
TACCTL1 = CCIE + OUTMOD_3; // TACCTL1 Capture Compare
TACCR1 = 600; // duty cycle
__bis_SR_register(LPM3_bits + GIE); // LPM3 with interrupts enabled
// in LPM3, MCLCK and SMCLK are off, but ACLK is on.
}
// this gets used in pre-application mode only to toggle the lights:
#if defined(__TI_COMPILER_VERSION__)
#pragma vector=TIMER0_A1_VECTOR
__interrupt void ta1_isr (void)
#else
void __attribute__ ((interrupt(TIMER0_A1_VECTOR))) ta1_isr (void)
#endif
{
TACCTL1 &= ~CCIFG; // reset the interrupt flag
if (Mode == PreAppMode){
P1OUT ^= (LED1 + LED2); // toggle the two lights.
}
else{
TACCTL1 = 0; // no more interrupts.
__bic_SR_register_on_exit(LPM3_bits); // Restart the cpu
}
}
void InitializeButton(void) // Configure Push Button
{
P1DIR &= ~BUTTON;
P1OUT |= BUTTON;
P1REN |= BUTTON;
P1IES |= BUTTON;
P1IFG &= ~BUTTON;
P1IE |= BUTTON;
}
/* *************************************************************
* Port Interrupt for Button Press
* 1. During standby mode: to enter application mode
*
* *********************************************************** */
#if defined(__TI_COMPILER_VERSION__)
#pragma vector=PORT1_VECTOR
__interrupt void port1_isr(void)
#else
void __attribute__ ((interrupt(PORT1_VECTOR))) port1_isr (void)
#endif
{
/* this disables port1 interrupts for a little while so that
we don't try to respond to two consecutive button pushes right together.
The watchdog timer interrupt will re-enable port1 interrupts
This whole watchdog thing is completely unnecessary here, but its useful
to see how it is done.
*/
P1IFG = 0; // clear out interrupt flag
P1IE &= ~BUTTON; // Disable port 1 interrupts
WDTCTL = WDT_ADLY_250; // set up watchdog timer duration
IFG1 &= ~WDTIFG; // clear interrupt flag
IE1 |= WDTIE; // enable watchdog interrupts
TACCTL1 = 0; // turn off timer 1 interrupts
P1OUT &= ~(LED1+LED2); // turn off the leds
Mode = RunningMode;
__bic_SR_register_on_exit(LPM3_bits); // take us out of low power mode
}
// WDT Interrupt Service Routine used to de-bounce button press
#if defined(__TI_COMPILER_VERSION__)
#pragma vector=WDT_VECTOR
__interrupt void wdt_isr(void)
#else
void __attribute__ ((interrupt(WDT_VECTOR))) wdt_isr (void)
#endif
{
IE1 &= ~WDTIE; /* disable watchdog interrupt */
IFG1 &= ~WDTIFG; /* clear interrupt flag */
WDTCTL = WDTPW + WDTHOLD; /* put WDT back in hold state */
P1IE |= BUTTON; /* Debouncing complete - reenable port 1 interrupts*/
}
// ADC10 interrupt service routine
#if defined(__TI_COMPILER_VERSION__)
#pragma vector=ADC10_VECTOR
__interrupt void adc10_isr(void)
#else
void __attribute__ ((interrupt(ADC10_VECTOR))) adc10_isr (void)
#endif
{
__bic_SR_register_on_exit(CPUOFF); // Restart the cpu
}

BIN
lab5/distance/main.o Normal file

Binary file not shown.

View File

@ -0,0 +1,90 @@
#!/usr/bin/python2.7
import serial # for serial port
import numpy as np # for arrays, numerical processing
from time import sleep,time
import gtk #the gui toolkit we'll use:
# graph plotting library:
from matplotlib.figure import Figure
from matplotlib.backends.backend_gtkagg import FigureCanvasGTKAgg as FigureCanvas
#needs: python2, pyserial, numpy, matplotlib, pygtk
#0) flash the serial temperature measurement program into the msp430
#1) start this program
#2) press the button the Launchpad to enter 'applcation mode'
#3) warm the chip (eg with a light bulb or your fingers)
#4) when you've seen enough, press the reset button on the launchpad
#5) exit the program by pressing 'q' or clicking on the x
#define the serial port. Pick one:
port = "/dev/ttyACM0" #for Linux
#port = "COM5" #For Windows?
#port = "/dev/tty.uart-XXXX" #For Mac?
#function that gets called when a key is pressed:
def press(event):
print('press', event.key)
if event.key == 'q':
print ('got q!')
quit_app(None)
return True
def quit_app(event):
outFile.close()
ser.close()
quit()
#start our program proper:
#open the serial port
try:
ser = serial.Serial(port,2400,timeout = 0.050)
ser.baudrate=9600
# with timeout=0, read returns immediately, even if no data
except:
print ("Opening serial port",port,"failed")
print ("Edit program to point to the correct port.")
print ("Hit enter to exit")
raw_input()
quit()
#create a window to put the plot in
win = gtk.Window()
#connect the destroy signal (clicking the x in the corner)
win.connect("destroy", quit_app)
win.set_default_size(400,300)
yvals = np.zeros(50) #array to hold last 50 measurements
times=np.arange(0,50,1.0) # 50 from 0 to 49.
#create a plot:
fig = Figure()
ax = fig.add_subplot(111,xlabel='Time Step',ylabel='Temp (deg F)')
ax.set_ylim(0,255) # set limits of y axis.
canvas = FigureCanvas(fig) #put the plot onto a canvas
win.add(canvas) #put the canvas in the window
# define a callback for when a key is pressed
fig.canvas.mpl_connect('key_press_event',press)
#show the window
win.show_all()
win.set_title("ready to receive data");
line, = ax.plot(times,yvals)
#open a data file for the output
outFile = open("time_and_temp.txt","w")
start_time = time()
ser.flushInput()
while(1): #loop forever
data = ser.read(1) # look for a character from serial port, will wait up to timeout above.
if len(data) > 0: #was there a byte to read? should always be true.
yvals = np.roll(yvals,-1) # shift the values in the array
yvals[49] = ord(data) # take the value of the byte
outFile.write(str(time()-start_time)+" "+str(yvals[49])+"\n") #write to file
line.set_ydata(yvals) # draw the line
fig.canvas.draw() # update the canvas
win.set_title("Temp: "+str(yvals[49])+" deg F")
while gtk.events_pending(): #makes sure the GUI updates
gtk.main_iteration()
# sleep(.05) # don't eat the cpu. This delay limits the data rate to ~ 200 samples/s

View File

@ -0,0 +1,37 @@
#!/usr/bin/python2.7
import serial # for serial port
import numpy as np # for arrays, numerical processing
#needs: python2, pyserial, numpy,
#0) flash the serial temperature measurement program into the msp430
#1) start this program
#2) press the button the Launchpad to enter 'applcation mode'
#3) warm the chip (eg with a light bulb or your fingers)
#4) when you've seen enough, press the reset button on the launchpad
#5) exit the program by pressing 'q' or clicking on the x
#define the serial port. Pick one:
port = "/dev/ttyACM0" #for Linux
#port = "COM5" #For Windows?
#port = "/dev/tty.uart-XXXX" #For Mac?
#start our program proper:
#open the serial port
try:
ser = serial.Serial(port,2400,timeout = 0.050)
ser.baudrate=9600
# with timeout=0, read returns immediately, even if no data
except:
print ("Opening serial port",port,"failed")
print ("Edit program to point to the correct port.")
print ("Hit enter to exit")
raw_input()
quit()
ser.flushInput()
while(1): #loop forever
data = ser.read(1) # look for a character from serial port - will wait for up to 50ms (specified above in timeout)
if len(data) > 0: #was there a byte to read?
print ord(data)

View File

@ -0,0 +1,100 @@
/* Example code demonstrating the use of the hardware UART on the MSP430G2553 to receive
* and transmit data back to a host computer over the USB connection on the MSP430
* launchpad.
* Note: After programming it is necessary to stop debugging and reset the uC before
* connecting the terminal program to transmit and receive characters.
* This demo will turn on the Red LED if an R is sent and turn it off if a r is sent.
* Similarly G and g will turn on and off the green LED
* It also transmits the received character back to the terminal.
FROM: https://bennthomsen.wordpress.com/engineering-toolbox/ti-msp430-launchpad/msp430g2553-hardware-uart/
*/
#include "msp430.h"
void UARTSendArray(char *TxArray, char ArrayLength);
static char data;
void main(void)
{
WDTCTL = WDTPW + WDTHOLD; // Stop WDT
P1DIR |= BIT0 + BIT6; // Set the LEDs on P1.0, P1.6 as outputs
P1OUT = BIT0; // Set P1.0
BCSCTL1 = CALBC1_1MHZ; // Set DCO to 1MHz
DCOCTL = CALDCO_1MHZ; // Set DCO to 1MHz
/* Configure hardware UART */
P1SEL = BIT1 + BIT2 ; // P1.1 = RXD, P1.2=TXD
P1SEL2 = BIT1 + BIT2 ; // P1.1 = RXD, P1.2=TXD
UCA0CTL1 |= UCSSEL_2; // Use SMCLK
UCA0BR0 = 104; // Set baud rate to 9600 with 1MHz clock (Data Sheet 15.3.13)
UCA0BR1 = 0; // Set baud rate to 9600 with 1MHz clock
UCA0MCTL = UCBRS0; // Modulation UCBRSx = 1
UCA0CTL1 &= ~UCSWRST; // Initialize USCI state machine
IE2 |= UCA0RXIE; // Enable USCI_A0 RX interrupt
__bis_SR_register(LPM0_bits + GIE); // Enter LPM0, interrupts enabled
}
// Echo back RXed character, confirm TX buffer is ready first
#if defined(__TI_COMPILER_VERSION__)
#pragma vector=USCIAB0RX_VECTOR
__interrupt void USCI0RX_ISR(void)
#else
void __attribute__ ((interrupt(USCIAB0RX_VECTOR))) uci0rx_isr(void)
#endif
{
data = UCA0RXBUF;
UARTSendArray("Received command: ", 18);
UARTSendArray(&data, 1);
UARTSendArray("\n\r", 2);
switch(data){
case 'R':
{
P1OUT |= BIT0;
}
break;
case 'r':
{
P1OUT &= ~BIT0;
}
break;
case 'G':
{
P1OUT |= BIT6;
}
break;
case 'g':
{
P1OUT &= ~BIT6;
}
break;
default:
{
UARTSendArray("Unknown Command: ", 17);
UARTSendArray(&data, 1);
UARTSendArray("\n\r", 2);
}
break;
}
}
void UARTSendArray(char *TxArray, char ArrayLength){
// Send number of bytes Specified in ArrayLength in the array at using the hardware UART 0
// Example usage: UARTSendArray("Hello", 5);
// int data[2]={1023, 235};
// UARTSendArray(data, 4); // Note because the UART transmits bytes it is necessary to send two bytes for each integer hence the data length is twice the array length
while(ArrayLength--){ // Loop until StringLength == 0 and post decrement
while(!(IFG2 & UCA0TXIFG)); // Wait for TX buffer to be ready for new data
UCA0TXBUF = *TxArray; //Write the character at the location specified py the pointer
TxArray++; //Increment the TxString pointer to point to the next character
}
}

File diff suppressed because it is too large Load Diff

18
lab5/temperature_demo5/Makefile Executable file
View File

@ -0,0 +1,18 @@
OBJECTS=main.o
DEVICE = msp430g2553
INSTALL_DIR=$(HOME)/ti/msp430_gcc
GCC_DIR = $(INSTALL_DIR)/bin
SUPPORT_FILE_DIRECTORY = $(INSTALL_DIR)/include
CC = $(GCC_DIR)/msp430-elf-gcc
GDB = $(GCC_DIR)/msp430-elf-gdb
CFLAGS = -I $(SUPPORT_FILE_DIRECTORY) -mmcu=$(DEVICE) -O2 -g
LFLAGS = -L $(SUPPORT_FILE_DIRECTORY) -T $(DEVICE).ld
all: ${OBJECTS}
$(CC) $(CFLAGS) $(LFLAGS) $? -o main.elf
debug: all
$(GDB) main.elf

View File

@ -0,0 +1,274 @@
/*
* main.c
*
* MSP-EXP430G2-LaunchPad User Experience Application
*
* Copyright (C) 2011 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.
*
* Heavily modified: Nov, 2013 Carl Michal
* Even more so, February, 2014
* This version modified to use the Hardware UART on MSP430G2553
* see code at https://bennthomsen.wordpress.com/engineering-toolbox/ti-msp430-launchpad/msp430g2553-hardware-uart/
* jumpers for TX/RX on Launchpad board must be rotated 90 degrees
* for hardware UART used here!!
* This may not work on all revisions of the board?
*/
/******************************************************************************
* MSP-EXP430G2-LaunchPad User Experience Application
*
* 1. Device starts up in LPM3 + blinking LED to indicate device is alive
* + Upon first button press, device transitions to application mode
* 2. Application Mode
* + Continuously sample ADC Temp Sensor channel
*
* + Transmit temperature value via TimerA UART to PC
*
*
* Texas Instruments, Inc.
******************************************************************************/
#include "msp430.h"
#define LED1 BIT0
#define LED2 BIT6
#define BUTTON BIT3
#define TXD BIT2 // TXD on P1.2
#define RXD BIT1 // RXD on P1.1
#define PreAppMode 0
#define RunningMode 1
unsigned int TXByte;
volatile unsigned int Mode;
void InitializeButton(void);
void PreApplicationMode(void);
void main(void)
{
long tempMeasured;
WDTCTL = WDTPW + WDTHOLD; // Stop WDT
/* next three lines to use internal calibrated 1MHz clock: */
BCSCTL1 = CALBC1_1MHZ; // Set range
DCOCTL = CALDCO_1MHZ;
BCSCTL2 &= ~(DIVS_3); // SMCLK = DCO = 1MHz
InitializeButton();
// setup port for leds:
P1DIR |= LED1 + LED2;
P1OUT &= ~(LED1 + LED2);
P1DIR |= TXD;
P1OUT |= TXD;
Mode = PreAppMode;
PreApplicationMode(); // Blinks LEDs, waits for button press
/* Configure ADC Temp Sensor Channel */
ADC10CTL1 = INCH_10 + ADC10DIV_3; // Temp Sensor ADC10CLK/4
ADC10CTL0 = SREF_1 + ADC10SHT_3 + REFON + ADC10ON + ADC10IE;
__delay_cycles(1000); // Wait for ADC Ref to settle
__enable_interrupt(); // Enable interrupts.
/* Configure hardware UART */
P1SEL = BIT1 + BIT2 ; // P1.1 = RXD, P1.2=TXD
P1SEL2 = BIT1 + BIT2 ; // P1.1 = RXD, P1.2=TXD
UCA0CTL1 |= UCSSEL_2; // Use SMCLK
UCA0BR0 = 104; // Set baud rate to 9600 with 1MHz clock (Data Sheet 15.3.13)
UCA0BR1 = 0; // Set baud rate to 9600 with 1MHz clock
UCA0MCTL = UCBRS0; // Modulation UCBRSx = 1
UCA0CTL1 &= ~UCSWRST; // Initialize USCI state machine
/* if we were going to receive, we would also:
IE2 |= UCA0RXIE; // Enable USCI_A0 RX interrupt
*/
/* Main Application Loop */
while(1)
{
ADC10CTL0 |= ENC + ADC10SC; // Sampling and conversion start
__bis_SR_register(CPUOFF + GIE); // LPM0 with interrupts enabled turns cpu off.
// an interrupt is triggered when the ADC result is ready.
// The interrupt handler restarts the cpu.
// store result
tempMeasured = ADC10MEM;
// convert to farenheit and send to host computer
TXByte = (unsigned char)( ((tempMeasured - 630) * 761) / 1024 );
while (! (IFG2 & UCA0TXIFG)); // wait for TX buffer to be ready for new data
UCA0TXBUF = TXByte;
P1OUT ^= LED1; // toggle the light every time we make a measurement.
// set up timer to wake us in a while:
TACCR0 = 2400; // period
TACTL = TASSEL_1 | MC_1; // TACLK = ACLK, Up mode.
TACCR1 = 2400; // interrupt at end
TACCTL1 = CCIE; // TACCTL0
// go to sleep, wait till timer expires to do another measurement.
__bis_SR_register(LPM3_bits + GIE); // LPM0 with interrupts enabled turns cpu off.
// could have just done this - but low power mode is nicer.
// __delay_cycles(500000);
}
}
void PreApplicationMode(void)
{
P1DIR |= LED1 + LED2;
P1OUT |= LED1; // To enable the LED toggling effect
P1OUT &= ~LED2;
/* these next two lines configure the ACLK signal to come from
a secondary oscillator source, called VLO */
BCSCTL1 |= DIVA_1; // ACLK is half the speed of the source (VLO)
BCSCTL3 |= LFXT1S_2; // ACLK = VLO
/* here we're setting up a timer to fire an interrupt periodically.
When the timer 1 hits its limit, the interrupt will toggle the lights
We're using ACLK as the timer source, since it lets us go into LPM3
(where SMCLK and MCLK are turned off). */
TACCR0 = 1200; // period
TACTL = TASSEL_1 | MC_1; // TACLK = ACLK, Up mode.
TACCTL1 = CCIE + OUTMOD_3; // TACCTL1 Capture Compare
TACCR1 = 600; // duty cycle
__bis_SR_register(LPM3_bits + GIE); // LPM3 with interrupts enabled
// in LPM3, MCLCK and SMCLK are off, but ACLK is on.
}
// this gets used in pre-application mode only to toggle the lights:
#if defined(__TI_COMPILER_VERSION__)
#pragma vector=TIMER0_A1_VECTOR
__interrupt void ta1_isr (void)
#else
void __attribute__ ((interrupt(TIMER0_A1_VECTOR))) ta1_isr (void)
#endif
{
TACCTL1 &= ~CCIFG; // reset the interrupt flag
if (Mode == PreAppMode){
P1OUT ^= (LED1 + LED2); // toggle the two lights.
}
else{
TACCTL1 = 0; // no more interrupts.
__bic_SR_register_on_exit(LPM3_bits); // Restart the cpu
}
}
void InitializeButton(void) // Configure Push Button
{
P1DIR &= ~BUTTON;
P1OUT |= BUTTON;
P1REN |= BUTTON;
P1IES |= BUTTON;
P1IFG &= ~BUTTON;
P1IE |= BUTTON;
}
/* *************************************************************
* Port Interrupt for Button Press
* 1. During standby mode: to enter application mode
*
* *********************************************************** */
#if defined(__TI_COMPILER_VERSION__)
#pragma vector=PORT1_VECTOR
__interrupt void port1_isr(void)
#else
void __attribute__ ((interrupt(PORT1_VECTOR))) port1_isr (void)
#endif
{
/* this disables port1 interrupts for a little while so that
we don't try to respond to two consecutive button pushes right together.
The watchdog timer interrupt will re-enable port1 interrupts
This whole watchdog thing is completely unnecessary here, but its useful
to see how it is done.
*/
P1IFG = 0; // clear out interrupt flag
P1IE &= ~BUTTON; // Disable port 1 interrupts
WDTCTL = WDT_ADLY_250; // set up watchdog timer duration
IFG1 &= ~WDTIFG; // clear interrupt flag
IE1 |= WDTIE; // enable watchdog interrupts
TACCTL1 = 0; // turn off timer 1 interrupts
P1OUT &= ~(LED1+LED2); // turn off the leds
Mode = RunningMode;
__bic_SR_register_on_exit(LPM3_bits); // take us out of low power mode
}
// WDT Interrupt Service Routine used to de-bounce button press
#if defined(__TI_COMPILER_VERSION__)
#pragma vector=WDT_VECTOR
__interrupt void wdt_isr(void)
#else
void __attribute__ ((interrupt(WDT_VECTOR))) wdt_isr (void)
#endif
{
IE1 &= ~WDTIE; /* disable watchdog interrupt */
IFG1 &= ~WDTIFG; /* clear interrupt flag */
WDTCTL = WDTPW + WDTHOLD; /* put WDT back in hold state */
P1IE |= BUTTON; /* Debouncing complete - reenable port 1 interrupts*/
}
// ADC10 interrupt service routine
#if defined(__TI_COMPILER_VERSION__)
#pragma vector=ADC10_VECTOR
__interrupt void adc10_isr(void)
#else
void __attribute__ ((interrupt(ADC10_VECTOR))) adc10_isr (void)
#endif
{
__bic_SR_register_on_exit(CPUOFF); // Restart the cpu
}

Binary file not shown.

View File

@ -0,0 +1,90 @@
#!/usr/bin/python2.7
import serial # for serial port
import numpy as np # for arrays, numerical processing
from time import sleep,time
import gtk #the gui toolkit we'll use:
# graph plotting library:
from matplotlib.figure import Figure
from matplotlib.backends.backend_gtkagg import FigureCanvasGTKAgg as FigureCanvas
#needs: python2, pyserial, numpy, matplotlib, pygtk
#0) flash the serial temperature measurement program into the msp430
#1) start this program
#2) press the button the Launchpad to enter 'applcation mode'
#3) warm the chip (eg with a light bulb or your fingers)
#4) when you've seen enough, press the reset button on the launchpad
#5) exit the program by pressing 'q' or clicking on the x
#define the serial port. Pick one:
port = "/dev/ttyACM0" #for Linux
#port = "COM5" #For Windows?
#port = "/dev/tty.uart-XXXX" #For Mac?
#function that gets called when a key is pressed:
def press(event):
print('press', event.key)
if event.key == 'q':
print ('got q!')
quit_app(None)
return True
def quit_app(event):
outFile.close()
ser.close()
quit()
#start our program proper:
#open the serial port
try:
ser = serial.Serial(port,2400,timeout = 0.050)
ser.baudrate=9600
# with timeout=0, read returns immediately, even if no data
except:
print ("Opening serial port",port,"failed")
print ("Edit program to point to the correct port.")
print ("Hit enter to exit")
raw_input()
quit()
#create a window to put the plot in
win = gtk.Window()
#connect the destroy signal (clicking the x in the corner)
win.connect("destroy", quit_app)
win.set_default_size(400,300)
yvals = np.zeros(50) #array to hold last 50 measurements
times=np.arange(0,50,1.0) # 50 from 0 to 49.
#create a plot:
fig = Figure()
ax = fig.add_subplot(111,xlabel='Time Step',ylabel='Temp (deg F)')
ax.set_ylim(50,100) # set limits of y axis.
canvas = FigureCanvas(fig) #put the plot onto a canvas
win.add(canvas) #put the canvas in the window
# define a callback for when a key is pressed
fig.canvas.mpl_connect('key_press_event',press)
#show the window
win.show_all()
win.set_title("ready to receive data");
line, = ax.plot(times,yvals)
#open a data file for the output
outFile = open("time_and_temp.txt","w")
start_time = time()
ser.flushInput()
while(1): #loop forever
data = ser.read(1) # look for a character from serial port, will wait up to timeout above.
if len(data) > 0: #was there a byte to read? should always be true.
yvals = np.roll(yvals,-1) # shift the values in the array
yvals[49] = ord(data) # take the value of the byte
outFile.write(str(time()-start_time)+" "+str(yvals[49])+"\n") #write to file
line.set_ydata(yvals) # draw the line
fig.canvas.draw() # update the canvas
win.set_title("Temp: "+str(yvals[49])+" deg F")
while gtk.events_pending(): #makes sure the GUI updates
gtk.main_iteration()
# sleep(.05) # don't eat the cpu. This delay limits the data rate to ~ 200 samples/s

View File

@ -0,0 +1,37 @@
#!/usr/bin/python2.7
import serial # for serial port
import numpy as np # for arrays, numerical processing
#needs: python2, pyserial, numpy,
#0) flash the serial temperature measurement program into the msp430
#1) start this program
#2) press the button the Launchpad to enter 'applcation mode'
#3) warm the chip (eg with a light bulb or your fingers)
#4) when you've seen enough, press the reset button on the launchpad
#5) exit the program by pressing 'q' or clicking on the x
#define the serial port. Pick one:
port = "/dev/ttyACM0" #for Linux
#port = "COM5" #For Windows?
#port = "/dev/tty.uart-XXXX" #For Mac?
#start our program proper:
#open the serial port
try:
ser = serial.Serial(port,2400,timeout = 0.050)
ser.baudrate=9600
# with timeout=0, read returns immediately, even if no data
except:
print ("Opening serial port",port,"failed")
print ("Edit program to point to the correct port.")
print ("Hit enter to exit")
raw_input()
quit()
ser.flushInput()
while(1): #loop forever
data = ser.read(1) # look for a character from serial port - will wait for up to 50ms (specified above in timeout)
if len(data) > 0: #was there a byte to read?
print ord(data)

View File

@ -0,0 +1,100 @@
/* Example code demonstrating the use of the hardware UART on the MSP430G2553 to receive
* and transmit data back to a host computer over the USB connection on the MSP430
* launchpad.
* Note: After programming it is necessary to stop debugging and reset the uC before
* connecting the terminal program to transmit and receive characters.
* This demo will turn on the Red LED if an R is sent and turn it off if a r is sent.
* Similarly G and g will turn on and off the green LED
* It also transmits the received character back to the terminal.
FROM: https://bennthomsen.wordpress.com/engineering-toolbox/ti-msp430-launchpad/msp430g2553-hardware-uart/
*/
#include "msp430.h"
void UARTSendArray(char *TxArray, char ArrayLength);
static char data;
void main(void)
{
WDTCTL = WDTPW + WDTHOLD; // Stop WDT
P1DIR |= BIT0 + BIT6; // Set the LEDs on P1.0, P1.6 as outputs
P1OUT = BIT0; // Set P1.0
BCSCTL1 = CALBC1_1MHZ; // Set DCO to 1MHz
DCOCTL = CALDCO_1MHZ; // Set DCO to 1MHz
/* Configure hardware UART */
P1SEL = BIT1 + BIT2 ; // P1.1 = RXD, P1.2=TXD
P1SEL2 = BIT1 + BIT2 ; // P1.1 = RXD, P1.2=TXD
UCA0CTL1 |= UCSSEL_2; // Use SMCLK
UCA0BR0 = 104; // Set baud rate to 9600 with 1MHz clock (Data Sheet 15.3.13)
UCA0BR1 = 0; // Set baud rate to 9600 with 1MHz clock
UCA0MCTL = UCBRS0; // Modulation UCBRSx = 1
UCA0CTL1 &= ~UCSWRST; // Initialize USCI state machine
IE2 |= UCA0RXIE; // Enable USCI_A0 RX interrupt
__bis_SR_register(LPM0_bits + GIE); // Enter LPM0, interrupts enabled
}
// Echo back RXed character, confirm TX buffer is ready first
#if defined(__TI_COMPILER_VERSION__)
#pragma vector=USCIAB0RX_VECTOR
__interrupt void USCI0RX_ISR(void)
#else
void __attribute__ ((interrupt(USCIAB0RX_VECTOR))) uci0rx_isr(void)
#endif
{
data = UCA0RXBUF;
UARTSendArray("Received command: ", 18);
UARTSendArray(&data, 1);
UARTSendArray("\n\r", 2);
switch(data){
case 'R':
{
P1OUT |= BIT0;
}
break;
case 'r':
{
P1OUT &= ~BIT0;
}
break;
case 'G':
{
P1OUT |= BIT6;
}
break;
case 'g':
{
P1OUT &= ~BIT6;
}
break;
default:
{
UARTSendArray("Unknown Command: ", 17);
UARTSendArray(&data, 1);
UARTSendArray("\n\r", 2);
}
break;
}
}
void UARTSendArray(char *TxArray, char ArrayLength){
// Send number of bytes Specified in ArrayLength in the array at using the hardware UART 0
// Example usage: UARTSendArray("Hello", 5);
// int data[2]={1023, 235};
// UARTSendArray(data, 4); // Note because the UART transmits bytes it is necessary to send two bytes for each integer hence the data length is twice the array length
while(ArrayLength--){ // Loop until StringLength == 0 and post decrement
while(!(IFG2 & UCA0TXIFG)); // Wait for TX buffer to be ready for new data
UCA0TXBUF = *TxArray; //Write the character at the location specified py the pointer
TxArray++; //Increment the TxString pointer to point to the next character
}
}

View File

@ -0,0 +1,171 @@
1.77205991745 87.0
10.0263590813 87.0
10.6817378998 87.0
10.8080530167 87.0
11.1541500092 0.0
26.2722930908 87.0
26.5502300262 0.0
29.9946060181 87.0
30.1150250435 88.0
30.4667789936 0.0
36.3493950367 88.0
37.739372015 88.0
38.0597360134 0.0
41.1656959057 88.0
41.53591609 0.0
44.5073740482 88.0
45.2329130173 88.0
45.8213620186 88.0
45.9182698727 88.0
46.292304039 0.0
47.9162359238 88.0
48.2350459099 0.0
51.0878880024 88.0
51.2012159824 88.0
51.5593209267 0.0
53.9454829693 88.0
54.9813899994 88.0
57.1134779453 88.0
58.8585898876 88.0
58.9516170025 88.0
59.3279669285 0.0
60.2412030697 88.0
60.5913639069 0.0
61.3735120296 88.0
61.7318439484 0.0
62.5942320824 88.0
62.9517040253 0.0
64.2808358669 87.0
64.6298289299 0.0
66.676609993 88.0
67.4041640759 88.0
68.1725950241 88.0
75.216796875 88.0
75.9059848785 87.0
76.0256788731 88.0
76.3773438931 0.0
77.4960620403 88.0
77.7985479832 0.0
78.4848248959 88.0
78.8059849739 0.0
80.1690919399 88.0
81.702039957 88.0
81.8249678612 88.0
82.172950983 0.0
83.0561380386 88.0
85.0543339252 87.0
85.5549719334 88.0
85.6780650616 88.0
86.023182869 0.0
197.485710859 87.0
197.642025948 87.0
197.957994938 0.0
200.328988075 87.0
200.63052392 0.0
204.43433094 87.0
204.552805901 87.0
204.90365696 0.0
207.021686077 87.0
207.602361917 87.0
208.664263964 87.0
208.78538394 87.0
209.13550806 0.0
211.361093044 87.0
211.638974905 0.0
212.498952866 87.0
212.807632923 0.0
214.108011007 87.0
214.200826883 87.0
214.576770067 0.0
215.203356028 87.0
215.518167973 0.0
216.203274965 87.0
216.510565042 0.0
217.959785938 87.0
224.170849085 87.0
224.260709047 87.0
224.64217186 0.0
226.045338869 87.0
226.257998943 87.0
226.429722071 87.0
226.606987953 87.0
226.695899963 87.0
226.870508909 87.0
227.101451874 87.0
227.270215988 87.0
227.371995926 87.0
227.548193932 88.0
227.707774878 87.0
227.975720882 87.0
228.151233912 87.0
228.235579014 87.0
228.395956993 88.0
228.579133034 87.0
228.723888874 87.0
228.967443943 87.0
229.065361023 87.0
229.235224962 87.0
229.483686924 87.0
229.595293999 87.0
229.788245916 87.0
230.038101912 87.0
230.147944927 87.0
230.397887945 87.0
230.502285957 87.0
230.685940027 87.0
230.857460976 88.0
231.020709038 87.0
231.197432041 88.0
231.35481596 88.0
231.520189047 87.0
231.913542986 88.0
232.158943892 88.0
232.296463013 87.0
232.426964045 88.0
232.595606089 87.0
232.761909008 87.0
233.015954018 87.0
233.096441031 88.0
233.280994892 87.0
233.448677063 87.0
233.614598989 87.0
233.794538975 87.0
233.968185902 87.0
234.153837919 88.0
234.332063913 88.0
234.631798029 87.0
234.690438032 88.0
234.878174067 88.0
235.168398857 87.0
235.324084044 88.0
235.509407043 88.0
235.688710928 87.0
235.866517067 88.0
235.956760883 87.0
236.227550983 87.0
238.925761938 87.0
239.866142035 88.0
239.985929966 88.0
240.333611012 0.0
241.162170887 88.0
241.48149991 0.0
242.113638878 88.0
242.241039038 87.0
242.525716066 88.0
242.70381093 87.0
242.798628092 88.0
242.989850998 88.0
243.258746862 88.0
243.33511591 88.0
243.531604052 88.0
243.689504862 88.0
243.870397091 88.0
244.036158085 88.0
244.219717026 88.0
244.484622955 88.0
244.575479984 88.0
244.77366209 88.0
245.063790083 88.0
245.142785072 88.0
245.309396029 88.0
245.707669973 0.0