]> Pileus Git - ~andy/csm213a-hw/commitdiff
Add sensors code from Yue
authorAndy Spencer <andy753421@gmail.com>
Sat, 1 Feb 2014 05:14:27 +0000 (05:14 +0000)
committerAndy Spencer <andy753421@gmail.com>
Sat, 1 Feb 2014 05:14:27 +0000 (05:14 +0000)
.gitignore
yue/MAG3110/MAG3110.cpp [new file with mode: 0644]
yue/MAG3110/MAG3110.h [new file with mode: 0644]
yue/MMA8451Q/MMA8451Q.cpp [new file with mode: 0644]
yue/MMA8451Q/MMA8451Q.h [new file with mode: 0644]
yue/TSI/TSISensor.cpp [new file with mode: 0644]
yue/TSI/TSISensor.h [new file with mode: 0644]
yue/main.cpp [new file with mode: 0644]
yue/makefile [new file with mode: 0644]

index 87641378bef242b558089c5a02706c2f09577bc3..83fd7028d56ae3ba57e3264aa48d908a5cca44ac 100644 (file)
@@ -1,5 +1,7 @@
 *.bin
+*.bld
 *.elf
+*.lib
 *.o
 *~
 config.mk
diff --git a/yue/MAG3110/MAG3110.cpp b/yue/MAG3110/MAG3110.cpp
new file mode 100644 (file)
index 0000000..a788d64
--- /dev/null
@@ -0,0 +1,91 @@
+
+#include "MAG3110.h"
+#include "mbed.h"
+
+/******************************************************************************
+ * Constructors
+ ******************************************************************************/
+MAG3110::MAG3110(PinName sda, PinName scl): _i2c(sda, scl), 
+    _i2c_address(0x1D), _pc(NULL), _debug(false)
+{
+    begin();
+}
+
+MAG3110::MAG3110(PinName sda, PinName scl, Serial *pc): _i2c(sda, scl), 
+   _i2c_address(0x1D), _pc(pc), _debug(true)
+{
+    begin();
+}
+
+void MAG3110::begin()
+{
+    char cmd[2];
+
+    cmd[0] = MAG_CTRL_REG2;
+    cmd[1] = 0x80;
+    _i2c.write(_i2c_address, cmd, 2);
+
+    cmd[0] = MAG_CTRL_REG1;
+    cmd[1] = MAG_3110_SAMPLE80+MAG_3110_OVERSAMPLE2+MAG_3110_ACTIVE;
+    _i2c.write(_i2c_address, cmd, 2);
+    
+    // No adjustment initially
+    _avgX = 0;
+    _avgY = 0;
+}
+
+// Read a single byte form 8 bit register, return as int
+int MAG3110::readReg(char regAddr)
+{
+    char cmd[1];
+
+    cmd[0] = regAddr;
+    _i2c.write(_i2c_address, cmd, 1);
+
+    cmd[0] = 0x00;
+    _i2c.read(_i2c_address, cmd, 1);
+    return (int)( cmd[0]);
+}
+
+
+// read a register per, pass first reg value, reading 2 bytes increments register
+// Reads MSB first then LSB
+int MAG3110::readVal(char regAddr)
+{
+    char cmd[2];
+
+    cmd[0] = regAddr;
+    _i2c.write(_i2c_address, cmd, 1);
+
+    cmd[0] = 0x00;
+    cmd[1] = 0x00;
+    _i2c.read(_i2c_address, cmd, 2);
+    return (int)( (cmd[1]|(cmd[0] << 8))); //concatenate the MSB and LSB
+}
+
+
+float MAG3110::getHeading()
+{
+    int xVal = readVal(MAG_OUT_X_MSB);
+    int yVal = readVal(MAG_OUT_Y_MSB);
+    return (atan2((double)(yVal - _avgY),(double)(xVal - _avgX)))*180/PI;
+}
+
+void MAG3110::getValues(int *xVal, int *yVal, int *zVal)
+{
+    *xVal = readVal(MAG_OUT_X_MSB);
+    *yVal = readVal(MAG_OUT_Y_MSB);
+    *zVal = readVal(MAG_OUT_Z_MSB);
+}
+
+
+void MAG3110::setCalibration(int minX, int maxX, int minY, int maxY )
+{
+    _avgX=(maxX+minX)/2;
+    _avgY=(maxY+minY)/2;
+}
+
+
+
+
+
diff --git a/yue/MAG3110/MAG3110.h b/yue/MAG3110/MAG3110.h
new file mode 100644 (file)
index 0000000..88cf042
--- /dev/null
@@ -0,0 +1,144 @@
+/*
+ * MAG3110 Sensor Library for mbed
+ * TODO: Add proper header
+ */
+
+#ifndef MAG3110_H
+#define MAG3110_H
+
+#include "mbed.h"
+
+#define PI 3.14159265359
+
+#define MAG_ADDR 0x1D
+
+// define registers
+#define MAG_DR_STATUS 0x00
+#define MAG_OUT_X_MSB 0x01
+#define MAG_OUT_X_LSB 0x02
+#define MAG_OUT_Y_MSB 0x03
+#define MAG_OUT_Y_LSB 0x04
+#define MAG_OUT_Z_MSB 0x05
+#define MAG_OUT_Z_LSB 0x06
+#define MAG_WHO_AM_I  0x07
+#define MAG_SYSMOD    0x08
+#define MAG_OFF_X_MSB 0x09
+#define MAG_OFF_X_LSB 0x0A
+#define MAG_OFF_Y_MSB 0x0B
+#define MAG_OFF_Y_LSB 0x0C
+#define MAG_OFF_Z_MSB 0x0D
+#define MAG_OFF_Z_LSB 0x0E
+#define MAG_DIE_TEMP  0x0F
+#define MAG_CTRL_REG1 0x10
+#define MAG_CTRL_REG2 0x11
+
+// what should WHO_AM_I return?
+#define MAG_3110_WHO_AM_I_VALUE 0xC4
+
+
+// Fields in registers
+// CTRL_REG1: dr2,dr1,dr0  os1,os0  fr tm ac
+
+// Sampling rate from 80Hz down to 0.625Hz
+#define MAG_3110_SAMPLE80 0
+#define MAG_3110_SAMPLE40 0x20
+#define MAG_3110_SAMPLE20 0x40
+#define MAG_3110_SAMPLE10 0x60
+#define MAG_3110_SAMPLE5 0x80
+#define MAG_3110_SAMPLE2_5 0xA0
+#define MAG_3110_SAMPLE1_25 0xC0
+#define MAG_3110_SAMPLE0_625 0xE0
+
+// How many samples to average (lowers data rate)
+#define MAG_3110_OVERSAMPLE1 0
+#define MAG_3110_OVERSAMPLE2 0x08
+#define MAG_3110_OVERSAMPLE3 0x10
+#define MAG_3110_OVERSAMPLE4 0x18
+
+// read only 1 byte per axis
+#define MAG_3110_FASTREAD 0x04
+// do one measurement (even if in standby mode)
+#define MAG_3110_TRIGGER 0x02
+// put in active mode
+#define MAG_3110_ACTIVE 0x01
+
+// CTRL_REG2: AUTO_MRST_EN  _ RAW MAG_RST _ _ _ _ _
+// reset sensor after each reading
+#define MAG_3110_AUTO_MRST_EN 0x80
+// don't subtract user offsets
+#define MAG_3110_RAW 0x20
+// reset magnetic sensor after too-large field
+#define MAG_3110_MAG_RST 0x10
+
+// DR_STATUS Register ZYXOW ZOW YOW XOW ZYXDR ZDR YDR XDR
+#define MAG_3110_ZYXDR  0x08
+
+/**
+ * MAG3110 Class to read X/Y/Z data from the magentometer
+ *
+ */
+class MAG3110
+{
+public:
+    /**
+     * Main constructor
+     * @param sda SDA pin
+     * @param sdl SCL pin
+     * @param addr addr of the I2C peripheral
+     */
+    MAG3110(PinName sda, PinName scl);
+    /**
+     * Debug version of constructor
+     * @param sda SDA pin
+     * @param sdl SCL pin
+     * @param addr Address of the I2C peripheral
+     * @param pc Serial object to output debug messages
+     */
+    MAG3110(PinName sda, PinName scl, Serial *pc); //pass serial for debug
+    /**
+     * Setup the Magnetometer
+     *
+     */
+    void begin();
+    /**
+     * Read a register, return its value as int
+     * @param regAddr The address to read
+     * @return value in register
+     */
+    int readReg(char regAddr);
+    /**
+     * Read a value from a pair of registers, return as int
+     * @param regAddr The address to read
+     * @return Value from 2 consecutive registers
+     */
+    int readVal(char regAddr);
+    /**
+     * Calculate the heading
+     * @return heading in degrees
+     */
+    float getHeading();
+    /**
+     * Perform a read on the X, Y and Z values.
+     * @param xVal Pointer to X value
+     * @param yVal Pointer to Y value
+     * @param zVal Pointer to Z value
+     */
+    void getValues(int *xVal, int *yVal, int *zVal);
+    /**
+     * Set the calibration parameters if required.
+     * @param minX Minimum value for X range
+     * @param maxX Maximum value for X range
+     * @param minY Minimum value for Y range
+     * @param maxY maximum value for Y range
+     */
+    void setCalibration(int minX, int maxX, int minY, int maxY);
+
+private:
+    I2C _i2c;
+    int _i2c_address;
+    Serial *_pc;
+    bool _debug;
+    int _avgX, _avgY;
+
+};
+#endif
diff --git a/yue/MMA8451Q/MMA8451Q.cpp b/yue/MMA8451Q/MMA8451Q.cpp
new file mode 100644 (file)
index 0000000..f65e807
--- /dev/null
@@ -0,0 +1,155 @@
+/* Copyright (c) 2010-2011 mbed.org, MIT License
+*
+* Permission is hereby granted, free of charge, to any person obtaining a copy of this software
+* and associated documentation files (the "Software"), to deal in the Software without
+* restriction, including without limitation the rights to use, copy, modify, merge, publish,
+* distribute, sublicense, and/or sell copies of the Software, and to permit persons to whom the
+* Software is furnished to do so, subject to the following conditions:
+*
+* The above copyright notice and this permission notice shall be included in all copies or
+* substantial portions of the Software.
+*
+* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING
+* BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND
+* NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM,
+* DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
+*/
+
+#include "MMA8451Q.h"
+
+#define INT_SOURCE        0x0C 
+#define REG_WHO_AM_I      0x0D
+#define HP_FILTER_CUTOFF  0x0F 
+#define PULSE_CFG         0x21 
+#define PULSE_SRC         0x22 
+#define PULSE_THSX        0x23 
+#define PULSE_THSY        0x24 
+#define PULSE_THSZ        0x25 
+#define PULSE_TMLT        0x26 
+#define PULSE_LTCY        0x27 
+#define PULSE_WIND        0x28 
+#define REG_CTRL_REG_1    0x2A 
+#define CTRL_REG2         0x2B
+#define CTRL_REG4         0x2D 
+#define CTRL_REG5         0x2E 
+#define REG_OUT_X_MSB     0x01
+#define REG_OUT_Y_MSB     0x03
+#define REG_OUT_Z_MSB     0x05
+
+#define UINT14_MAX        16383
+
+MMA8451Q::MMA8451Q(PinName sda, PinName scl, int addr) : m_i2c(sda, scl), m_addr(addr) {
+    // activate the peripheral
+    uint8_t data[2] = {REG_CTRL_REG_1, 0x01};
+    writeRegs(data, 2);
+}
+
+MMA8451Q::~MMA8451Q() { }
+
+uint8_t MMA8451Q::getWhoAmI() {
+    uint8_t who_am_i = 0;
+    readRegs(REG_WHO_AM_I, &who_am_i, 1);
+    return who_am_i;
+}
+
+float MMA8451Q::getAccX() {
+//divide by 4096 b/c MMA output is 4096 counts per g so this f outputs accelorometer value formatted to g (gravity)
+    return (float(getAccAxis(REG_OUT_X_MSB))/4096.0);
+}
+
+float MMA8451Q::getAccY() {
+    return (float(getAccAxis(REG_OUT_Y_MSB))/4096.0);
+}
+
+float MMA8451Q::getAccZ() {
+    return (float(getAccAxis(REG_OUT_Z_MSB))/4096.0);
+}
+
+void MMA8451Q::getAccAllAxis(float * res) {
+    res[0] = getAccX();
+    res[1] = getAccY();
+    res[2] = getAccZ();
+}
+
+int16_t MMA8451Q::getAccAxis(uint8_t addr) {
+    int16_t acc;
+    uint8_t res[2];
+    readRegs(addr, res, 2);
+
+    acc = (res[0] << 6) | (res[1] >> 2);
+    if (acc > UINT14_MAX/2)
+        acc -= UINT14_MAX;
+
+    return acc;
+}
+
+void MMA8451Q::setDoubleTap(void){
+//Implemented directly from Freescale's AN4072 
+//Added to MMA8451Q lib
+
+    uint8_t CTRL_REG1_Data;
+//    int adds;
+   uint8_t data[2] = {REG_CTRL_REG_1, 0x08};
+    
+    //400 Hz, Standby Mode
+    writeRegs(data,2);
+    
+    //Enable X, Y and Z Double Pulse with DPA = 0 no double pulse abort    
+    data[0]=PULSE_CFG;data[1]=0x2A;
+    writeRegs(data,2);
+    
+    //SetThreshold 3g on X and Y and 5g on Z
+    //Note: Every step is 0.063g
+    //3 g/0.063g = 48 counts
+    //5g/0.063g = 79 counts
+    data[0]=PULSE_THSX;data[1]=0x30;
+    writeRegs(data,2);//Set X Threshold to 3g 
+    data[0]=PULSE_THSY;data[1]=0x30;
+    writeRegs(data,2);//Set Y Threshold to 3g 
+    data[0]=PULSE_THSZ;data[1]=0x4F;
+    writeRegs(data,2);//Set Z Threshold to 5g
+
+    //Set Time Limit for Tap Detection to 60 ms LP Mode
+    //Note: 400 Hz ODR, Time step is 1.25 ms per step
+    //60 ms/1.25 ms = 48 counts 
+    data[0]=PULSE_TMLT;data[1]=0x30;
+    writeRegs(data,2);//60 ms
+    
+    //Set Latency Time to 200 ms
+    //Note: 400 Hz ODR LPMode, Time step is 2.5 ms per step 00 ms/2.5 ms = 80 counts
+    data[0]=PULSE_LTCY;data[1]=0x50;
+    writeRegs(data,2);//200 ms
+    
+    //Set Time Window for second tap to 300 ms
+    //Note: 400 Hz ODR LP Mode, Time step is 2.5 ms per step
+    //300 ms/2.5 ms = 120 counts
+    data[0]=PULSE_WIND;data[1]=0x78;
+    writeRegs(data,2);//300 ms
+    
+    //Route INT1 to System Interrupt
+    data[0]=CTRL_REG4;data[1]=0x08;
+    writeRegs(data,2);//Enable Pulse Interrupt in System CTRL_REG4
+    data[0]=CTRL_REG5;data[1]=0x08; 
+    writeRegs(data,2);//Route Pulse Interrupt to INT1 hardware Pin CTRL_REG5
+
+    //Set the device to Active Mode
+    readRegs(0x2A,&CTRL_REG1_Data,1);//Read out the contents of the register 
+    CTRL_REG1_Data |= 0x01; //Change the value in the register to Active Mode.
+    data[0]=REG_CTRL_REG_1; 
+    data[1]=CTRL_REG1_Data;
+    writeRegs(data,2);//Write in the updated value to put the device in Active Mode
+}
+
+
+void MMA8451Q::readRegs(int addr, uint8_t * data, int len) {
+    char t[1] = {addr};
+    m_i2c.write(m_addr, t, 1, true);
+    m_i2c.read(m_addr, (char *)data, len);
+}
+
+
+
+void MMA8451Q::writeRegs(uint8_t * data, int len) {
+    m_i2c.write(m_addr, (char *)data, len);
+}
diff --git a/yue/MMA8451Q/MMA8451Q.h b/yue/MMA8451Q/MMA8451Q.h
new file mode 100644 (file)
index 0000000..da82407
--- /dev/null
@@ -0,0 +1,159 @@
+/* Copyright (c) 2010-2011 mbed.org, MIT License
+*
+* Permission is hereby granted, free of charge, to any person obtaining a copy of this software
+* and associated documentation files (the "Software"), to deal in the Software without
+* restriction, including without limitation the rights to use, copy, modify, merge, publish,
+* distribute, sublicense, and/or sell copies of the Software, and to permit persons to whom the
+* Software is furnished to do so, subject to the following conditions:
+*
+* The above copyright notice and this permission notice shall be included in all copies or
+* substantial portions of the Software.
+*
+* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING
+* BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND
+* NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM,
+* DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
+*/
+
+#ifndef MMA8451Q_H
+#define MMA8451Q_H
+
+#include "mbed.h"
+
+/**
+* MMA8451Q accelerometer example
+*
+* @code
+* #include "mbed.h"
+* #include "MMA8451Q.h"
+* 
+* #define MMA8451_I2C_ADDRESS (0x1d<<1)
+* 
+* int main(void) {
+* 
+* MMA8451Q acc(P_E25, P_E24, MMA8451_I2C_ADDRESS);
+* PwmOut rled(LED_RED);
+* PwmOut gled(LED_GREEN);
+* PwmOut bled(LED_BLUE);
+* 
+*     while (true) {       
+*         rled = 1.0 - abs(acc.getAccX());
+*         gled = 1.0 - abs(acc.getAccY());
+*         bled = 1.0 - abs(acc.getAccZ());
+*         wait(0.1);
+*     }
+* }
+* @endcode
+*/
+class MMA8451Q
+{
+public:
+  /**
+  * MMA8451Q constructor
+  *
+  * @param sda SDA pin
+  * @param sdl SCL pin
+  * @param addr addr of the I2C peripheral
+  */
+  MMA8451Q(PinName sda, PinName scl, int addr);
+
+  /**
+  * MMA8451Q destructor
+  */
+  ~MMA8451Q();
+
+  /**
+   * Get the value of the WHO_AM_I register
+   *
+   * @returns WHO_AM_I value
+   */
+  uint8_t getWhoAmI();
+
+  /**
+   * Get X axis acceleration
+   *
+   * @returns X axis acceleration
+   */
+  float getAccX();
+
+  /**
+   * Get Y axis acceleration
+   *
+   * @returns Y axis acceleration
+   */
+  float getAccY();
+
+  /**
+   * Get Z axis acceleration
+   *
+   * @returns Z axis acceleration
+   */
+  float getAccZ();
+
+  /**
+   * Get XYZ axis acceleration
+   *
+   * @param res array where acceleration data will be stored
+   */
+  void getAccAllAxis(float * res);
+  
+  /** JK
+  * Setup Double Tap detection
+Example:
+
+#include "mbed.h"
+#include "MMA8451Q.h"
+
+#define MMA8451_I2C_ADDRESS (0x1d<<1)
+#define ON  0
+#define OFF !ON
+
+//Setup the interrupts for the MMA8451Q
+InterruptIn accInt1(PTA14);
+InterruptIn accInt2(PTA15);//not used in this prog but this is the other int from the accelorometer
+
+uint8_t togstat=0;//Led status
+DigitalOut bled(LED_BLUE);
+
+
+void tapTrue(void){//ISR
+    if(togstat == 0){
+        togstat = 1;
+        bled=ON;
+    } else {
+        togstat = 0;
+        bled=OFF;
+    }
+        
+}
+
+
+int main(void) {
+
+    MMA8451Q acc(PTE25, PTE24, MMA8451_I2C_ADDRESS);//accelorometer instance
+  
+    acc.setDoubleTap();//Setup the MMA8451Q to look for a double Tap
+    accInt1.rise(&tapTrue);//call tapTrue when an interrupt is generated on PTA14
+    
+    while (true) {
+    //Interrupt driven so nothing in main loop
+    }
+}
+
+
+  */
+  void setDoubleTap(void);
+
+private:
+  I2C m_i2c;
+  int m_addr;
+  void readRegs(int addr, uint8_t * data, int len);
+  void writeRegs(uint8_t * data, int len);
+  int16_t getAccAxis(uint8_t addr);
+
+};
+
+#endif
diff --git a/yue/TSI/TSISensor.cpp b/yue/TSI/TSISensor.cpp
new file mode 100644 (file)
index 0000000..5206aad
--- /dev/null
@@ -0,0 +1,254 @@
+/* Freescale Semiconductor Inc.
+ * (c) Copyright 2004-2005 Freescale Semiconductor, Inc.
+ * (c) Copyright 2001-2004 Motorola, Inc. 
+ *
+ * mbed Microcontroller Library
+ * (c) Copyright 2009-2012 ARM Limited.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy of this software
+ * and associated documentation files (the "Software"), to deal in the Software without
+ * restriction, including without limitation the rights to use, copy, modify, merge, publish,
+ * distribute, sublicense, and/or sell copies of the Software, and to permit persons to whom the
+ * Software is furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in all copies or
+ * substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING
+ * BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND
+ * NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM,
+ * DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+ * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
+ */
+
+#include "mbed.h"
+#include "TSISensor.h"
+
+#define NO_TOUCH                 0
+#define SLIDER_LENGTH           40 //LENGTH in mm
+#define TOTAL_ELECTRODE          3
+
+#define TSI0a        0
+#define TSI1         1
+#define TSI2         2
+#define TSI3         3
+#define TSI4         4
+#define TSI5         5
+#define TSI6         6
+#define TSI7         7
+#define TSI8         8
+#define TSI9         9
+#define TSI10        10
+#define TSI11        11
+#define TSI12        12
+#define TSI13        13
+#define TSI14        14
+#define TSI15        15
+
+/*Chose the correct TSI channel for the electrode number*/
+#define ELECTRODE0   TSI9
+#define ELECTRODE1   TSI10
+#define ELECTRODE2   TSI0a
+#define ELECTRODE3   TSI1
+#define ELECTRODE4   TSI2
+#define ELECTRODE5   TSI3
+#define ELECTRODE6   TSI4
+#define ELECTRODE7   TSI5
+#define ELECTRODE8   TSI6
+#define ELECTRODE9   TSI7
+#define ELECTRODE10  TSI8
+#define ELECTRODE11  TSI11
+#define ELECTRODE12  TSI12
+#define ELECTRODE13  TSI13
+#define ELECTRODE14  TSI14
+#define ELECTRODE15  TSI15
+
+#define THRESHOLD0   100
+#define THRESHOLD1   100
+#define THRESHOLD2   100
+#define THRESHOLD3   100
+#define THRESHOLD4   100
+#define THRESHOLD5   100
+#define THRESHOLD6   100
+#define THRESHOLD7   100
+#define THRESHOLD8   100
+#define THRESHOLD9   100
+#define THRESHOLD10   100
+#define THRESHOLD11   100
+#define THRESHOLD12   100
+#define THRESHOLD13   100
+#define THRESHOLD14   100
+#define THRESHOLD15   100
+
+static uint8_t total_electrode = TOTAL_ELECTRODE;
+static uint8_t elec_array[16]={ELECTRODE0,ELECTRODE1,ELECTRODE2,ELECTRODE3,ELECTRODE4,ELECTRODE5,
+                               ELECTRODE6,ELECTRODE7,ELECTRODE8,ELECTRODE9,ELECTRODE10,ELECTRODE11,
+                               ELECTRODE12,ELECTRODE13,ELECTRODE14,ELECTRODE15};
+static uint16_t gu16TSICount[16];
+static uint16_t gu16Baseline[16];
+static uint16_t gu16Threshold[16]={THRESHOLD0,THRESHOLD1,THRESHOLD2,THRESHOLD3,THRESHOLD4,THRESHOLD5,
+                                   THRESHOLD6,THRESHOLD7,THRESHOLD8,THRESHOLD9,THRESHOLD10,THRESHOLD11,
+                                   THRESHOLD12,THRESHOLD13,THRESHOLD14,THRESHOLD15};
+static uint16_t gu16Delta[16];
+static uint8_t ongoing_elec;
+static uint8_t end_flag = 1;
+
+static uint8_t SliderPercentegePosition[2] = {NO_TOUCH,NO_TOUCH};
+static uint8_t SliderDistancePosition[2] = {NO_TOUCH,NO_TOUCH};
+static uint32_t AbsolutePercentegePosition = NO_TOUCH;
+static uint32_t AbsoluteDistancePosition = NO_TOUCH;
+
+static void tsi_irq();
+
+TSISensor::TSISensor() {
+    SIM->SCGC5 |= SIM_SCGC5_PORTB_MASK;
+    SIM->SCGC5 |= SIM_SCGC5_TSI_MASK;
+
+    TSI0->GENCS |= (TSI_GENCS_ESOR_MASK
+                   | TSI_GENCS_MODE(0)
+                   | TSI_GENCS_REFCHRG(4)
+                   | TSI_GENCS_DVOLT(0)
+                   | TSI_GENCS_EXTCHRG(7)
+                   | TSI_GENCS_PS(4)
+                   | TSI_GENCS_NSCN(11)
+                   | TSI_GENCS_TSIIEN_MASK
+                   | TSI_GENCS_STPE_MASK
+                   );
+
+    TSI0->GENCS |= TSI_GENCS_TSIEN_MASK;
+
+    NVIC_SetVector(TSI0_IRQn, (uint32_t)&tsi_irq);
+    NVIC_EnableIRQ(TSI0_IRQn);
+
+    selfCalibration();
+}
+
+void TSISensor::TSISensor_reset(void) {
+    SIM->SCGC5 |= SIM_SCGC5_PORTB_MASK;
+    SIM->SCGC5 |= SIM_SCGC5_TSI_MASK;
+
+    TSI0->GENCS |= (TSI_GENCS_ESOR_MASK
+                   | TSI_GENCS_MODE(0)
+                   | TSI_GENCS_REFCHRG(4)
+                   | TSI_GENCS_DVOLT(0)
+                   | TSI_GENCS_EXTCHRG(7)
+                   | TSI_GENCS_PS(4)
+                   | TSI_GENCS_NSCN(11)
+                   | TSI_GENCS_TSIIEN_MASK
+                   | TSI_GENCS_STPE_MASK
+                   );
+
+    TSI0->GENCS |= TSI_GENCS_TSIEN_MASK;
+
+    //NVIC_SetVector(TSI0_IRQn, (uint32_t)&tsi_irq);
+    //NVIC_EnableIRQ(TSI0_IRQn);
+
+    selfCalibration();
+}
+
+void TSISensor::selfCalibration(void)
+{
+    unsigned char cnt;
+    unsigned char trigger_backup;
+
+    TSI0->GENCS |= TSI_GENCS_EOSF_MASK;      // Clear End of Scan Flag
+    TSI0->GENCS &= ~TSI_GENCS_TSIEN_MASK;    // Disable TSI module
+
+    if(TSI0->GENCS & TSI_GENCS_STM_MASK)     // Back-up TSI Trigger mode from Application
+        trigger_backup = 1;
+    else
+        trigger_backup = 0;
+
+    TSI0->GENCS &= ~TSI_GENCS_STM_MASK;      // Use SW trigger
+    TSI0->GENCS &= ~TSI_GENCS_TSIIEN_MASK;    // Enable TSI interrupts
+
+    TSI0->GENCS |= TSI_GENCS_TSIEN_MASK;     // Enable TSI module
+
+    for(cnt=0; cnt < total_electrode; cnt++)  // Get Counts when Electrode not pressed
+    {
+        TSI0->DATA = ((elec_array[cnt] << TSI_DATA_TSICH_SHIFT) );
+        TSI0->DATA |= TSI_DATA_SWTS_MASK;
+        while(!(TSI0->GENCS & TSI_GENCS_EOSF_MASK));
+        TSI0->GENCS |= TSI_GENCS_EOSF_MASK;
+        gu16Baseline[cnt] = (TSI0->DATA & TSI_DATA_TSICNT_MASK);
+    }
+
+    TSI0->GENCS &= ~TSI_GENCS_TSIEN_MASK;    // Disable TSI module
+    TSI0->GENCS |= TSI_GENCS_TSIIEN_MASK;     // Enale TSI interrupt
+    if(trigger_backup)                      // Restore trigger mode
+        TSI0->GENCS |= TSI_GENCS_STM_MASK;
+    else
+        TSI0->GENCS &= ~TSI_GENCS_STM_MASK;
+
+    TSI0->GENCS |= TSI_GENCS_TSIEN_MASK;     // Enable TSI module
+
+    TSI0->DATA = ((elec_array[0]<<TSI_DATA_TSICH_SHIFT) );
+    TSI0->DATA |= TSI_DATA_SWTS_MASK;
+}
+
+void TSISensor::sliderRead(void ) {
+    if(end_flag) {
+        end_flag = 0;
+        if((gu16Delta[0] > gu16Threshold[0])||(gu16Delta[1] > gu16Threshold[1])) {
+            SliderPercentegePosition[0] = (gu16Delta[0]*100)/(gu16Delta[0]+gu16Delta[1]);
+            SliderPercentegePosition[1] = (gu16Delta[1]*100)/(gu16Delta[0]+gu16Delta[1]);
+            SliderDistancePosition[0] = (SliderPercentegePosition[0]* SLIDER_LENGTH)/100;
+            SliderDistancePosition[1] = (SliderPercentegePosition[1]* SLIDER_LENGTH)/100;
+            AbsolutePercentegePosition = ((100 - SliderPercentegePosition[0]) + SliderPercentegePosition[1])/2;
+            AbsoluteDistancePosition = ((SLIDER_LENGTH - SliderDistancePosition[0]) + SliderDistancePosition[1])/2;
+         } else {
+            SliderPercentegePosition[0] = NO_TOUCH;
+            SliderPercentegePosition[1] = NO_TOUCH;
+            SliderDistancePosition[0] = NO_TOUCH;
+            SliderDistancePosition[1] = NO_TOUCH;
+            AbsolutePercentegePosition = NO_TOUCH;
+            AbsoluteDistancePosition = NO_TOUCH;
+         }
+    }
+}
+
+float TSISensor::readPercentage() {
+    sliderRead();
+    return (float)AbsolutePercentegePosition/100.0;
+}
+
+uint8_t TSISensor::readDistance() {
+    sliderRead();
+    return AbsoluteDistancePosition;
+}
+
+uint16_t TSISensor::readValue(uint8_t index)
+{
+    return gu16TSICount[index];
+}
+
+static void changeElectrode(void)
+{
+    int16_t u16temp_delta;
+
+    gu16TSICount[ongoing_elec] = (TSI0->DATA & TSI_DATA_TSICNT_MASK);          // Save Counts for current electrode
+    u16temp_delta = gu16TSICount[ongoing_elec] - gu16Baseline[ongoing_elec];  // Obtains Counts Delta from callibration reference
+    if(u16temp_delta < 0)
+        gu16Delta[ongoing_elec] = 0;
+    else
+        gu16Delta[ongoing_elec] = u16temp_delta;
+
+    //Change Electrode to Scan
+    if(total_electrode > 1)  
+    {
+        if((total_electrode-1) > ongoing_elec)
+            ongoing_elec++;
+        else
+            ongoing_elec = 0;
+
+        TSI0->DATA = ((elec_array[ongoing_elec]<<TSI_DATA_TSICH_SHIFT) );
+        TSI0->DATA |= TSI_DATA_SWTS_MASK;
+    }
+}
+
+void tsi_irq(void)
+{
+    end_flag = 1;
+    TSI0->GENCS |= TSI_GENCS_EOSF_MASK; // Clear End of Scan Flag
+    changeElectrode();
+}
diff --git a/yue/TSI/TSISensor.h b/yue/TSI/TSISensor.h
new file mode 100644 (file)
index 0000000..8d24cac
--- /dev/null
@@ -0,0 +1,73 @@
+/* Freescale Semiconductor Inc.
+ * (c) Copyright 2004-2005 Freescale Semiconductor, Inc.
+ * (c) Copyright 2001-2004 Motorola, Inc. 
+ *
+ * mbed Microcontroller Library
+ * (c) Copyright 2009-2012 ARM Limited.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy of this software
+ * and associated documentation files (the "Software"), to deal in the Software without
+ * restriction, including without limitation the rights to use, copy, modify, merge, publish,
+ * distribute, sublicense, and/or sell copies of the Software, and to permit persons to whom the
+ * Software is furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in all copies or
+ * substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING
+ * BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND
+ * NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM,
+ * DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+ * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
+ */
+
+#ifndef TSISENSOR_H
+#define TSISENSOR_H
+
+/**
+* TSISensor example
+*
+* @code
+* #include "mbed.h"
+* #include "TSISensor.h"
+* 
+* int main(void) {
+*     PwmOut led(LED_GREEN);
+*     TSISensor tsi;
+*     
+*     while (true) {
+*         led = 1.0 - tsi.readPercentage();
+*         wait(0.1);
+*     }
+* }
+* @endcode
+*/
+class TSISensor {
+public:
+    /**
+     *   Initialize the TSI Touch Sensor
+     */
+    TSISensor();
+
+    /**
+     * Read Touch Sensor percentage value
+     *
+     * @returns percentage value between [0 ... 1]
+     */
+    float readPercentage();
+
+    /**
+     * Read Touch Sensor distance
+     *
+     * @returns distance in mm. The value is between [0 ... 40]
+     */
+    uint8_t readDistance();
+    uint16_t readValue(uint8_t);
+    void TSISensor_reset(void);
+
+private:
+    void sliderRead(void);
+    void selfCalibration(void);
+};
+
+#endif
diff --git a/yue/main.cpp b/yue/main.cpp
new file mode 100644 (file)
index 0000000..fc45431
--- /dev/null
@@ -0,0 +1,188 @@
+#include "mbed.h"
+#include "TSISensor.h"          // Touch Sensor
+#include "MAG3110.h"            // Magnetic Sensor
+#include "MMA8451Q.h"           // AcceleroMeter
+
+
+#define MMA8451_I2C_ADDRESS (0x1d<<1)   // acc sensor address
+#define TIME_ACCURACY 0.1
+#define LIGHT_SNS_DEFAULT 1             // default collecting interval in seconds
+#define ACC_SNS_DEFAULT 1
+#define MAG_SNS_DEFAULT 1
+#define TOUCH_SNS_DEFAULT 1
+
+// Define Devices & Pins
+MMA8451Q accSensor(PTE25, PTE24, MMA8451_I2C_ADDRESS);
+TSISensor touchSensor;
+Serial serial(USBTX, USBRX);
+Ticker clock1;
+AnalogIn lightSensor(PTE22);
+
+
+// Global Variables
+// Initial interval: in seconds
+float lightTmr = LIGHT_SNS_DEFAULT;
+float accTmr = ACC_SNS_DEFAULT;
+float magTmr = MAG_SNS_DEFAULT;
+float touchTmr = TOUCH_SNS_DEFAULT;
+
+
+bool lightEnable = true;
+bool accEnable = true;
+bool magEnable = true;
+bool touchEnable = true;
+
+void clock1_interrupt();
+void serialRx_interrupt();
+void sendLightInfo();
+void sendAccInfo();
+void sendMagInfo();
+void sendTouchInfo();
+
+
+int main() {
+    // Initialization
+    // Interruption Declarations
+    clock1.attach(&clock1_interrupt, TIME_ACCURACY);    // maximun accuracy be 0.1s
+    serial.attach(&serialRx_interrupt, Serial::RxIrq);  // receive interrupt for serialS
+
+    serial.printf("\r\n============= Start of the program ============\r\n");
+    while(1){
+        wait(3);
+    }
+}
+
+
+/*---------------------------------------------------------------
+  ## Receive Interruption of the Serial ##
+  -> used to receive & process user command
+  -> and configure the board accordingly
+  ---------------------------------------------------------------*/
+void serialRx_interrupt(){
+    clock1.detach();                // close the interrupt
+    serial.printf("\r\n");
+
+    // Receive the Serial Input
+    float interval;
+    char buffer[255];
+    char temp[255];
+    char ch = serial.getc();
+    int i;
+    for (i=0 ; ch!='\n' && ch!='\r'; i++){
+        serial.putc(ch);
+        buffer[i] = ch;
+        ch = serial.getc();
+    }
+    buffer[i] = '\0';
+    serial.printf("\r\n");
+    // TODO: buffer -> lower case
+
+    // Process the Serial Input
+    // Set-Interval Command
+    if (strstr(buffer, "set")!=NULL && strstr(buffer, "int")!= NULL){
+        sscanf(buffer, "%*[^0123456789.]%s", temp);       // find the number in buffer
+        sscanf(temp, "%f", &interval);                    // translate into float
+        if (interval<0.1 || interval>5){
+            interval  = 1;
+        }
+        if (strstr(buffer, "acc")){
+            accTmr = interval;
+        }else if (strstr(buffer, "mag")){
+            magTmr = interval;
+        }else if (strstr(buffer, "light")){
+            lightTmr = interval;
+        }else if (strstr(buffer, "touch")){
+            touchTmr = interval;
+        }
+    }
+
+    // Stop Command
+    else if (strstr(buffer, "stop")!= NULL){
+        if (strstr(buffer, "acc")){
+            accEnable = false;
+            accTmr = ACC_SNS_DEFAULT;
+        }else if (strstr(buffer, "mag")){
+            magEnable = false;
+            magTmr = MAG_SNS_DEFAULT;
+        }else if (strstr(buffer, "light")){
+            lightEnable = false;
+            lightTmr = LIGHT_SNS_DEFAULT;
+        }else if (strstr(buffer, "touch")){
+            touchEnable = false;
+            touchTmr = TOUCH_SNS_DEFAULT;
+        }
+    }
+
+    // Start Command
+    else if (strstr(buffer, "start")!=NULL){
+        if (strstr(buffer, "acc") && !accEnable){
+            accEnable = true;
+            accTmr = ACC_SNS_DEFAULT;
+        }else if (strstr(buffer, "mag") && !magEnable){
+            magEnable = true;
+            magTmr = MAG_SNS_DEFAULT;
+        }else if (strstr(buffer, "light") && !lightEnable){
+            lightEnable = true;
+            lightTmr = LIGHT_SNS_DEFAULT;
+        }else if (strstr(buffer, "touch") && !touchEnable){
+            touchEnable = true;
+            touchTmr = TOUCH_SNS_DEFAULT;
+        }
+    }
+    clock1.attach(&clock1_interrupt,0.1);
+}
+
+
+void clock1_interrupt(){
+    static int accCnt;
+    static int magCnt;
+    static int lightCnt;
+    static int touchCnt;
+
+    accCnt++;
+    magCnt++;
+    lightCnt++;
+    touchCnt++;
+
+    // TODO: send data through Serial
+    if (lightEnable && (lightCnt<0 || lightCnt>=lightTmr/TIME_ACCURACY)){
+        sendLightInfo();
+        lightCnt = 0;
+    }
+    /*if (magEnable){
+        sendMagInfo();
+    }*/
+    if (touchEnable && (touchCnt<0 || touchCnt>=touchTmr/TIME_ACCURACY)){
+        sendTouchInfo();
+        touchCnt = 0;
+    }
+    if (accEnable && (accCnt<0 || accCnt>=accTmr/TIME_ACCURACY)){
+        sendAccInfo();
+        accCnt = 0;
+    }
+
+}
+
+void sendLightInfo(){
+    serial.printf("[LGT] Light Intensity=%f\r\n", lightSensor.read());
+}
+
+
+void sendAccInfo(){
+    // get acc data
+    float accX = accSensor.getAccX();
+    float accY = accSensor.getAccY();
+    float accZ = accSensor.getAccZ();
+
+    // send acc data
+    serial.printf("[ACC] accX=%-2.4f accY=%-2.4f accZ=%-2.4f\r\n",accX,accY,accZ);
+}
+
+void sendTouchInfo(){
+    // get data
+    float touchForce = touchSensor.readPercentage();
+    float distance = touchSensor.readDistance();
+
+    // send data
+    serial.printf("[TCH] Force=%0.4f Distance=%2.2f\r\n", touchForce, distance);
+}
diff --git a/yue/makefile b/yue/makefile
new file mode 100644 (file)
index 0000000..55b6de4
--- /dev/null
@@ -0,0 +1,10 @@
+PROG = mbed
+OBJS = main.o MAG3110/MAG3110.o MMA8451Q/MMA8451Q.o TSI/TSISensor.o
+
+CPPFLAGS = -IMAG3110 -IMMA8451Q -ITSI
+LDFLAGS  = -lm
+
+default: info install
+
+-include ../config.mk
+-include ../common.mk