Full version for Rev C Hardware Also needs modified USBDevice driver in SV repository

Dependencies:   MODSERIAL USBDevice_for_Rev_C_HW mbed

Fork of mbed_sv_firmware_with_init by Bob Recny

main.cpp

Committer:
bob_tpc
Date:
2015-06-23
Revision:
24:41e424031aba
Parent:
23:52504c8f63c5

File content as of revision 24:41e424031aba:

 /**
 * Copyright (c) 2015 The Positive Charge, LLC for Supervision, LLC
 * @file   main.cpp
 * @date   2015-06-04
 * @brief  Freescale KL25Z firmware for USB-RFID adapter
 *
 * This firmware provides communication from a PC's USB host port to the following peripherals:
 *  RFID-FE over UART - SuperVision RFID reader module
 *  VL6180X over I2C - ST Microelectronics proximity and ambient light sensor
 *  GPIO - two LEDs and several control signals for the RFID module
 *  EEPROM - over I2C - Generic 24LC16B (untested since first revision prototype hardware does not have an EEPROM)
 *
 * Revision History
 * 2014-11-01
 * For Rev A Hardware - No EEPROM, single-byte GPIO
 *
 * 2015-03-01
 * For Rev B and C Hardware - Includes EEPROM, single-byte GPIO
 *
 * 2015-06-04
 * For Rev C Hardware - Includes EEPROM, 2-byte GPIO allows extra pins on LED connector to be used.
 *                    - Includes EEPROM storage of USB string descriptors and RFID command for Proximity interrupt
 *                    - Includes USB initialization update and added code to send RFID command on Proximity interrupt
 *
 */

// mbed.org headers
#include "mbed.h"                       // main mbed.org libraries
#include "iostream"
#include "string"
#include "USBDevice.h"
#include "USBSerial.h"                  // USB CDC drivers
#include "MODSERIAL.h"                  // UART drivers - MODSERIAL allows block writes compared to the mbed driver

// Supervision-specific headers
#include "SV_USBConfig.h"               // Default USB strings for initial power-up.
#include "ProxInit.h"                   // VL6180X default initial values - *not* calibrated

// Constants
#define LEDON       0                   // Low active for LEDs - turns LED on
#define LEDOFF      1                   // Low active for LEDs - turns LED off

#define TRUE        1                   // Boolean true and false
#define FALSE       0

// Error return values
#define ERR_NONE                0x00    // Success
#define ERR_CDC_BAD_CMD         0x01    // First byte of PC to USB board needs to be 0xBB, 0xCC, 0xDD or 0xEE;
#define ERR_CDC_NO_TX_ENDMARK   0xA1    // message for no endmark on message to PC
#define ERR_UART_NOT_WRITEABLE  0xB1    // UART has no buffer space
#define ERR_UART_NOT_READABLE   0xB2    // UART has no buffer space
#define ERR_UART_NO_TX_ENDMARK  0xB3    // message for UART has no 0x7E end-mark
#define ERR_UART_NO_RX_ENDMARK  0xB4    // message received from UART has no end-mark
#define ERR_I2C_NOT_WRITEABLE   0xC1    // I2C has no buffer space
#define ERR_I2C_NO_TX_ENDMARK   0xC2    // message for I2C has no 0x7E end-mark
#define ERR_I2C_NO_RX_ENDMARK   0xC3    // message received from I2C has no end-mark
#define ERR_I2C_WRITE_TOO_LARGE 0x16    // message for I2C write is too large (16 bytes max)
#define ERR_NOT_IMPLEMENTED     0xFF    // method has not yet been implemented

// I2C addresses and parameters
#define PROX                    (0x29 << 1) // default I2C address of VL6180X, shift into upper 7 bits
#define EEPROM                  (0xA0)  // default I2C address of EEPROM, already shifted
#define I2CRATE                 400000  // I2C speed
#define I2CRATE1M               1000000 // EEPROM can run at 1Mbps

// UART-RFID baud rate
#define RFIDBAUD                115200  // RFID-FE board default rate = 115.2Kbps
#define BUFFERSIZE              128     // default buffer sizes
#define RFIDLENLOW              5       // RFID message length location (length is 2 bytes)

// Peripherals
USBSerial cdc;                          // CDC Class USB-Serial adapter.  Needs custom INF, but uses existing Windows CDC drivers.
MODSERIAL uart(PTA2, PTA1);             // UART port connected to RFID-FE board
I2C i2c(PTB1, PTB0);                    // I2C port connected to VL6180X and EEPROM - note addresses above)

// GPIO signals
DigitalOut led_err(PTC1);               // Red LED shows error condition (active low)
DigitalOut led_com(PTC2);               // Yellow LED shows communication activity (active low)
DigitalOut rfid_int(PTD4);              // RFID FE power control (active high)
DigitalOut rfid_isp(PTD5);              // RFID FE In-System Programming (active high)
DigitalOut rfid_rst(PTD6);              // RFID FE Reset (active high)
DigitalOut rfid_pwr(PTE30);             // RFID power switch on USB board (active high for prototype 1, low for all others)
DigitalIn rfid_hot(PTE0);               // RFID over-current detection on USB board power switch (active low)
InterruptIn prox_int(PTD7);             // Proximity sensor interrupt (active low)
DigitalOut ee_wp(PTC5);                 // EEPROM Write Protect (active high)

DigitalInOut gpio_0(PTC3);              // Extra GPIO on LED connector, pin 6
DigitalInOut gpio_1(PTC4);              // Extra GPIO on LED connector, pin 7
DigitalOut gpio_7(PTA4);                // Extra GPIO output on LED connector, pin 3 - pin supports PWM for buzzer, not implemented here

// global buffers & variables
uint8_t led_com_state = LEDOFF;         // initial LED state
uint8_t prox_irq_state = 0;             // interrupt state passed from service routine
uint8_t usb_irq_state = 0;              // interrupt state passed from service routine
uint8_t gpio_values = 0x00;             // register to read GPIO values
uint8_t cdc_buffer_rx[BUFFERSIZE];      // buffers for cdc (USB-Serial port on PC)
uint8_t cdc_buffer_tx[BUFFERSIZE];
uint8_t uart_buffer_rx[BUFFERSIZE];     // buffers for uart (RFID-FE board)
uint8_t uart_buffer_tx[BUFFERSIZE];
uint8_t gpio_buffer[BUFFERSIZE];        // buffer for GPIO messages

char i2c_buffer[BUFFERSIZE];            // buffer for I2C devices - Proximity sensor and EEPROM - up to BUFFERSIZE bytes data payload for EEPROM, up to 4 for proximity
char prox_irq_msg[BUFFERSIZE];          // buffer for automatic RFID message on proximity interrupt

int i, j;                               // general index variables
int status = 0x00;                      // return value

// USB config descriptor strings
// These are held in SV_USBConfig.h, and only used during initial bring-up after manufacturing

char mfg_str[0x2E] = {SV_MFG};          // Default USB strings - Manufacturer
char mfg_str_cnt = SV_MFG_CNT;
char ser_str[0x2E] = {SV_SER};          // Default USB strings - Serial Number
char ser_str_cnt = SV_SER_CNT;
char des_str[0x3E] = {SV_DES};          // Default USB strings - Product Description
char des_str_cnt = SV_DES_CNT;

/**
 * @name    get_id
 * @brief   Reads KL25Z unique ID (80 bits) and converts it to a string for use as the USB Serial Number
 *
 * @param [out] char* id = USB Serial Number string
 */
void get_id(void)
{
    uint32_t val;
    int i;
    int len = 4;
 
    val = SIM->UIDMH;
    for (i = (2*len-2); i >= 0; i-=2){
        char byte = (char)(val & 0xF);

        if(byte < 0xA){
            ser_str[i] = (char)(byte + '0');
        }
        else{
            byte -= 0xA;
            ser_str[i] = (char)(byte + 'A');
        }
        val >>= 4;
    }
    
    val = SIM->UIDML;
    for (i = (2*len-2); i >= 0; i-=2){
        char byte = (char)(val & 0xF);

        if(byte < 0xA){
            ser_str[i+8] = (char)(byte + '0');
        }
        else{
            byte -= 0xA;
            ser_str[i+8] = (char)(byte + 'A');
        }
        val >>= 4;
    }
    
    val = SIM->UIDL;
    for (i = (2*len-2); i >= 0; i-=2){
        char byte = (char)(val & 0xF);

        if(byte < 0xA){
            ser_str[i+16] = (char)(byte + '0');
        }
        else{
            byte -= 0xA;
            ser_str[i+16] = (char)(byte + 'A');
        }
        val >>= 4;
    }

}



// These next functions are modified from the original USBDevice.cpp and USBCDC.cpp mbed drivers
// in order to allow custom USB descriptor strings.

/**
 * @name    USBDevice::stringImanufacturerDesc
 * @name    USBDevice::stringIserialDesc
 * @name    USBDevice::stringIproductDesc
 * @name    USBCDC::stringIproductDesc
 * @brief   Sets custom USB Config Descriptor Strings
 *
 *  These methods are modified from the original to allow custom USB config descriptor strings.
 *  The original (in USBDevice.cpp and USBCDC.cpp) are hard-coded for generic mbed.org values 
 *  The values used in these methods are read from the EEPROM.  Especially important is allowing
 *  a custom USB Serial Number, which will be written to the EEPROM during the factory test.
 *
 * @param [in] none
 * @retval stringImanufacturerDescriptor
 * @retval stringIserialDescriptor
 * @retval stringIproductDescriptor
 * @retval stringIproductDescriptor
 */


// MODIFIED to allow custom strings
uint8_t * USBDevice::stringImanufacturerDesc() {
    static uint8_t stringImanufacturerDescriptor[0x30];
    stringImanufacturerDescriptor[0] = mfg_str_cnt;
    stringImanufacturerDescriptor[1] = STRING_DESCRIPTOR;
    for (int i = 0; i < sizeof(mfg_str); i++){
        stringImanufacturerDescriptor[i+2] = mfg_str[i];
    }
    return stringImanufacturerDescriptor;
}

// MODIFIED to allow custom strings

uint8_t * USBDevice::stringIserialDesc() {
    static uint8_t stringIserialDescriptor[0x30];
    
    // Read KL25Z ID and set to USB serial number string
    get_id();                                                   // Read the unique ID from the KL25Z
    ser_str_cnt = 26;                                           // 12 bytes of ID *2 for Unicode, plus 2 to include the length and USB string type

    stringIserialDescriptor[0] = ser_str_cnt;
    stringIserialDescriptor[1] = STRING_DESCRIPTOR;
    for (int i = 0; i < sizeof(ser_str); i++){
        stringIserialDescriptor[i+2] = ser_str[i];
    }
    return stringIserialDescriptor;
}

// MODIFIED to allow custom strings
uint8_t * USBDevice::stringIproductDesc() {
    static uint8_t stringIproductDescriptor[0x40];
    stringIproductDescriptor[0] = des_str_cnt;
    stringIproductDescriptor[1] = STRING_DESCRIPTOR;
    for (int i = 0; i < sizeof(des_str); i++){
        stringIproductDescriptor[i+2] = des_str[i];
    }
    return stringIproductDescriptor;
}


// MODIFIED to allow custom strings
uint8_t * USBCDC::stringIproductDesc() {
    static uint8_t stringIproductDescriptor[0x40];
    stringIproductDescriptor[0] = des_str_cnt;
    stringIproductDescriptor[1] = STRING_DESCRIPTOR;
    for (int i = 0; i < sizeof(des_str); i++){
        stringIproductDescriptor[i+2] = des_str[i];
    }
    return stringIproductDescriptor;
}

/**
 * @name    prox_irq
 * @brief   Sets interrupt variable for use in the main loop.
 * The interrupt is triggered by the VL6180X GPIO1 (IRQ output)
 *
 * @param [in] none
 * @param [out] prox_irq_state = 1 indicates an interrupt occured.
 */
void prox_irq(void)
{
    prox_irq_state = 1;
    led_com.write(LEDON);                                           // Turn on COM LED until interrupt is serviced
}

/**
 * @name    usb_irq
 * @brief   Sets interrupt variable for use in the main loop.
 * The interrupt is triggered when the host PC has sent data to the CDC port.
 *
 * @param [in] none
 * @param [out] usb_irq_state = 1 indicates an interrupt occured.
 */
void usb_irq(void)
{
    usb_irq_state = 1;
}

/**
 * @name    init_periph
 * @brief   Initializes the KL25Z peripheal interfaces
 * KL25Z interfaces:
 *  USB - Initializes USB config descriptors
 *  UART - Connects to SuperVision RFID-FE module
 *  I2C - Configures to the ST VL6180X proximity/ambient light sensor device 
 *  I2C - Reads configuration data from EEPROM
 *  GPIO - Includes two LEDs and signals to control RFID reader.
 *
 * @param [in] none
 * @param [out] error status (0 = no error)
 *
 * @retval error state
 */
int init_periph(void)
{
    int i2c_err;                                                    // return value
    char temploc = 0x00;                                            // temporary values
    char temp[] = {0,0};
    char i2c_page = 0;
    char prox_ee[254] = {0};                                        // buffer for Proximity initialization values stored
                                                                    // in EEPROM, especially the cover glass calibration
    // Set up peripherals on KL25Z
    // Prox & EEPROM
    led_err.write(LEDOFF);                                          // Start with leds
    led_com.write(LEDOFF);

    i2c.frequency(I2CRATE);                                         // I2C speed = 400Kbps
    ee_wp.write(0);                                                 // no write protection on EEPROM

  
    // Get the VL6180X register values from the ProxInit.h header and program them to the Proximity Sensor (from VL6180X app notes)

    for (i = 0; i < sizeof(proxinit); i += 3){                      // Initialize VL6180X with default values, calibration data sent later
        i2c_err = i2c.write(PROX, &proxinit[i], 3, 0);              // I2C Address, pointer to buffer, number of bytes (for index + data), stop at end.
                                                                    // also includes taking off the "Fresh out of Reset" flag.
        if (i2c_err){
            led_err.write(LEDON);                                   // Turn on both LEDs
            led_com.write(LEDON);                                   // We can't write to the proximity sensor
            return i2c_err;
        }
    }
    
    // Get Supervision-specific register values and program them to the Proximity Sensor (calibration, other operating features)
    
    i2c_page = EEPROM | 1 << 1;                                     // set EEPROM page = bank 1
    temploc = 0;
    i2c.write(i2c_page, &temploc, 1, 1);                            // i2c address+bank 1, memory index, 1 byte (just index), no stop at end.
    i2c.read(i2c_page, temp, 2, 0);                                 // i2c address+bank 1, variable location, 2 bytes (just data), stop at end.
    
    if ((temp[0] == 'S') && (temp[1] == 'V')) {
        led_com.write(LEDON);
        // Read values
        temploc = 0x02;                                             // Values start here.  Since this section is mostly one-byte values with two-byte
                                                                    //                     addresses, 2- and 4-byte registers are individually addressed    
        i2c.write(i2c_page, &temploc, 1, 1);                        // i2c address+bank 1, location 2, 1 byte, no stop at end - read the whole bank
        i2c.read(i2c_page, prox_ee, sizeof(prox_ee), 0);            // i2c address+bank 1, buffer location, 1 byte, stop at end
        for (i = 0; i < sizeof(prox_ee); i += 3){                   // Initialize VL6180X with default values, calibration data sent later
            if ((prox_ee[i] == 0xFF) && (prox_ee[i+1] == 0xFF)){
                break;                                              // No more values are in the EEPROM (blank / erased = 0xFF)
            }
            else {
                i2c_err = i2c.write(PROX, &prox_ee[i], 3, 0);       // I2C Address, pointer to buffer, number of bytes (for index + data), stop at end.
                                                                    // also includes taking off the "Fresh out of Reset" flag.
                if (i2c_err){
                    led_err.write(LEDON);                           // Turn on both LEDs
                    led_com.write(LEDON);                           // We can't write to the proximity sensor
                    return i2c_err;
                }
            }
        }
        led_com.write(LEDOFF);
    }

    // Enable the Proximity interrupt
    prox_int.mode(PullUp);                                          // pull up proximity sensor interrupt at MCU
    prox_int.fall(&prox_irq);                                       // VL6180X interrupt is low active
    prox_int.enable_irq();                                          // Enable proximity interrupt inputs

    // "Fresh-out-of-reset" register was automatically set to 0x01 after boot
    prox_ee[0] = 0x00;                                              
    prox_ee[1] = 0x16;
    prox_ee[2] = 0x00;
    i2c.write(PROX, prox_ee, 3, 0);                                 // Remove "Fresh out of Reset" flag to allow normal operation

    cdc.attach(&usb_irq);                                           // Attach USB interrupt
    usb_irq_state = 0;                                              // Ensure interrupt flag is not set after setup
  
    // RFID
    uart.baud(RFIDBAUD);                                            // RFID-FE baud rate

    rfid_int = 0;                                                   // RFID FE power control (active high)
    rfid_isp = 0;                                                   // RFID FE In-System Programming (active high)
    rfid_rst = 1;                                                   // RFID FE Reset (active high)
    rfid_pwr = 0;                                                   // RFID power switch on USB board (active low for all others)
    wait(0.25);                                                     // wait 250ms before...
    rfid_rst = 0;                                                   // ... taking RFID out of reset
    wait(0.25);

    while(!uart.readable()) {                                       // wait for RESET message from RFID
        led_err.write(LEDON);                                       // flash LED until it arrives
        wait(0.1);                                                  // This is a good way to see if the RFID cable is properly seated
        led_err.write(LEDOFF);
        wait(0.1);
    }

    uart.txBufferFlush();                                           // clear out UART buffers - we don't need the reset message
    uart.rxBufferFlush();

    // LEDs                                                         // Cycle through the LEDs.
    led_err.write(LEDON);
    led_com.write(LEDON);
    wait(0.5);
    led_err.write(LEDOFF);
    wait(0.5);
    led_com.write(LEDOFF);

    return ERR_NONE;
}

/**
 * @name    rfid_wr
 * @brief   Forwards command to RFID reader
 *
 * RFID reader is connected to the KL25Z UART interface.  The host PC will have a USB CDC class COM port device driver.
 * The host PC sends the RFID command over the COM port.  Messages destined for the RFID reader (0xBB leading byte) are
 * forwarded as-is to the RFID reader.  The reader then responds in kind.  All RFID commands are described in the
 * RFID-FE module manual.
 *
 * @param [out] uart_buffer_tx - messages to the RFID reader
 *
 * @retval ERR_NONE                No error
 * @retval ERR_UART_NOT_WRITEABLE  UART has no buffer space
 * @retval ERR_UART_NO_TX_ENDMARK  message for UART has no 0x7E end-mark
 * @example
 * BB 00 03 00 01 02 7E 2E C9 = read
 */
int rfid_wr(void)
{
    int em_pos = 0;

    for (i = 0; i < sizeof(uart_buffer_tx); i++) {
        if (uart_buffer_tx[i] == 0x7E) em_pos = (i + 1);            // allows 0x7E to appear in the data payload - uses last one for end-mark
    }

    if (em_pos == 0) {
        led_err.write(LEDON);                                       // end mark never reached
        return ERR_UART_NO_TX_ENDMARK;
    }

    if (!uart.writeable()) {
        led_err.write(LEDON);
        return ERR_UART_NOT_WRITEABLE;                              // if no space in uart, return error
    }

    for (i = 0; i < (em_pos + 2); i++) {
        uart.putc(uart_buffer_tx[i]);                               // send uart message
    }

    return ERR_NONE;
}

/**
 * @name    prox_msg_wr
 * @brief   Forwards command to VL6180X sensor
 *
 * Proximity/ALS reader is connected to the KL25Z I2C interface.
 * The host PC sends the sensor command over the COM port.  Messages destined for the proximity/ALS sensor (0xCC leading byte) are
 * forwarded to the proximity/ALS sensor after removing the leading byte and trailing bytes (0x7E endmark plus 2 bytes).
 * The sensor then responds in kind.  Firmware re-attaches the leading 0xCC and trailing bytes before sending the response over the
 * CDC port to the host PC.
 *
 * I2C-prox messages:
 * - 0xCC                (byte) leading value = 0xCC
 * - r/w#                (byte) 0 = write, 1 = read
 * - number of data bytes(byte) 0 to 32 (size of declared buffers)
 * - index               (2 bytes) 12-bit VL6801X register offset, high byte first
 * - data                (n bytes) number of data bytes noted above
 * - end_mark            (byte) 0x7E
 * - dummy               (2 bytes) values are don't-care - fillers for RFID CRC bytes
 *
 * Multiple registers can be read or written with single prox_msg_rd() or prox_msg_wr().  Location address increments for each byte.
 * VL6180X registers are defined in the sensor datasheet.
 *
 * @param [in] i2c_buffer - messages to and from the VL6180X and EEPROM
 *
 * @retval 0            No error
 * @retval 1            I2C bus has NAK'd / failure
 *
 * @param [in/out] i2c_buffer - messages to and from the i2c bus - see above
 *
 */
int prox_msg_wr()                                                   // write proximity I2C register
{
    int i2c_err;
    i2c_err = i2c.write(PROX, &i2c_buffer[3], i2c_buffer[2] + 2, 0);// I2C Address, pointer to buffer, number of bytes (for index + data), stop at end.
    while (i2c.write(PROX, 0, 0, 0));         // wait until write is done (PROX will ACK = 0 for single byte i2c.write)

    return i2c_err;                                                 // 0 = ACK received, 1 = NAK/failure
}

/**
 * @name    prox_msg_rd
 * @brief   retrieves response from VL6180X sensor
 *
 * Proximity/ALS reader is connected to the KL25Z I2C interface.
 * The host PC sends the sensor command over the COM port.  Messages destined for the proximity/ALS sensor (0xCC leading byte) are
 * forwarded to the proximity/ALS sensor after removing the leading byte and trailing bytes (0x7E endmark plus 2 bytes).
 * The sensor then responds in kind.  Firmware re-attaches the leading 0xCC and trailing bytes before sending the response over the
 * CDC port to the host PC.
 *
 * I2C-prox messages:
 * - 0xCC                (byte) leading value = 0xCC
 * - r/w#                (byte) 0 = write, 1 = read
 * - number of data bytes(byte) 0 to 32 (size of declared buffers)
 * - index               (2 bytes) 12-bit VL6801X register offset, high byte first
 * - data                (n bytes) number of data bytes noted above
 * - end_mark            (byte) 0x7E
 * - dummy               (2 bytes) values are don't-care - fillers for RFID CRC bytes
 *
 * Multiple registers can be read or written with single prox_msg_rd() or prox_msg_wr().  Location address increments for each byte.
 * VL6180X registers are defined in the sensor datasheet.
 *
 * @param [in/out] i2c_buffer - messages to and from the i2c bus - see above
 *
 * @retval 0            No error
 * @retval 1            I2C bus has NAK'd / failure
 *
 *
 */
int prox_msg_rd()
{
    int i2c_err;
    i2c_err = i2c.write(PROX, &i2c_buffer[3], 2, 1);                // I2C Address, pointer to buffer (just the index), index, number of bytes (2 for index), no stop at end.
    i2c_err |= i2c.read(PROX, &i2c_buffer[5], i2c_buffer[2], 0);    // I2C Address, pointer to buffer (just the data), number of data bytes, stop at end.
    return i2c_err;                                                 // 0 = ACK received, 1 = NAK/failure
}

/**
 * @name    gpio_rd
 * @brief   retrieves instantaneous value of GPIO pins
 *
 * GPIO signals are defined directly off of the KL25Z.
 * The host PC sends the GPIO command over the COM port.  With a 0xDD leading byte in the message, the state of the GPIO signals are read and returned.
 * This allows a read-modify-write GPIO sequence.
 *
 * GPIO messages:
 * - 0xDD                (byte) leading value = 0xDD
 * - r/w#                (byte) 0 = write, 1 = read
 * - data                (2 bytes) see below
 * - end_mark            (byte) 0x7E
 * - dummy               (2 bytes) values are don't-care - fillers for RFID CRC bytes
 *
 * GPIO data bits - First Byte
 * - 0 LED - Error           0 = on, 1 = off
 * - 1 LED - Comm state      0 = on, 1 = off
 * - 2 RFID interrupt input  0 = off, 1 = on (inverted in h/w)
 * - 3 RFID in-system-prog   0 = off, 1 = on (inverted in h/w)
 * - 4 RFID reset            0 = off, 1 = on (inverted in h/w)
 * - 5 RFID power enable     for first prototype, 0 = off, 1 = on / for production, 0 = on, 1 = off
 * - 6 RFID over-current     0 = overcurrent detected, 1 = OK
 * - 7 Proximity interrupt   0 = interrupt, 1 = idle (This pin may not return anything meaningful here.  The interrupt is edge triggered).
 *
 * GPIO data bits - Second Byte
 * - 0 GPIO on pin 6 of LED connector - I/O
 * - 1 GPIO on pin 7 of LED connector - I/O
 * - 2-6 - unused bits, output don't care, input read as zero
 * - 7 GPIO on pin 3 of LED connector - OUTPUT only, inverted logic, open drain with 1K pull-up, read as zero
 *
 * @param [in/out] gpio_buffer - GPIO states
 *
 * @retval 0            No error
 *
 */

int gpio_rd()
{
    gpio_buffer[2]  = ( led_err.read()        & 0x01);              // read first byte of the GPIO pins
    gpio_buffer[2] |= ((led_com_state   << 1) & 0x02);              // use of led_com_state allows the LED to remain ON in the main loop if desired
    gpio_buffer[2] |= ((rfid_int.read() << 2) & 0x04);
    gpio_buffer[2] |= ((rfid_isp.read() << 3) & 0x08);
    gpio_buffer[2] |= ((rfid_rst.read() << 4) & 0x10);
    gpio_buffer[2] |= ((rfid_pwr.read() << 5) & 0x20);
    gpio_buffer[2] |= ((rfid_hot.read() << 6) & 0x40);
    gpio_buffer[2] |= ((prox_int.read() << 7) & 0x80);

    gpio_buffer[3]  = (   gpio_0.read()       & 0x01);              // read second byte of the GPIO pins
    gpio_buffer[3] |= ((  gpio_1.read() << 1) & 0x02);
    gpio_buffer[3] |= ((              0 << 2) & 0x04);              // bits 2-7 always return zero
    gpio_buffer[3] |= ((              0 << 3) & 0x08);
    gpio_buffer[3] |= ((              0 << 4) & 0x10);
    gpio_buffer[3] |= ((              0 << 5) & 0x20);
    gpio_buffer[3] |= ((              0 << 6) & 0x40);
    gpio_buffer[3] |= ((              0 << 7) & 0x80);
    return ERR_NONE;
}


/**
 * @name    gpio_wr
 * @brief   sets value of GPIO pins
 *
 * GPIO signals are defined directly off of the KL25Z.
 * The host PC sends the GPIO command over the COM port.  With a 0xDD leading byte in the message, the state of the GPIO signals are read and returned.
 * This allows a read-modify-write GPIO sequence.
 *
 * GPIO messages:
 * - 0xDD                (byte) leading value = 0xDD
 * - r/w#                (byte) 0 = write, 1 = read
 * - data                (2 bytes) see below
 * - end_mark            (byte) 0x7E
 * - dummy               (2 bytes) values are don't-care - fillers for RFID CRC bytes
 *
 * GPIO data bits - First Byte:
 * - 0 LED - Error           0 = on, 1 = off
 * - 1 LED - Comm state      0 = on, 1 = off
 * - 2 RFID interrupt input  0 = off, 1 = on (inverted in h/w)
 * - 3 RFID in-system-prog   0 = off, 1 = on (inverted in h/w)
 * - 4 RFID reset            0 = off, 1 = on (inverted in h/w)
 * - 5 RFID power enable     for first prototype, 0 = off, 1 = on / for production, 0 = on, 1 = off
 * - 6 RFID over-current     0 = overcurrent detected, 1 = OK
 * - 7 Proximity interrupt   0 = interrupt, 1 = idle (This pin may not return anything meaningful here.  The interrupt is edge triggered).
 *
 * GPIO data bits - Second Byte
 * - 0 GPIO on pin 6 of LED connector - I/O
 * - 1 GPIO on pin 7 of LED connector - I/O
 * - 2-6 - unused bits, output don't care, input read as zero
 * - 7 GPIO on pin 3 of LED connector - OUTPUT only, inverted logic, open drain with 1K pull-up, read as zero
 *
 * @param [in/out] gpio_buffer - GPIO states
 *
 * @retval 0            No error
 *
 */
int gpio_wr()
{
    if ((gpio_buffer[2] & 0x02) == 0x00) {                          // Set the desired state of the yellow LED
        led_com_state = LEDON;
    } else {
        led_com_state = LEDOFF;
    }
    led_err.write(gpio_buffer[2] & 0x01);                           // Write GPIO bits - first byte
    led_com.write(led_com_state);                                   // use of led_com_state allows the LED to remain ON in the main loop if desired
    rfid_int.write(gpio_buffer[2] & 0x04);
    rfid_isp.write(gpio_buffer[2] & 0x08);
    rfid_rst.write(gpio_buffer[2] & 0x10);
    rfid_pwr.write(gpio_buffer[2] & 0x20);

    gpio_0.write(gpio_buffer[3] & 0x01);                            // Write GPIO bits - second byte
    gpio_1.write(gpio_buffer[3] & 0x02);                            // Write GPIO bits - second byte
    gpio_7.write(gpio_buffer[3] & 0x80);                            // Write GPIO bits - second byte

    return ERR_NONE;
}


/**
 * @name    eeprom_msg_wr
 * @brief   writes data to the I2C EEPROM
 *
 * The EEPROM is connected to the KL25Z I2C interface.
 * The host PC sends the sensor command over the COM port.  Messages destined for the EERPOM (0xEE leading byte) are
 * forwarded to the EEPROM after removing the leading byte and trailing bytes (0x7E endmark plus 2 bytes).
 * Firmware re-attaches the leading 0xEE and trailing bytes before sending the response over the
 * CDC port to the host PC.
 *
 * I2C-EEPROM messages:
 * - 0xEE                (byte) leading value = 0xEE
 * - r/w#                (byte) 0 = write, 1 = read
 * - number of data bytes(byte) 0 to 16 bytes for write
 * - block               (byte) lower 3 bits are logically OR'd with the I2C address
 * - address             (byte) memory location within block
 * - data                (n bytes) number of data bytes noted above
 * - end_mark            (byte) 0x7E
 * - dummy               (2 bytes) values are don't-care - fillers for RFID CRC bytes
 *
 * Multiple memory locations can be read or written with single eeprom_msg_rd() or eeprom_msg_wr().  Location address increments for each byte.
 * Read/Write sequences are defined in the 24LC16B datasheet.
 *
 * This practically the the same as the proximity calls, except the index/location is only one byte and the block select is part of the I2C address byte.
 *
 * @param [in] i2c_buffer - messages to and from the VL6180X and EEPROM
 *
 * @retval 0            No error
 * @retval 1            I2C bus has NAK'd / failure
 * @retval ERR_I2C_WRITE_TOO_LARGE  buffer size too large
 *
 * @param [in/out] i2c_buffer - messages to and from the i2c bus - see above
 *
 */

int eeprom_msg_wr()                                                 // write proximity I2C register
{
    int i2c_err = ERR_NONE;
    char wr[2] = {0xFF, 0xFF};

    for (i = 0; i < i2c_buffer[2]; i++){                            // done with single-byte writes to avoid addressing wrap-around
        wr[0] = i2c_buffer[4]+i;
        wr[1] = i2c_buffer[5+i];
        i2c_err |= i2c.write((EEPROM | (i2c_buffer[3] << 1 )), wr, 2, 0);
        while ( (i2c.write(EEPROM | (i2c_buffer[3] << 1 )), 0, 0, 0));         // wait until write is done (EEPROM will ACK = 0 for single byte i2c.write)
        // I2C Address & block select, pointer to buffer, 2 bytes (address + one data), stop at end.
    }
    return i2c_err;                                                 // 0 = ACK received, 1 = NAK/failure
}

/**
 * @name    eeprom_msg_rd
 * @brief   read data from the I2C EEPROM
 * @note    EEPROM only availalbe on REV B and later
 *
 * The EEPROM is connected to the KL25Z I2C interface.
 * The host PC sends the sensor command over the COM port.  Messages destined for the EERPOM (0xEE leading byte) are
 * forwarded tjo the EEPROM after removing the leading byte and trailing bytes (0x7E endmark plus 2 bytes).
 * Firmware re-attaches the leading 0xEE and trailing bytes before sending the response over the
 * CDC port to the host PC.
 *
 * I2C-EEPROM messages:
 * - 0xEE                (byte) leading value = 0xEE
 * - r/w#                (byte) 0 = write, 1 = read
 * - number of data bytes(byte) 0 to 128 bytes for read (size of declared buffer)
 * - block               (byte) lower 3 bits are logically OR'd with the I2C address
 * - address             (byte) memory location within block
 * - data                (n bytes) number of data bytes noted above
 * - end_mark            (byte) 0x7E
 * - dummy               (2 bytes) values are don't-care - fillers for RFID CRC bytes
 *
 * Multiple memory locations can be read or written with single eeprom_msg_rd() or eeprom_msg_wr().  Location address increments for each byte.
 * Read/Write sequences are defined in the 24LC16B datasheet.
 *
 * This practically the the same as the proximity calls, except the index/location is only one byte and the block select is part of the I2C address byte.
 *
 * @param [in/out] i2c_buffer - messages to and from the VL6180X and EEPROM
 *
 * @retval [none]0            No error
 * @retval 1            I2C bus has NAK'd / failure
 *
 * @param [in/out] i2c_buffer - messages to and from the i2c bus - see above
 *
 */
int eeprom_msg_rd()
{
    int i2c_err;
    i2c_err = i2c.write((EEPROM | (i2c_buffer[3] << 1)), &i2c_buffer[4], 1, 1);
    // I2C Address & block select, pointer to buffer (just the index), index, number of bytes (for address + data), no stop at end.
    i2c_err |= i2c.read((EEPROM | (i2c_buffer[3] << 1)), &i2c_buffer[5], i2c_buffer[2], 0);
    // I2C Address & block select, pointer to buffer (just the data), number of data bytes, stop at end.
    return i2c_err;                                                 // 0 = ACK received, 1 = NAK/failure
}

/**
 * @name    clrcdctx
 * @brief   Clear CDC TX buffer
 *
 * @returns [none]
 */
void clrcdctx(void)
{
    for (i = 0; i < sizeof(cdc_buffer_tx); i++){
        cdc_buffer_tx[i] = 0x00;                                    // clear CDC tx buffer
    }    
}

/**
 * @name    clrcdcrx
 * @brief   Clear CDC RX buffer
 *
 * @returns [none]
 */
void clrcdcrx(void)
{
    for (i = 0; i < sizeof(cdc_buffer_rx); i++){
        cdc_buffer_rx[i] = 0x00;                                    // clear CDC tx buffer
    }    
}


/**
 * @name    main
 * @brief   Main firmware loop
 *
 * @returns [none]
 */
int main(void)
{
    int em_pos = 0;                                                 // end of message count - allows multiple 0x7e in message.
    char msgcount;
    char temploc;
    char autorange[] = {0x00, 0x18, 0x00};                          // Proximity sensor automatic measurement.  Set last byte = 0x03 to start
    char proxintclr[] = {0x00, 0x15, 0x07};                         // Clear proximity interrupt

    char i2c_addr = (EEPROM | (2 << 1));                            // EEPROM base address is 0xA0 (already shifted).  Bank 2 in use here, shifted for I2C addressing.

    init_periph();                                                  // initialize everything

    while(1) {                                                      // main loop
        led_com.write(led_com_state);                               // turn off communication LED unless it was specifically turned on by GPIO command
        if (prox_irq_state == 1) {                                  // process the proximity interrupt
            clrcdctx();


            if (prox_irq_msg[0] != 0xBB){                           // no message to send to RFID
                cdc_buffer_tx[0] = 0xFF;                            // just send a dummy message back to the host
                cdc_buffer_tx[1] = 0x7E;
                cdc_buffer_tx[2] = 0x0F;
                cdc_buffer_tx[3] = 0xF0;
                cdc.writeBlock(cdc_buffer_tx, 4);
                led_err.write(LEDON);                               // we shouldn't get here
            }
            else{
                msgcount = prox_irq_msg[2] + 6;                     // See RFID-FE manual for message construction
                for (i = 0; i < msgcount; i++) {
                    uart.putc(prox_irq_msg[i]);                     // send message to RFID-FE module for a single read
                }
            }
            prox_irq_state = 0;                                     // reset proximity interrupt state
            wait(0.5);                                              // wait 1/2 sec so the COM LED can be seen
            led_com.write(led_com_state);                           // turn off COM LED if not on by GPIO (it was turned on in the ISR)
            i2c.write(PROX, proxintclr, 3, 0);                      // i2c prox sensor, interrupt clear message, 3 bytes, stop at end

        }
        if (uart.readable()) {                                      // message availalbe from rfid (all responses (0x01) and broadcast (0x02))
            clrcdctx();
            int rfid_len = 0;
            led_com.write(LEDON);
            for (i = 0; i < (RFIDLENLOW); i++) {                    // Get first part of message to find out total count
                uart_buffer_rx[i] = uart.getc();                    // get a byte from rfid
            }
            rfid_len = ((uart_buffer_rx[i-2]<<8) + (uart_buffer_rx[i-1]));  // location of message length for RFID
            for (i = RFIDLENLOW; i < (RFIDLENLOW + rfid_len + 3); i++) { // get the reset of the message
                uart_buffer_rx[i] = uart.getc();                    // get a byte from rfid
            }
            for (i = 0; i < (RFIDLENLOW + rfid_len + 3); i++) {     // copy the message to the USB buffer
                cdc_buffer_tx[i] = uart_buffer_rx[i];
            }
            cdc.writeBlock(cdc_buffer_tx, (RFIDLENLOW + rfid_len + 3)); // send the RFID message to the PC
            led_com.write(led_com_state);
        }
        if (usb_irq_state == 1) {                                   // message available from PC
            usb_irq_state = 0;                                      // allow another USB interrupt 
            clrcdcrx();                                             // clear cdc RX buffer
            for (i = 0; i < sizeof(cdc_buffer_rx); i++) {
                if (cdc.readable()) cdc_buffer_rx[i] = cdc._getc(); // read data from USB side
            }
            if ((cdc_buffer_rx[0] == 'A') && (cdc_buffer_rx[1] == 'T')) { // check for Hayes command and ignore it
                    break;                                          // Linux systems will enumerate as ttyACMx
            }                                                       // and attempt to initialize the non-existent modem
            for (i = 0; i < sizeof(cdc_buffer_rx); i++) {
                if (cdc_buffer_rx[i] == 0x7E) {                     // check for rfid end mark in outbound message
                    em_pos = (i + 1);
                }
            }
            led_com.write(LEDON);                                   // Message received - turn on LED
            if (em_pos == 0) {                                      // end mark never reached
                led_err.write(LEDON);
                break;
            }

            switch(cdc_buffer_rx[0]) {                              // check first byte for "destination"
                case 0xAA:                                          // RFID-FE Firmware Update
                
                    break;
                case 0xBB:                                          // RFID-FE
                    for (i = 0; i < sizeof(cdc_buffer_rx); i++) {
                        uart_buffer_tx[i] = cdc_buffer_rx[i];       // copy USB message to UART for RFID
                    }

                    status = rfid_wr();                             // send buffer to RFID and get response according to RFID board
                    break;

                case 0xCC:                                          // Proximity Sensor
                    clrcdctx();
                    led_com.write(LEDON);
                    for (i = 0; i < sizeof(cdc_buffer_rx); i++) {
                        i2c_buffer[i] = cdc_buffer_rx[i];           // copy USB message to buffer for I2C
                    }

                    if (i2c_buffer[1] == 1)                         // I2C read = 1
                        status = prox_msg_rd();                     // read the requested data
                    else if (i2c_buffer[1] == 0)                    // I2C write = 0
                        status = prox_msg_wr();                     // send buffer to proximity sensor and get response

                    if (status) led_err.write(LEDON);               // we shouldn't get here

                    em_pos = 0;
                    for (i = 0; i < sizeof(cdc_buffer_tx); i++) {
                        cdc_buffer_tx[i] = i2c_buffer[i];           // copy RFID response back to USB buffer
                        if (cdc_buffer_tx[i] == 0x7E) {
                            em_pos = (i + 1);                       // allows 0x7E to appear in the data payload - uses last one for end-mark
                        }
                    }
                    if (em_pos == 0) {
                        led_err.write(LEDON);                       // end mark never reached
                        break;
                    }

                    cdc.writeBlock(cdc_buffer_tx, (em_pos + 2));
                    led_com.write(led_com_state);
                    break;

                case 0xDD:                                          // GPIO (LEDs and RFID-FE control)
                    clrcdctx();
                    led_com.write(LEDON);
                    for (i = 0; i < sizeof(cdc_buffer_rx); i++) {
                        gpio_buffer[i] = cdc_buffer_rx[i];          // copy USB message to buffer for GPIO
                    }

                    if (gpio_buffer[1] == 1)                        // GPIO read = 1
                        status = gpio_rd();                         // read the requested data
                    else if (gpio_buffer[1] == 0)                   // GPIO write = 0
                        status = gpio_wr();                         // send GPIO pin data

                    em_pos = 0;
                    for (i = 0; i < sizeof(cdc_buffer_tx); i++) {
                        cdc_buffer_tx[i] = gpio_buffer[i];          // copy RFID response back to USB buffer
                        if (cdc_buffer_tx[i] == 0x7E) {
                            em_pos = (i + 1);                       // allows 0x7E to appear in the data payload - uses last one for end-mark
                        }
                    }
                    if (em_pos == 0) {
                        led_err.write(LEDON);                       // end mark never reached
                        break;
                    }

                    cdc.writeBlock(cdc_buffer_tx, (em_pos + 2));
                    led_com.write(led_com_state);

                    break;

                case 0xEE:                                          // Read/write EEPROM
                    clrcdctx();
                    led_com.write(LEDON);
                    for (i = 0; i < sizeof(cdc_buffer_rx); i++) {
                        i2c_buffer[i] = cdc_buffer_rx[i];           // copy USB message to buffer for I2C
                    }

                    if (i2c_buffer[1] == 1)                         // I2C read = 1
                        status = eeprom_msg_rd();                   // read the requested data
                    else if (i2c_buffer[1] == 0)                    // I2C write = 0
                        status = eeprom_msg_wr();                   // send buffer to EEPROM and get response

                    //if (status) led_err.write(LEDON);

                    em_pos = 0;
                    for (i = 0; i < sizeof(cdc_buffer_tx); i++) {
                        cdc_buffer_tx[i] = i2c_buffer[i];           // copy RFID response back to USB buffer
                        if (cdc_buffer_tx[i] == 0x7E) {
                            em_pos = (i + 1);                       // allows 0x7E to appear in the data payload - uses last one for end-mark
                        }
                    }
                    if (em_pos == 0) {
                        led_err.write(LEDON);                       // end mark never reached
                        break;
                    }

                    cdc.writeBlock(cdc_buffer_tx, (em_pos + 2));
                    led_com.write(led_com_state);
                    break;

                case 0xFF:
                    clrcdctx();
                    if (cdc_buffer_rx[1] > 0){                      // FF, 01, 7E, 0F, F0 = read message from EEPROM and turn on prox IRQ
                        // read message sent to RFID on interrupt
                        
                        temploc = 0x12;
                        i2c.write(i2c_addr, &temploc, 1, 1);        // i2c address+bank 2, RFID message size location, 1 byte, no stop at end
                        i2c.read(i2c_addr, &msgcount, 1, 0);        // i2c address+bank 2, RFID message size, 1 byte, stop at end
                        msgcount += 6;                              // get the real size
                        temploc = 0x10;
                        i2c.write(i2c_addr, &temploc, 1, 1);        // i2c address+bank 2, RFID message location, 1 byte, no stop at end
                        i2c.read(i2c_addr, prox_irq_msg, msgcount, 0);  // i2c address+bank 2, description string, string size, stop at end

                        autorange[2] = 0x03;
                        i2c.write(PROX, autorange, 3, 0);           // Start contonuous proximity range read
                    }
                    else {                                          // FF, 00, 7E, 0F, F0 = turn off prox irq
                        prox_irq_msg[0] = 0xFF;                     // clear first byte
                        autorange[2] = 0x00;
                        i2c.write(PROX, autorange, 3, 0);           // Stop range read
                    }
                    
                    break;
                default:
                    led_err.write(LEDON);                           // we should never get here
                    //while(1);                                       // halt!
            }
        }
        led_com.write(led_com_state);
    }
}
//EOF main.cpp