Skip to content

Instantly share code, notes, and snippets.

@ossicode
Created January 4, 2013 10:46
Show Gist options
  • Save ossicode/4451594 to your computer and use it in GitHub Desktop.
Save ossicode/4451594 to your computer and use it in GitHub Desktop.
i2c test
/*
* aclkuart.c
*
* Created on: 2012. 12. 19.
* Author: OSSI
*/
#include "aclkuart.h"
static volatile uint8_t uart_rx_flag = 0;
static volatile uint8_t rx_byte = '\0';
// Low-Frequency Baud Rate Mode
// read chapter 15.3.10 of msp430x2xxx user's guide for baud rate generation
void uart_setup_9600(void)
{
P3SEL = 0x30; // P3.4,5 = USCI_A0 TXD/RXD, No need to set IO direction
UCA0CTL1 |= UCSSEL_1; // CLK = ACLK
UCA0BR0 = 0x03; // 3 = INT(3.41), 32.768kHz/9600 = 3.41
UCA0BR1 = 0x00; //
UCA0MCTL = UCBRS1 + UCBRS0; // Modulation UCBRSx = 3 = round(0.41 * 8)
UCA0CTL1 &= ~UCSWRST; // **Initialize USCI state machine**
}
void uart_setup_4800(void)
{
P3SEL = 0x30; // P3.4,5 = USCI_A0 TXD/RXD, No need to set IO direction
UCA0CTL1 |= UCSSEL_1; // CLK = ACLK
UCA0BR0 = 0x06; // 6 = INT(6.83), 32.768kHz/4800 = 6.83
UCA0BR1 = 0x00; //
UCA0MCTL = UCBRS2 + UCBRS1 + UCBRS0; // Modulation UCBRSx = 7 = round(0.83 * 8)
UCA0CTL1 &= ~UCSWRST; // **Initialize USCI state machine**
}
void uart_init(void)
{
IE2 |= UCA0RXIE; // default: Enable USCI_A0 RX interrupt
IE2 &= ~UCA0TXIE; // default: Disable USCI_A0 TX interrupt
}
void i2c_set_rxFlag(void)
{
}
void i2c_clear_rxFlag(void)
{
}
uint8_t i2c_rx_ready(void)
{
return 0;
}
void uart_set_rxFlag(void)
{
uart_rx_flag = 1;
}
void uart_clear_rxFlag(void)
{
uart_rx_flag = 0;
}
uint8_t uart_rx_ready(void)
{
if(uart_rx_flag)
{
return 1;
}
else
{
return 0;
}
}
uint8_t uart_get_byte(void)
{
// return only you have available data from uart, NOT i2c
return rx_byte;
}
/**
* Sends a single byte out through UART
**/
void uart_send_byte(unsigned char byte)
{
// we're not going to change this to avoid infinite loop as we only use printf() for debugging purpose.
while (!(IFG2&UCA0TXIFG)); // USCI_A0 TX buffer ready?
UCA0TXBUF = byte; // TX -> RXed character
}
void puts(char *s) {
char c;
// Loops through each character in string 's'
while (c = *s++) {
uart_send_byte(c);
}
}
/**
* puts() is used by printf() to display or send a character. This function
* determines where printf prints to. For this case it sends a character
* out over UART.
**/
void putc(unsigned b) {
uart_send_byte(b);
}
//// USCI A0/B0 Transmit ISR
//#pragma vector=USCIAB0TX_VECTOR
//__interrupt void USCI0TX_ISR(void)
//{
// IE2 &= ~UCA0TXIE; // Disable USCI_A0 TX interrupt
//}
// USCI A0/B0 Receive ISR
//#pragma vector=USCIAB0RX_VECTOR
//__interrupt void USCI0RX_ISR(void)
//{
// // TODO: I2C and UART handle at the same time
// rx_byte = UCA0RXBUF; // Get the received character
//
// // gps (uart)
// uart_set_rxFlag();
// __bic_SR_register_on_exit(LPM3_bits);
//
//
//}
/*
* aclkuart.h
*
* Created on: 2012. 12. 19.
* Author: OSSI
*/
#ifndef ACLKUART_H_
#define ACLKUART_H_
#include "ossibeacon.h"
void uart_setup_4800(void);
void uart_setup_9600(void);
void uart_init(void);
void uart_set_rxFlag(void);
void uart_clear_rxFlag(void);
uint8_t uart_rx_ready(void);
void i2c_set_rxFlag(void);
void i2c_clear_rxFlag(void);
uint8_t i2c_rx_ready(void);
uint8_t uart_get_byte(void);
void putc(unsigned);
void puts(char *);
#endif /* ACLKUART_H_ */
/*
* adc.c
*
* Created on: 2012. 12. 27.
* Author: OSSI
*/
#include "adc10.h"
// USE ADC module something like this
// main()
// {
// adc10_portSetup()
// while(1)
// {
// adc10_init()
// adc10_enable()
// adc10_enableInterrupt()
// adc10_setVolReference()
// adc10_startConversion()
// Low Power Mode
// }
// }
//
// ADC_ISR
// {
// clear ENC
// adc10_disable()
// adc10_disableInterrupt()
// exit Low Power Mode
// }
void adc10_portSetup(uint8_t ports)
{
ASSERT(ports <= 0xFF);
// reset ports
ADC10AE0 = ports; // set input for pin P2.0 , P2.1, no need to set directions
}
// we initialize adc10 with MSC bit = 1 as we are going to repeated single channel mode and don't want to intervene during the conversion
// TODO: check default values and make sure you understand everything
void adc10_init(uint16_t sampleHoldSignalSourceSelect,
uint8_t clockSourceSelect,
uint8_t clockSourceDivider,
uint16_t clockCycleHoldCount)
{
//Make sure the ENC bit is cleared before initializing the ADC10
ASSERT(!(ADC10CTL0 & ENC));
ASSERT(sampleHoldSignalSourceSelect <= ADC10_SAMPLEHOLDSOURCE_3);
ASSERT(clockSourceSelect <= ADC10_CLOCKSOURCE_SMCLK);
ASSERT(clockSourceDivider <= ADC10_CLOCKDIVIDER_8);
ASSERT(clockCycleHoldCount <= ADC10_CYCLEHOLD_64_CYCLES);
//Turn OFF ADC10 Module & Clear Interrupt Registers
ADC10CTL0 &= ~(ADC10ON + ENC + ADC10SC + ADC10IE + ADC10IFG); // ADC10ON, sampling rate = ACLK * 16
//Reset and Set ADC10 Control 0
ADC10CTL0 = clockCycleHoldCount + ADC10_MULTIPLESAMPLESENABLE;
//Reset and Set ADC10 Control 1
ADC10CTL1 = sampleHoldSignalSourceSelect + clockSourceSelect + clockSourceDivider; // ADC clock = ACLK, default: Single channel single conversion
}
// we limit adc10_setVolReference() function to 2 options:
// 1. Vr+: VCC, Vr-: VSS / SREFx: 000
// 2. Vr+: Vref+ , Vr-: VSS / SREFx: 001
// for Vref+ reference voltage setting, we use:
// ADC10SR = 0
// REFOUT = 0
// REFBIRST = 0
// REF2_5V = 1 (2.5V internal Reference Voltage)
// REFON = 1
void adc10_setVolReference(uint16_t refVoltageSourceSelect)
{
ASSERT(refVoltageSourceSelect <= ADC10_REF_VREF_VSS);
// clear ENC to set registers
ADC10CTL0 &= ~ENC;
// reset voltage reference settings
// clear SREFx bits
ADC10CTL0 &= 0x1FFF;
// clear rest of the reference settings
ADC10CTL0 &= ~(ADC10SR + REFOUT + REFBURST + REF2_5V + REFON);
if(refVoltageSourceSelect == ADC10_REF_VCC_VSS)
{
ADC10CTL0 |= ADC10_REF_VCC_VSS;
}
else
{
ADC10CTL0 |= ADC10_REF_VREF_VSS + REF2_5V + REFON;
}
}
// we only use DTC options for ADC
// TODO:for now, only ADC10_REPEATED_SINGLECHANNEL / ADC10_REPEATED_SEQOFCHANNELS modes are working!!!
// So declare buffer and use the buffer address and the size as the parameter of adc10_startConversion()
// TODO: check the function for single-channel / single conversion mode and sequences of channel mode.
void adc10_startConversion(uint16_t inputSourceSelect, uint8_t conversionSequenceModeSelect, uint16_t blockStartAddress, uint8_t buf_size)
{
ASSERT(inputSourceSelect <= ADC10_INPUT_VMID);
ASSERT(conversionSequenceModeSelect <= ADC10_REPEATED_SEQOFCHANNELS);
//TODO:how can we check blockStartAddress is valid or not. need to check the address is even number.
ASSERT(buf_size <= 0x80); // we're going to limit maximum buffer size to 128
// clear ENC to set registers
ADC10CTL0 &= ~ENC;
// reset input channel and conversion sequence mode
ADC10CTL1 &= 0x0FF9;
// set input channel and conversion sequence mode
ADC10CTL1 |= inputSourceSelect + conversionSequenceModeSelect;
//TODO: we are not using polling but we clear ENC bit inside ADC ISR. check whether this is universal to all modes
// while (ADC10CTL1 & ADC10BUSY);
// reset DTC by writing 0 to ADC10DTC1 register
ADC10DTC1 = 0;
// set ADC10DTC1 size
ADC10DTC1 = buf_size;
// reset the ADC10SA address to start DTC conversion again
ADC10SA = blockStartAddress;
// set to start conversion
ADC10CTL0 |= ADC10SC + ENC;
}
// how to stop conversion? stop conversion has to take care of all 4 modes. but now this is only valid for 2 repeated mode with MSC bit =1
void adc10_stopConversion(void)
{
//TODO: we are not using polling but we clear ENC bit inside ADC ISR. check whether this is universal to all modes
// while (ADC10CTL1 & ADC10BUSY);
// clear ENC to stop the conversion
ADC10CTL0 &= ~ENC;
}
void adc10_enable(void)
{
ADC10CTL0 |= ADC10ON;
}
void adc10_disable(void)
{
// turn off ADC core and Reference to save power consumption
// ADC10CTL0 &= ~(ADC10SR + REFOUT + REFBURST + REF2_5V + REFON);
// ADC10CTL0 &= ~ADC10ON;
// turn off all for low power operation
ADC10CTL0 =0;
}
void adc10_enableInterrupt(void)
{
ADC10CTL0 |= ADC10IE;
}
void adc10_disableInterrupt(void)
{
ADC10CTL0 &= ~ADC10IE;
}
//#pragma vector=ADC10_VECTOR
//__interrupt void ADC10_ISR(void)
//{
//
//
// __bic_SR_register_on_exit(LPM3_bits); // Clear LPM3_bits from 0(SR)
//}
/*
* adc10.h
*
* Created on: 2012. 12. 27.
* Author: OSSI
*/
#ifndef ADC10_H_
#define ADC10_H_
#include "ossibeacon.h"
//*****************************************************************************
//
//The following are values that can be passed to adc10_setup()
//
//
//*****************************************************************************
#define ADC10_PIN_2_0 (BIT0)
#define ADC10_PIN_2_1 (BIT1)
#define ADC10_PIN_2_2 (BIT2)
#define ADC10_PIN_2_3 (BIT3)
#define ADC10_PIN_2_4 (BIT4)
#define ADC10_PIN_3_0 (BIT5)
#define ADC10_PIN_3_6 (BIT6)
#define ADC10_PIN_3_7 (BIT7)
//*****************************************************************************
//
//The following are values that can be passed to ADC10_init() in the
//sampleTimerSourceSelect parameter.
//
//*****************************************************************************
#define ADC10_SAMPLEHOLDSOURCE_SC (SHS_0)
#define ADC10_SAMPLEHOLDSOURCE_1 (SHS_1)
#define ADC10_SAMPLEHOLDSOURCE_2 (SHS_2)
#define ADC10_SAMPLEHOLDSOURCE_3 (SHS_3)
//*****************************************************************************
//
//The following are values that can be passed to ADC10_init() in the
//clockSourceSelect parameter.
//
//*****************************************************************************
#define ADC10_CLOCKSOURCE_ADC10OSC (ADC10SSEL_0)
#define ADC10_CLOCKSOURCE_ACLK (ADC10SSEL_1)
#define ADC10_CLOCKSOURCE_MCLK (ADC10SSEL_2)
#define ADC10_CLOCKSOURCE_SMCLK (ADC10SSEL_3)
//*****************************************************************************
//
//The following are values that can be passed to ADC10_setupSamplingTimer() in
//the clockCycleHoldCount parameter.
//
//*****************************************************************************
#define ADC10_CYCLEHOLD_4_CYCLES (ADC10SHT_0)
#define ADC10_CYCLEHOLD_8_CYCLES (ADC10SHT_1)
#define ADC10_CYCLEHOLD_16_CYCLES (ADC10SHT_2)
#define ADC10_CYCLEHOLD_64_CYCLES (ADC10SHT_3)
//*****************************************************************************
//
//The following are values that can be passed to ADC10_memoryConfigure() in the
//inputSourceSelect parameter.
//
//*****************************************************************************
#define ADC10_INPUT_A0 (INCH_0)
#define ADC10_INPUT_A1 (INCH_1)
#define ADC10_INPUT_A2 (INCH_2)
#define ADC10_INPUT_A3 (INCH_3)
#define ADC10_INPUT_A4 (INCH_4)
#define ADC10_INPUT_A5 (INCH_5)
#define ADC10_INPUT_A6 (INCH_6)
#define ADC10_INPUT_A7 (INCH_7)
#define ADC10_INPUT_VREF_POS (INCH_8) //TODO: what is this?
#define ADC10_INPUT_VREF_NEG (INCH_9) //TODO: what is this?
#define ADC10_INPUT_TEMPSENSOR (INCH_10)
#define ADC10_INPUT_VMID (INCH_11)
//#define ADC10_INPUT_VMID (INCH_12)
//#define ADC10_INPUT_VMID (INCH_13)
//#define ADC10_INPUT_VMID (INCH_14)
//#define ADC10_INPUT_VMID (INCH_15)
//*****************************************************************************
//
//The following are values that can be passed to ADC10_init() in the
//clockSourceDivider parameter.
//Note: Bit 8-9 determines if the pre-divider is 1, 4, or 64
//Bits 5-7 determine the the post-divider 1-8 (0x00 - 0xE0)
//
//*****************************************************************************
#define ADC10_CLOCKDIVIDER_1 (ADC10DIV_0)
#define ADC10_CLOCKDIVIDER_2 (ADC10DIV_1)
#define ADC10_CLOCKDIVIDER_3 (ADC10DIV_2)
#define ADC10_CLOCKDIVIDER_4 (ADC10DIV_3)
#define ADC10_CLOCKDIVIDER_5 (ADC10DIV_4)
#define ADC10_CLOCKDIVIDER_6 (ADC10DIV_5)
#define ADC10_CLOCKDIVIDER_7 (ADC10DIV_6)
#define ADC10_CLOCKDIVIDER_8 (ADC10DIV_7)
//*****************************************************************************
//
//The following are values that can be passed to adc10_setVolReference()
//
//
//*****************************************************************************
#define ADC10_REF_VCC_VSS (SREF_0)
#define ADC10_REF_VREF_VSS (SREF_1)
//*****************************************************************************
//
//The following are values that can be passed to ADC10_startConversion() in the
//conversionSequenceModeSelect parameter.
//
//*****************************************************************************
#define ADC10_SINGLECHANNEL (CONSEQ_0)
#define ADC10_SEQOFCHANNELS (CONSEQ_1)
#define ADC10_REPEATED_SINGLECHANNEL (CONSEQ_2)
#define ADC10_REPEATED_SEQOFCHANNELS (CONSEQ_3)
//*****************************************************************************
//
//The following are values that can be passed to ADC10_setupSamplingTimer() in
//the multipleSamplesEnabled parameter.
//
//*****************************************************************************
#define ADC10_MULTIPLESAMPLESDISABLE ( !(MSC) )
#define ADC10_MULTIPLESAMPLESENABLE (MSC)
void adc10_portSetup(uint8_t ports);
void adc10_init(uint16_t sampleHoldSignalSourceSelect, uint8_t clockSourceSelect, uint8_t clockSourceDivider, uint16_t clockCycleHoldCount);
void adc10_enable(void);
void adc10_disable(void);
void adc10_setVolReference(uint16_t refVoltageSourceSelect);
void adc10_startConversion(uint16_t inputSourceSelect, uint8_t conversionSequenceModeSelect, uint16_t blockStartAddress, uint8_t buf_size);
void adc10_stopConversion(void);
void adc10_enableInterrupt(void);
void adc10_disableInterrupt(void);
#endif /* ADC10_H_ */
/* --COPYRIGHT--,BSD
* Copyright (c) 2012, 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--*/
//*****************************************************************************
//
//debug.h - Macros for assisting debug of the driver library.
//
//
//This is part of revision 0001 of the MSP430 Peripheral Driver Library.
//
//*****************************************************************************
#ifndef __DEBUG_H__
#define __DEBUG_H__
//*****************************************************************************
//
//Prototype for the function that is called when an invalid argument is passed
//to an API. This is only used when doing a DEBUG build.
//
//*****************************************************************************
extern void __error__ (char *pcFilename, unsigned long ulLine);
//*****************************************************************************
//
//The ASSERT macro, which does the actual assertion checking. Typically, this
//will be for procedure arguments.
//
//*****************************************************************************
#ifdef DEBUG
#define ASSERT(expr) { \
if (!(expr)) \
{ \
__error__(__FILE__, __LINE__); \
} \
}
#else
#define ASSERT(expr)
#endif
#endif //__DEBUG_H__
/*
* i2c.c
*
* Created on: 2012. 12. 30.
* Author: OSSI
*/
// we implement I2C as below:
//
// 7 bit addressing mode
// NO Multi-Master
#include "i2c.h"
// Master
// max buffer size
#define I2C_RX_BUFFER_SIZE 16
#define I2C_TX_BUFFER_SIZE 16
static uint16_t i2cRXIndex;
static uint16_t i2cTXIndex;
static uint8_t *rxData;
static uint8_t *txData;
// Slave
static volatile uint16_t slaveRXIndex;
static volatile uint16_t slaveTXIndex;
static volatile uint8_t *slaveRXData;
static volatile uint8_t *slaveTXData;
static volatile uint16_t defaultSlaveRXIndex;
static volatile uint16_t defaultSlaveTXIndex;
static volatile uint8_t *defaultSlaveRXData;
static volatile
uint8_t *defaultSlaveTXData;
static uint8_t i2cTxFlag;
static uint8_t i2cRxFlag;
void i2c_setTxFlag(void)
{
i2cTxFlag = 1;
}
void i2c_clearTxFlag(void)
{
i2cTxFlag = 0;
}
uint8_t i2c_getTxFlag(void)
{
return i2cTxFlag;
}
void i2c_setRxFlag(void)
{
i2cRxFlag = 1;
}
void i2c_clearRxFlag(void)
{
i2cRxFlag = 0;
}
uint8_t i2c_getRxFlag(void)
{
return i2cRxFlag;
}
void i2c_portSetup(void)
{
// For MSP430F2132, P3.1 = SDA, P3.2 = SCL
P3SEL |= 0x06;
}
// call this only when you need need master
void i2c_masterInit(uint8_t selctClockSource, uint16_t preScalerValue ,uint8_t modeSelect)
{
ASSERT((selctClockSource == I2C_CLOCKSOURCE_ACLK)||(selctClockSource == I2C_CLOCKSOURCE_SMCLK));
ASSERT((preScalerValue>=4) && (preScalerValue<=0xFFFF));
ASSERT((modeSelect == I2C_TRANSMIT_MODE)||(modeSelect == I2C_RECEIVE_MODE));
// reset I2C
UCB0CTL1 = UCSWRST;
// reset and set UCB0CTL0 for I2C mode
// UCA10 = 0 owe address 7 bit
// UCSLA10 = 0 slave address 7bit
// UCMM = 0 no multi-master
UCB0CTL0 = UCMST + UCMODE_3 + UCSYNC;
// reset clock source while UCSWRST = 1
UCB0CTL1 = selctClockSource + modeSelect + UCSWRST;
// fSCL = selctClockSource / preScalerValue
// for single master mode, minimum preScalerValue = 4
UCB0BR0 = preScalerValue & 0xFF;
UCB0BR1 = (preScalerValue >> 8) & 0xFF;
UCB0CTL1 &= ~UCSWRST;
}
void i2c_setSlaveAddress(uint8_t slaveAddress)
{
// slaveAddress is right justified. bit 6 is MSB for 7 bit address
// TODO:how to check whether we have valid 7 bit slaveAddress?
UCB0I2CSA = slaveAddress;
}
void i2c_enableRXInterrupt(void)
{
IE2 |= UCB0RXIE;
}
void i2c_disableRXInterrupt(void)
{
IE2 &= ~UCB0RXIE;
}
void i2c_enableTXInterrupt(void)
{
IE2 |= UCB0TXIE;
}
void i2c_disableTXInterrupt(void)
{
IE2 &= ~UCB0TXIE;
}
void i2c_masterReceive(uint8_t byteCount, uint8_t *data)
{
ASSERT((byteCount >=1)&&(byteCount<=I2C_RX_BUFFER_SIZE));
rxData = data;
if (byteCount == 1)
{
i2cRXIndex = byteCount ;
__disable_interrupt();
UCB0CTL1 |= UCTXSTT; // I2C start condition
while (UCB0CTL1 & UCTXSTT); // Start condition sent?
UCB0CTL1 |= UCTXSTP; // I2C stop condition
__enable_interrupt();
}
else if (byteCount > 1)
{
i2cRXIndex = byteCount ;
UCB0CTL1 |= UCTXSTT; // I2C start condition
}
}
void i2c_masterSend(uint8_t byteCount, uint8_t *data)
{
ASSERT((byteCount >=1)&&(byteCount<=I2C_TX_BUFFER_SIZE));
txData = data;
i2cTXIndex = byteCount;
UCB0CTL1 |= UCTXSTT; // I2C TX, start condition
}
void i2c_slaveInit(uint8_t rxByteCount, uint8_t *rxData, uint8_t txByteCount, uint8_t *txData)
{
// initialize buffer and count
slaveRXData = rxData;
slaveTXData = txData;
slaveRXIndex = rxByteCount;
slaveTXIndex = txByteCount;
defaultSlaveRXData= rxData;
defaultSlaveTXData = txData;
defaultSlaveRXIndex = rxByteCount;
defaultSlaveTXIndex = txByteCount;
UCB0CTL1 |= UCSWRST; // Enable SW reset
UCB0CTL0 = UCMODE_3 + UCSYNC; // I2C Slave, synchronous mode
UCB0CTL1 &= ~UCSWRST; // Clear SW reset, resume operation
IE2 |= UCB0TXIE + UCB0RXIE; // Enable TX interrupt
UCB0I2CIE |= UCSTTIE; // Enable STT interrupt
}
void i2c_setOwnAddress(uint8_t slaveAddress)
{
UCB0I2COA = slaveAddress;
}
#pragma vector = USCIAB0RX_VECTOR
__interrupt void USCIAB0RX_ISR(void)
{
// Master & Slave Mode: when NACK is detected
if (UCB0STAT & UCNACKIFG){ // send STOP if slave sends NACK
UCB0CTL1 |= UCTXSTP;
UCB0STAT &= ~UCNACKIFG;
// i2c_disableRXInterrupt();
// TA0CCTL0 |= CCIE;
// __bic_SR_register_on_exit(LPM3_bits);
}
// Slave mode: when start condition is detected
if (UCB0STAT & UCSTTIFG)
{
UCB0STAT &= ~UCSTTIFG; // Clear start condition int flag
// initialize something
slaveRXData = defaultSlaveRXData;
slaveTXData = defaultSlaveTXData;
slaveRXIndex = defaultSlaveRXIndex;
slaveTXIndex = defaultSlaveTXIndex;
}
}
#pragma vector = USCIAB0TX_VECTOR
__interrupt void USCIAB0TX_ISR(void)
{
// uart interrupt
if ((IFG2 & UCA0TXIFG) && (IE2 & UCA0TXIE))
{
IE2 &= ~UCA0TXIE;
}
// i2c RX interrupt
if (IFG2 & UCB0RXIFG)
{
// Master
if (UCB0CTL0 & UCMST)
{
//easier when we count down and compare for the one last byte to initiate STOP condition
i2cRXIndex--;
if (i2cRXIndex)
{
*rxData = UCB0RXBUF;
rxData++;
if (i2cRXIndex == 1)
{
UCB0CTL1 |= UCTXSTP;
}
}
else
{
*rxData = UCB0RXBUF;
// when all bytes we want are received
// TODO: make separate process for the below
// i2c_disableRXInterrupt();
// TA0CCTL0 |= CCIE;
// Back to Low Power Mode
__bic_SR_register_on_exit(LPM3_bits);
}
}
else
{
// Slave
if(slaveRXIndex)
{
*slaveRXData = UCB0RXBUF;
slaveRXData++;
slaveRXIndex --;
}
else
{
// when we receive all data
}
}
}
// i2c TX interrupt
if (IFG2 & UCB0TXIFG)
{
// Master
if (UCB0CTL0 & UCMST)
{
//easier when we count down and compare for the one last byte to initiate STOP condition
if (i2cTXIndex)
{
UCB0TXBUF=*txData;
txData++;
// When we send only one byte, do this after sending one byte
i2cTXIndex--;
}
else
{
// When we send only one byte, do this after sending one byte
UCB0CTL1 |= UCTXSTP; // Generate I2C stop condition right after sending last data
IFG2 &= ~UCB0TXIFG;
// send last byte
// UCB0TXBUF=*txData;
// i2c_disableTXInterrupt();
// TA0CCTL0 |= CCIE;
// Back to Low Power Mode
// __bic_SR_register_on_exit(LPM3_bits);
}
}
else
{
// Slave
if (slaveTXIndex)
{
// UCB0TXBUF = *slaveTXData;
// slaveTXData++;
// slaveTXIndex --;
UCB0TXBUF = 128;
}
else
{
// when we transmit all the data
_NOP();
// slaveTXData = defaultSlaveTXData;
// slaveTXIndex = defaultSlaveTXIndex;
}
}
}
}
/*
* i2c.h
*
* Created on: 2012. 12. 30.
* Author: OSSI
*/
#ifndef I2C_H_
#define I2C_H_
#include "ossibeacon.h"
//*****************************************************************************
//
//The following are values that can be passed to the I2C_masterInit() API
//as the selectClockSource parameter.
//
//*****************************************************************************
#define I2C_CLOCKSOURCE_ACLK UCSSEL_1
#define I2C_CLOCKSOURCE_SMCLK UCSSEL_2
//*****************************************************************************
//
//The following are values that can be passed to the I2C_setMode() API
//as the mode parameter.
//
//*****************************************************************************
#define I2C_TRANSMIT_MODE UCTR
#define I2C_RECEIVE_MODE 0x00
void i2c_portSetup(void);
void i2c_enable(void);
void i2c_disable(void);
void i2c_enableTXInterrupt(void);
void i2c_disableTXInterrupt(void);
void i2c_setTXBuffer(uint8_t *buff);
void i2c_enableRXInterrupt(void);
void i2c_disableRXInterrupt(void);
void i2c_enableInterrupt(uint8_t interruptSelect);
void i2c_masterInit(uint8_t selctClockSource, uint16_t preScalerValue ,uint8_t modeSelect);
void i2c_setSlaveAddress(uint8_t slaveAddress);
void i2c_masterReceive(uint8_t byteCount, uint8_t *data);
void i2c_masterSend(uint8_t byteCount, uint8_t *data);
void i2c_slaveInit(uint8_t rxByteCount, uint8_t *rxData, uint8_t txByteCount, uint8_t *txData);
void i2c_setOwnAddress(uint8_t slaveAddress);
void i2c_setTxFlag(void);
void i2c_clearTxFlag(void);
uint8_t i2c_getTxFlag(void);
void i2c_setRxFlag(void);
void i2c_clearRxFlag(void);
uint8_t i2c_getRxFlag(void);
#endif /* I2C_H_ */
/*
* main.c
*/
#include "ossibeacon.h"
#include "printf.h"
#include "adc10.h"
#include "i2c.h"
#define ADC_BUF_SIZE 8
#define ADC_BUF_SIZE2 16
volatile uint16_t VBUSVal[ADC_BUF_SIZE] = {0};
volatile uint16_t VextVal[ADC_BUF_SIZE2] = {0};
volatile uint8_t cnt;
volatile uint8_t adc;
volatile uint8_t flag;
volatile uint8_t taskNum;
uint8_t tmp102Data[2] = {0};
uint8_t tmp102Tx[1] = {0x01};
uint8_t beaconRxData[64]={0};
uint8_t beaconTxData[128]={0};
void main(void) {
WDTCTL = WDTPW + WDTHOLD; // Stop watchdog timer
// default: MCLK = SMCLK = DCO ~ 1.2MHz
// set DCO speed to calibrated 1MHz
BCSCTL1 = CALBC1_8MHZ;
DCOCTL = CALDCO_8MHZ;
// TODO: Internal Capacitor VS External Capacitor???
// BCSCTL3 |= XCAP_0;
// general IO init
// set unused pins!!!
P1DIR = 0xFF & ~(BIT1+BIT2); // ADF7012 TXCLK output is high. Beware!!! Why??
P1OUT = 0x00;
P3DIR = 0xFF & ~(BIT1+BIT2+BIT3+BIT5);
P3OUT = 0x00;
P2DIR = 0xFF & ~(BIT0+BIT1+BIT5);
P2OUT = 0x00;
adc10_portSetup(ADC10_PIN_2_0 + ADC10_PIN_2_1);
TA0CTL = TASSEL_1 + MC_2; // ACLK = 32.768kHz, contmode
uart_setup_9600();
uart_init();
IE2 &= ~UCA0RXIE;
IE2 &= ~UCA0TXIE;
i2c_portSetup();
TA0CCTL0 |= CCIE;
volatile uint8_t i;
for( i = 0; i <64; i++)
{
beaconRxData[i] = i;
}
for( i = 0; i <16; i++)
{
beaconTxData[i] = 15-i;
}
while(1)
{
// i2c Master
i2c_slaveInit(64, beaconRxData, 16, beaconTxData);
i2c_setOwnAddress(0x49);
__bis_SR_register(LPM3_bits + GIE);
//TA0CCTL0 &= ~CCIE;
// /* Set 1 **************************************/
// // TODO: implement timeout function instead of using while
// // while (UCB0CTL1 & UCTXSTT); // also check this if i2c clock source is too slow
// while(UCB0STAT & UCBBUSY);
// i2c_masterInit(I2C_CLOCKSOURCE_SMCLK, 80 ,I2C_TRANSMIT_MODE);
// i2c_setSlaveAddress(0x48);
// UCB0I2CIE = UCNACKIE;
// i2c_enableTXInterrupt();
// i2c_masterSend(1, tmp102Tx);
//
// /* Set 2 **************************************/
// // TODO: implement timeout function instead of using while
// // while (UCB0CTL1 & UCTXSTT); // also check this if i2c clock source is too slow
// while(UCB0STAT & UCBBUSY);
// i2c_masterInit(I2C_CLOCKSOURCE_SMCLK, 80 ,I2C_RECEIVE_MODE);
// i2c_setSlaveAddress(0x48);
// UCB0I2CIE = UCNACKIE;
// i2c_enableRXInterrupt();
// i2c_masterReceive(2, tmp102Data);
}
}
#pragma vector = TIMER0_A0_VECTOR
__interrupt void TA0_ISR(void)
{
__bic_SR_register_on_exit(LPM3_bits); // Exit LPM0
}
//#pragma vector=ADC10_VECTOR
//__interrupt void ADC10_ISR(void)
//{
// // It's very important to stop conversion right after ISR is entered to avoid corrupted data or sequence.
// // TODO: compare this method to polling ADC10BUSY flag
// ADC10CTL0 &= ~ENC;
// __bic_SR_register_on_exit(LPM3_bits); // Clear LPM3_bits from 0(SR)
//}
/*
* ossibeacon.h
*
* Created on: 2012. 12. 22.
* Author: OSSI
*/
#ifndef OSSIBEACON_H_
#define OSSIBEACON_H_
#include "msp430x21x2.h"
#include "debug.h"
#include "system.h"
#include "ossitypes.h"
#include "util.h"
#endif /* OSSIBEACON_H_ */
/*
* ossitypes.h
*
* Created on: 2012. 12. 22.
* Author: OSSI
*/
#ifndef OSSITYPES_H_
#define OSSITYPES_H_
typedef unsigned char uint8_t;
typedef signed char int8_t;
typedef unsigned short int uint16_t;
typedef signed short int int16_t;
typedef unsigned long int uint32_t;
typedef signed long int int32_t;
#endif /* OSSITYPES_H_ */
/******************************************************************************
* Reusable MSP430 printf()
*
* Description: This printf function was written by oPossum and originally
* posted on the 43oh.com forums. For more information on this
* code, please see the link below.
*
* http://www.43oh.com/forum/viewtopic.php?f=10&t=1732
*
* A big thanks to oPossum for sharing such great code!
*
* Author: oPossum
* Source: http://www.43oh.com/forum/viewtopic.php?f=10&t=1732
* Date: 10-17-11
*
* Note: This comment section was written by Nicholas J. Conn on 06-07-2012
* for use on NJC's MSP430 LaunchPad Blog.
******************************************************************************/
/*
* printf.c
*
* Created on: 2012. 12. 19.
* Author: OSSI
*/
#include "printf.h"
static const unsigned long dv[] = {
// 4294967296 // 32 bit unsigned max
1000000000,// +0
100000000, // +1
10000000, // +2
1000000, // +3
100000, // +4
// 65535 // 16 bit unsigned max
10000, // +5
1000, // +6
100, // +7
10, // +8
1, // +9
};
static void xtoa(unsigned long x, const unsigned long *dp) {
char c;
unsigned long d;
if (x) {
while (x < *dp)
++dp;
do {
d = *dp++;
c = '0';
while (x >= d)
++c, x -= d;
putc(c);
} while (!(d & 1));
} else
putc('0');
}
static void puth(unsigned n) {
static const char hex[16] = { '0', '1', '2', '3', '4', '5', '6', '7', '8',
'9', 'A', 'B', 'C', 'D', 'E', 'F' };
putc(hex[n & 15]);
}
void printf(char *format, ...)
{
char c;
int i;
long n;
va_list a;
va_start(a, format);
while(c = *format++) {
if(c == '%') {
switch(c = *format++) {
case 's': // String
puts(va_arg(a, char*));
break;
case 'c':// Char
putc(va_arg(a, char));
break;
case 'i':// 16 bit Integer
case 'u':// 16 bit Unsigned
i = va_arg(a, int);
if(c == 'i' && i < 0) i = -i, putc('-');
xtoa((unsigned)i, dv + 5);
break;
case 'l':// 32 bit Long
case 'n':// 32 bit uNsigned loNg
n = va_arg(a, long);
if(c == 'l' && n < 0) n = -n, putc('-');
xtoa((unsigned long)n, dv);
break;
case 'x':// 16 bit heXadecimal
i = va_arg(a, int);
puth(i >> 12);
puth(i >> 8);
puth(i >> 4);
puth(i);
break;
case 0: return;
default: goto bad_fmt;
}
} else
bad_fmt: putc(c);
}
va_end(a);
}
/*
* printf.h
*
* Created on: 2012. 12. 19.
* Author: OSSI
*/
#ifndef PRINTF_H_
#define PRINTF_H_
#include "stdarg.h"
#include "aclkuart.h"
void printf(char *, ...);
#endif /* PRINTF_H_ */
/*
* setup2132.c
*
* Created on: 2012. 12. 19.
* Author: OSSI
*/
#include "system.h"
void int_wdt_disable(void)
{
WDTCTL = WDTPW + WDTHOLD; // Stop watchdog timer
}
void clock_setup(void)
{
// default: MCLK = SMCLK = DCO ~ 1.2MHz
// set DCO speed to calibrated 1MHz
// TODO: clock switching when clock failure (when LFXT1CLK 32.768kHz fails, ACLK source switches from LFXT1CLK -> VLOCLK)
BCSCTL1 = CALBC1_8MHZ;
DCOCTL = CALDCO_8MHZ;
}
void IO_setup(void)
{
// general IO init
// TODO: set unused pins!!!
IO_DIRECTION(LED,OUTPUT);
IO_SET(LED,LOW);
}
void ext_wdt_setup(void)
{
IO_DIRECTION(EXTWDT,OUTPUT);
}
void ext_wdt_rst(void)
{
//LOW-HIGH-LOW
IO_SET(EXTWDT,LOW);
delay_ms(1);
IO_SET(EXTWDT,HIGH);
delay_ms(1);
IO_SET(EXTWDT,LOW);
}
/*
* setup2132.h
*
* Created on: 2012. 12. 19.
* Author: OSSI
*/
#ifndef SETUP2132_H_
#define SETUP2132_H_
#include "msp430x21x2.h"
#include "ossitypes.h"
#include "util.h"
// System IO Define
#define LED_PORT 3
#define LED_PIN 0
#define EXTWDT_PORT 2
#define EXTWDT_PIN 2
void int_wdt_disable(void);
void clock_setup(void);
void IO_setup(void);
void ext_wdt_setup(void);
void ext_wdt_rst(void);
#endif /* SETUP2132_H_ */
/*
* util.c
*
* Created on: 2012. 12. 19.
* Author: OSSI
*/
#include "util.h"
void delay_ms(uint16_t delay)
{
volatile uint16_t i;
for (i=0; i<delay;i++)
{
__delay_cycles(8000); // @ DCO 8MHz
}
}
void min_max(uint8_t min, uint8_t max, uint8_t value)
{
if (value <= min)
{
value = min;
}
if (value > max)
{
value = max;
}
}
/*
* global.h
*
* Created on: 2012. 6. 3.
* Author: donghee
*/
#ifndef GLOBAL_H_
#define GLOBAL_H_
#include "ossitypes.h"
// Macros for turning on and off the LEDs (for testing only)
enum {FALSE = 0, TRUE = 1};
#define _BV(bit) (1<<(bit))
//macros for IO config (with preprocessor abuse)
#define st(x) do{x} while(__LINE__ == -1)
enum IoState {LOW = 0, HIGH = 1, TOGGLE = 2};
#define IO_SET(name,val) _IO_SET(name##_PORT,name##_PIN,val)
#define _IO_SET(port,pin,val) st(__IO_SET(port,pin,val);)
#define __IO_SET(port,pin,val) if (val == TOGGLE)\
{\
st((P##port##OUT ^= _BV(pin)););\
}\
else if (val == HIGH)\
{\
st((P##port##OUT |= _BV(pin)););\
}\
else\
{\
st((P##port##OUT &= ~_BV(pin)););\
}
enum IoDirection {INPUT = 0, OUTPUT = 1};
#define IO_DIRECTION(name,dir) _IO_DIRECTION(name##_PORT,name##_PIN,dir)
#define _IO_DIRECTION(port,pin,dir) st(__IO_DIRECTION(port,pin,dir);)
#define __IO_DIRECTION(port,pin,dir) if (dir)\
{\
st((P##port##DIR |= _BV(pin)););\
}\
else\
{\
st((P##port##DIR &= ~_BV(pin)););\
}
void delay_ms(uint16_t delay);
void min_max(uint8_t min, uint8_t max, uint8_t value);
#endif /* GLOBAL_H_ */
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment