]> code.bitgloo.com Git - clyne/msp430-temp-lcd.git/commitdiff
Made things work
authortcsullivan <tullivan99@gmail.com>
Tue, 30 Apr 2019 16:29:06 +0000 (12:29 -0400)
committertcsullivan <tullivan99@gmail.com>
Tue, 30 Apr 2019 16:29:06 +0000 (12:29 -0400)
12 files changed:
Makefile [new file with mode: 0644]
board.c [new file with mode: 0755]
board.h [new file with mode: 0755]
delay.c [new file with mode: 0755]
delay.h [new file with mode: 0755]
i2c.c [new file with mode: 0755]
i2c.h [new file with mode: 0755]
lcd.c [new file with mode: 0755]
lcd.h [new file with mode: 0755]
main.c [new file with mode: 0755]
temp.c [new file with mode: 0755]
temp.h [new file with mode: 0755]

diff --git a/Makefile b/Makefile
new file mode 100644 (file)
index 0000000..ea846a1
--- /dev/null
+++ b/Makefile
@@ -0,0 +1,27 @@
+CC = msp430-gcc
+CFLAGS = -mmcu=msp430g2553 -std=gnu99 -Os -ggdb
+
+CSRC = board.c \
+       delay.c \
+       i2c.c \
+       lcd.c \
+       temp.c \
+       main.c
+COBJ = $(patsubst %.c, %.o, $(CSRC))
+
+ELF = main.elf
+
+all: $(ELF)
+
+clean:
+       @echo "  CLEAN"
+       @rm -f $(ELF) $(COBJ)
+
+$(ELF): $(COBJ)
+       @echo "  CC    " $@
+       @$(CC) $(CFLAGS) $(COBJ) -o $(ELF)
+
+%.o: %.c
+       @echo "  CC    " $<
+       @$(CC) $(CFLAGS) -c $< -o $@
+
diff --git a/board.c b/board.c
new file mode 100755 (executable)
index 0000000..769d1db
--- /dev/null
+++ b/board.c
@@ -0,0 +1,55 @@
+/**
+ * @file board.c
+ * Provides board configuration and initialization.
+ *
+ * Copyright (C) 2019  Clyne Sullivan
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program.  If not, see <https://www.gnu.org/licenses/>.
+ */
+
+#include "board.h"
+
+static void boardInitWatchdog(void);
+static void boardInitPins(void);
+
+void boardInit(void)
+{
+       // Slow down needed for LCD
+       BCSCTL1 = CALBC1_1MHZ;
+       DCOCTL = CALDCO_1MHZ; 
+
+       boardInitWatchdog();
+       boardInitPins();
+}
+
+void boardInitWatchdog(void)
+{
+       WDTCTL = WDTHOLD | WDTPW;
+}
+
+void boardInitPins(void)
+{
+       // All pins are output
+       P1DIR = PORT1_PINS;
+       P2DIR = PORT2_PINS;
+
+       // All pins should start at a low state
+       P1OUT = 0;
+       P2OUT = 0;
+
+       // Set I2C pins to the proper mode
+       P1SEL |= TEMP_SDA | TEMP_SCL;
+       P1SEL2 |= TEMP_SDA | TEMP_SCL;
+}
+
diff --git a/board.h b/board.h
new file mode 100755 (executable)
index 0000000..7c796a8
--- /dev/null
+++ b/board.h
@@ -0,0 +1,48 @@
+/**
+ * @file board.h
+ * Provides board configuration and initialization.
+ *
+ * Copyright (C) 2019  Clyne Sullivan
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program.  If not, see <https://www.gnu.org/licenses/>.
+ */
+
+#ifndef BOARD_H_
+#define BOARD_H_
+
+#include <msp430.h>
+#include <stdint.h>
+
+// Port 1 pins
+#define LCD_DATL (0x0F)
+#define LCD_RW   (1 << 4)
+#define LCD_RS   (1 << 5)
+#define TEMP_SCL (1 << 6)
+#define TEMP_SDA (1 << 7)
+
+#define PORT1_PINS (LCD_DATL | LCD_RW | LCD_RS | TEMP_SCL | TEMP_SDA)
+
+// Port 2 pins
+#define LCD_DATH (0x0F)
+#define LCD_E   (1 << 4)
+
+#define PORT2_PINS (LCD_DATH | LCD_E)
+
+/**
+ * Initializes pins and core functionality.
+ */
+void boardInit(void);
+
+#endif // BOARD_H_
+
diff --git a/delay.c b/delay.c
new file mode 100755 (executable)
index 0000000..05960e6
--- /dev/null
+++ b/delay.c
@@ -0,0 +1,42 @@
+/**
+ * @file delay.c
+ * Delay support using a timer.
+ *
+ * Copyright (C) 2019  Clyne Sullivan
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program.  If not, see <https://www.gnu.org/licenses/>.
+ */
+
+#include "board.h"
+
+volatile unsigned int delayTicks = 0;
+
+void delayInit(void)
+{
+       TACCTL0 |= CCIE;
+       TACCR0 = 128;
+       TACTL |= TASSEL_2 | MC_1 | ID_3;
+}
+
+void delay(unsigned int ms)
+{
+    unsigned int target = delayTicks + ms;
+    while (delayTicks < target);
+}
+
+__attribute__((__interrupt__(TIMER0_A0_VECTOR)))
+static void delayInterruptHandler(void)
+{
+    delayTicks++;
+}
diff --git a/delay.h b/delay.h
new file mode 100755 (executable)
index 0000000..f806a76
--- /dev/null
+++ b/delay.h
@@ -0,0 +1,29 @@
+/**
+ * @file delay.h
+ * Delay support using a timer.
+ *
+ * Copyright (C) 2019  Clyne Sullivan
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program.  If not, see <https://www.gnu.org/licenses/>.
+ */
+
+#ifndef DELAY_H_
+#define DELAY_H_
+
+void delayInit(void);
+
+void delay(unsigned int ms);
+
+#endif // DELAY_H_
+
diff --git a/i2c.c b/i2c.c
new file mode 100755 (executable)
index 0000000..a10141c
--- /dev/null
+++ b/i2c.c
@@ -0,0 +1,136 @@
+/*
+ * i2c.h
+ *
+ *  Created on: 28 de abr de 2017
+ *      Author: helio.capella
+ *
+ *      Based on msp430g2xx3_uscib0_i2c_12.c by D. Dang
+ *
+ *  Modified by tcsullivan:
+ *      04/29: Modified pin macros to work with project
+ */
+
+#include <msp430.h>
+#include "i2c.h"
+#include "board.h"
+
+#define I2CSEL   P1SEL
+#define I2CSEL2  P1SEL2
+#define I2CSCL   (TEMP_SCL)
+#define I2CSDA   (TEMP_SDA)
+
+void I2C_init(uint8_t slaveAddress){
+    // Port Configuration
+    I2CSEL |= I2CSDA + I2CSCL;                     // Assign I2C pins to USCI_B0
+    I2CSEL2|= I2CSDA + I2CSCL;                     // Assign I2C pins to USCI_B0
+
+//    isRx = 0;                                    // State variable - possibly useless
+
+    //USCI Configuration
+    UCB0CTL1 |= UCSWRST;                           // Enable SW reset
+    UCB0CTL0 = UCMST + UCMODE_3 + UCSYNC;          // I2C Master, synchronous mode
+    UCB0CTL1 = UCSSEL_2 + UCSWRST;                 // Use SMCLK, keep SW reset
+
+    //Set USCI Clock Speed
+    UCB0BR0 = 12;                                  // fSCL = SMCLK/12 = ~100kHz
+    UCB0BR1 = 0;
+
+    //Set Slave Address and Resume operation
+    UCB0I2CSA = slaveAddress;                      // Slave Address passed as parameter
+    UCB0CTL1 &= ~UCSWRST;                          // Clear SW reset, resume operation
+}
+
+
+void I2C_write(uint8_t ByteCtr, uint8_t *TxData) {
+    __disable_interrupt();
+//    isRx = 0;
+    //Interrupt management
+    IE2 &= ~UCB0RXIE;                              // Disable RX interrupt
+//    while (UCB0CTL1 & UCTXSTP);                  // Ensure stop condition got sent
+    IE2 |= UCB0TXIE;                               // Enable TX interrupt
+
+    //Pointer to where data is stored to be sent
+    PTxData = (uint8_t *) TxData;                  // TX array start address
+    TxByteCtr = ByteCtr;                           // Load TX byte counter
+
+    //Send start condition
+    //    while (UCB0CTL1 & UCTXSTP);              // Ensure stop condition got sent
+    UCB0CTL1 |= UCTR + UCTXSTT;                    // I2C TX, start condition
+
+    __bis_SR_register(CPUOFF + GIE);               // Enter LPM0 w/ interrupts
+    while (UCB0CTL1 & UCTXSTP);
+}
+
+void I2C_read(uint8_t ByteCtr, volatile uint8_t *RxData) {
+    __disable_interrupt();
+//    isRx = 1;
+
+    //Interrupt management
+    IE2 &= ~UCB0TXIE;                              // Disable TX interrupt
+    UCB0CTL1 = UCSSEL_2 + UCSWRST;                 // Use SMCLK, keep SW reset
+    UCB0CTL1 &= ~UCSWRST;                          // Clear SW reset, resume operation
+    IE2 |= UCB0RXIE;                               // Enable RX interrupt
+
+    //Pointer to where data will be stored
+    PRxData = (uint8_t *) RxData;                  // Start of RX buffer
+    RxByteCtr = ByteCtr;                           // Load RX byte counter
+
+    //while (UCB0CTL1 & UCTXSTP);                  // Ensure stop condition got sent
+
+    //If only 1 byte will be read send stop signal as soon as it starts transmission
+    if(RxByteCtr == 1){
+        UCB0CTL1 |= UCTXSTT;                       // I2C start condition
+        while (UCB0CTL1 & UCTXSTT);                // Start condition sent?
+        UCB0CTL1 |= UCTXSTP;                       // I2C stop condition
+        __enable_interrupt();
+    } else {
+        UCB0CTL1 |= UCTXSTT;                       // I2C start condition
+    }
+
+    __bis_SR_register(CPUOFF + GIE);               // Enter LPM0 w/ interrupts
+    while (UCB0CTL1 & UCTXSTP);                    // Ensure stop condition got sent
+}
+
+#if defined(__TI_COMPILER_VERSION__) || defined(__IAR_SYSTEMS_ICC__)
+#pragma vector = USCIAB0TX_VECTOR
+__interrupt void USCIAB0TX_ISR(void)
+#elif defined(__GNUC__)
+void __attribute__ ((interrupt(USCIAB0TX_VECTOR))) USCIAB0TX_ISR (void)
+#else
+#error Compiler not supported!
+#endif
+{
+  if(IFG2 & UCB0RXIFG){                              // Receive In
+  if (RxByteCtr == 1)
+  {
+     *PRxData = UCB0RXBUF;                           // Move final RX data to PRxData
+     __bic_SR_register_on_exit(CPUOFF);              // Exit LPM0
+  }
+  else
+  {
+      *PRxData++ = UCB0RXBUF;                        // Move RX data to address PRxData
+      if (RxByteCtr == 2)                            // Check whether byte is second to last to be read to send stop condition
+      UCB0CTL1 |= UCTXSTP;
+      __no_operation();
+  }
+  RxByteCtr--;                                       // Decrement RX byte counter
+  }
+
+  else{                                              // Master Transmit
+      if (TxByteCtr)                                 // Check TX byte counter
+  {
+    UCB0TXBUF = *PTxData;                            // Load TX buffer
+    PTxData++;
+    TxByteCtr--;                                     // Decrement TX byte counter
+  }
+  else
+  {
+    UCB0CTL1 |= UCTXSTP;                             // I2C stop condition
+    IFG2 &= ~UCB0TXIFG;                              // Clear USCI_B0 TX int flag
+    __bic_SR_register_on_exit(CPUOFF);               // Exit LPM0
+  }
+ }
+}
+
+
+
diff --git a/i2c.h b/i2c.h
new file mode 100755 (executable)
index 0000000..987d109
--- /dev/null
+++ b/i2c.h
@@ -0,0 +1,26 @@
+/*
+ * i2c.h
+ *
+ *  Created on: 28 de abr de 2017
+ *      Author: helio.capella
+ */
+
+#ifndef I2C_H_
+#define I2C_H_
+
+#include <stdint.h>
+
+uint8_t *PTxData;                     // Pointer to TX data
+uint8_t *PRxData;                     // Pointer to RX data
+
+uint8_t TxByteCtr;
+uint8_t RxByteCtr;
+
+//uint8_t isRx;
+
+void I2C_init(uint8_t slaveAddress);
+void I2C_write(uint8_t ByteCtr, uint8_t *TxData);
+void I2C_read(uint8_t ByteCtr, volatile uint8_t *RxData);
+
+#endif /* I2C_H_ */
+
diff --git a/lcd.c b/lcd.c
new file mode 100755 (executable)
index 0000000..3405782
--- /dev/null
+++ b/lcd.c
@@ -0,0 +1,61 @@
+#include "board.h"\r
+#include "delay.h"\r
+#include "lcd.h"\r
+\r
+static void lcdPulseE(void);\r
+static void lcdSetDAT(uint8_t value);\r
+static void lcdSendCommand(uint8_t command);\r
+static void lcdSendData(uint8_t data);\r
+\r
+void lcdInit(void)\r
+{\r
+    // Give time for LCD to prepare itself\r
+    delay(100);\r
+    lcdSendCommand(0x38);\r
+    lcdSendCommand(0x10);\r
+    lcdSendCommand(0x0D);\r
+    delay(5);\r
+    lcdClear();\r
+}\r
+\r
+void lcdClear(void)\r
+{\r
+    lcdSendCommand(0x01);\r
+    delay(2);\r
+}\r
+\r
+void lcdPuts(const char *s)\r
+{\r
+       lcdSendCommand(0x06);\r
+       while (*s != '\0')\r
+               lcdSendData(*s++);\r
+}\r
+\r
+void lcdPulseE(void)\r
+{\r
+    P2OUT |= LCD_E;\r
+    delay(2);\r
+    P2OUT &= ~(LCD_E);\r
+}\r
+\r
+void lcdSetDAT(uint8_t value)\r
+{\r
+    P2OUT &= ~(LCD_DATH);\r
+    P2OUT |= (value >> 4) & LCD_DATH;\r
+    P1OUT &= ~(LCD_DATL);\r
+    P1OUT |= value & LCD_DATL;\r
+}\r
+\r
+void lcdSendCommand(uint8_t command)\r
+{\r
+    P1OUT &= ~(LCD_RS);\r
+    lcdSetDAT(command);\r
+    lcdPulseE();\r
+}\r
+\r
+void lcdSendData(uint8_t data)\r
+{\r
+    P1OUT |= LCD_RS;\r
+    lcdSetDAT(data);\r
+    lcdPulseE();\r
+}\r
diff --git a/lcd.h b/lcd.h
new file mode 100755 (executable)
index 0000000..134652d
--- /dev/null
+++ b/lcd.h
@@ -0,0 +1,6 @@
+\r
+void lcdInit(void);\r
+\r
+void lcdClear(void);\r
+void lcdPuts(const char *s);\r
+\r
diff --git a/main.c b/main.c
new file mode 100755 (executable)
index 0000000..3cab384
--- /dev/null
+++ b/main.c
@@ -0,0 +1,55 @@
+/**
+ * @file main.c
+ * Main program entry point.
+ *
+ * Copyright (C) 2019  Clyne Sullivan
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program.  If not, see <https://www.gnu.org/licenses/>.
+ */
+
+#include "board.h"
+#include "delay.h"
+#include "lcd.h"
+#include "temp.h"
+
+#include <stdio.h>
+
+int main(void)
+{
+       // Prepare processor and IO
+       boardInit();
+
+       delayInit();
+       _NOP();
+       __enable_interrupt();
+
+       lcdInit();
+
+       if (tempInit() != 0) {
+           lcdPuts("Sensor broken.");
+           while (1);
+       }
+
+       char buf[8];
+       while (1) {
+           lcdClear();
+           int16_t temp = tempGetDieTemperature();
+           sprintf(buf, "%04d", temp);
+           lcdPuts(buf);
+           delay(1000);
+       }
+
+       return 0;
+}
+
diff --git a/temp.c b/temp.c
new file mode 100755 (executable)
index 0000000..e094d6f
--- /dev/null
+++ b/temp.c
@@ -0,0 +1,92 @@
+/**
+ * @file temp.c
+ * Provides support for the TMP006 temperature sensor.
+ *
+ * Copyright (C) 2019  Clyne Sullivan
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program.  If not, see <https://www.gnu.org/licenses/>.
+ */
+
+#include "board.h"
+#include "i2c.h"
+
+// TMP006 I2C address
+#define TEMP_ADDR (0x40)
+
+// TMP006 registers
+#define TMP006_CONFIG (0x02)
+#define TMP006_VOBJ   (0x00)
+#define TMP006_TAMB   (0x01)
+#define TMP006_MANID  (0xFE)
+#define TMP006_DEVID  (0xFF)
+
+// TMP006 CONFIG register parameters
+#define TMP006_CFG_RESET    (0x8000)
+#define TMP006_CFG_MODEON   (0x7000)
+#define TMP006_CFG_1SAMPLE  (0x0000)
+#define TMP006_CFG_2SAMPLE  (0x0200)
+#define TMP006_CFG_4SAMPLE  (0x0400)
+#define TMP006_CFG_8SAMPLE  (0x0600)
+#define TMP006_CFG_16SAMPLE (0x0800)
+#define TMP006_CFG_DRDYEN   (0x0100)
+#define TMP006_CFG_DRDY     (0x0080)
+
+static void tempI2CWrite(uint8_t reg, uint16_t value);
+static uint16_t tempI2CRead(uint8_t reg);
+
+int tempInit(void)
+{
+       // Prepare I2C
+       I2C_init(TEMP_ADDR);
+
+       // Initialize the TMP006 sensor
+       tempI2CWrite(TMP006_CONFIG, TMP006_CFG_MODEON | TMP006_CFG_DRDYEN |
+               TMP006_CFG_16SAMPLE);
+
+       // Check that the device is in fact the TMP006
+       uint16_t manid = tempI2CRead(TMP006_MANID);
+       uint16_t devid = tempI2CRead(TMP006_DEVID);
+       if (manid != 0x5449 || devid != 0x67)
+               return 1;
+
+       return 0;
+}
+
+int16_t tempGetDieTemperature(void)
+{
+    int16_t raw = tempI2CRead(TMP006_TAMB);
+    return (raw >> 2) / 32;
+}
+
+void tempI2CWrite(uint8_t reg, uint16_t value)
+{
+       uint8_t data[3] = {
+               reg,
+               value >> 8,
+               value & 0xFF
+       };
+       I2C_write(3, data);
+}
+
+uint16_t tempI2CRead(uint8_t reg)
+{
+       uint8_t data[2] = {
+               reg,
+               0
+       };
+       I2C_write(1, data);
+       I2C_read(2, data);
+       return (data[0] << 8) | data[1];
+}
+
diff --git a/temp.h b/temp.h
new file mode 100755 (executable)
index 0000000..aec66c9
--- /dev/null
+++ b/temp.h
@@ -0,0 +1,33 @@
+/**
+ * @file temp.h
+ * Provides support for the TMP006 temperature sensor.
+ *
+ * Copyright (C) 2019  Clyne Sullivan
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program.  If not, see <https://www.gnu.org/licenses/>.
+ */
+
+#ifndef TEMP_H_
+#define TEMP_H_
+
+/**
+ * Attempts to initialize the TMP006 temperature sensor.
+ * @return Zero on success, non-zero on failure
+ */
+int tempInit(void);
+
+int16_t tempGetDieTemperature(void);
+
+#endif // TEMP_H_
+