Important changes to repositories hosted on mbed.com
Mbed hosted mercurial repositories are deprecated and are due to be permanently deleted in July 2026.
To keep a copy of this software download the repository Zip archive or clone locally using Mercurial.
It is also possible to export all your personal repositories from the account settings page.
Revision 0:2deb247ab4bd, committed 2014-12-09
- Comitter:
- wueric
- Date:
- Tue Dec 09 05:06:37 2014 +0000
- Commit message:
- sharing stuff;
Changed in this revision
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/WifiRobot/.gitignore Tue Dec 09 05:06:37 2014 +0000 @@ -0,0 +1,2 @@ +*.swp +*~
Binary file WifiRobot/.wifi_test_main.cpp.swp has changed
Binary file WifiRobot/IntensityScanner/.IntensityScanner.cpp.swp has changed
Binary file WifiRobot/IntensityScanner/.IntensityScanner.h.swp has changed
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/WifiRobot/IntensityScanner/IntensityScanner.cpp	Tue Dec 09 05:06:37 2014 +0000
@@ -0,0 +1,53 @@
+#include "IntensityScanner.h"
+
+IntensityScanner::IntensityScanner (PinName cc3000_irq,
+    PinName cc3000_en,
+    PinName cc3000_cs,
+    SPI cc3000_spi, const char* SSID, const char* key, mbed_cc3000::Security sec, bool smart_config, uint32_t timeout) : wifi(cc3000_irq, cc3000_en,
+        cc3000_cs, cc3000_spi, SSID, key, sec, smart_config), timeout(timeout) {
+    wifi.init();
+    /*
+    const unsigned long intervalTime[16] = { 2000, 2000, 2000, 2000,  2000,
+    2000, 2000, 2000, 2000, 2000, 2000, 2000, 2000, 2000, 2000, 2000 };
+    */
+
+    /*wifi._wlan.ioctl_set_scan_params(timeout, 20, 30, 5,
+    0x7ff, -80, 0, 205, (uint32_t*) intervalTime);
+    */
+    const unsigned long intervalTime[16] = { 200, 200, 200, 200,  200,
+    200, 200, 200, 200, 200, 200, 200, 200, 200, 200, 200 };
+    wifi._wlan.ioctl_set_scan_params(timeout, 20, 30, 5,
+        0x400, -80, 0, 205, (uint32_t*) intervalTime);
+        
+};
+        
+
+int IntensityScanner::rssi_for_ssid (const char* ssid, uint8_t* rssi) {
+
+    uint8_t scan_buffer[50];
+    uint8_t rssi_field, ssid_length_field, ssid_length;
+    char* measured_ssid_name;
+    
+    int found_match = 0;
+    while (!found_match
+        && wifi._wlan.ioctl_get_scan_results(1000, scan_buffer) == 0) {
+            
+        rssi_field = scan_buffer[8];
+        ssid_length_field = scan_buffer[9];
+        ssid_length = ssid_length_field & (0x3F);
+
+        measured_ssid_name = (char*) malloc(sizeof(char) * (ssid_length+1));
+        memcpy(measured_ssid_name, scan_buffer + 12, ssid_length);
+        measured_ssid_name[ssid_length] = '\0';
+        
+        if (strcmp(ssid, measured_ssid_name) == 0) {
+            
+            *rssi = (rssi_field & 0x7f);
+            found_match = 1;
+        }
+
+        free(measured_ssid_name);
+    }
+
+    return found_match ? 0 : 1;
+}
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/WifiRobot/IntensityScanner/IntensityScanner.h	Tue Dec 09 05:06:37 2014 +0000
@@ -0,0 +1,16 @@
+#include "mbed.h"
+#include "cc3000.h"
+
+class IntensityScanner {
+    public:
+        IntensityScanner (PinName cc3000_irq,
+            PinName cc3000_en,
+            PinName cc3000_cs,
+            SPI cc3000_spi, const char* SSID, const char* key, mbed_cc3000::Security sec, bool smart_config, uint32_t timeout);
+
+        int rssi_for_ssid (const char* ssid, uint8_t* rssi);
+
+    private:
+        mbed_cc3000::cc3000 wifi;
+        uint32_t timeout;
+};
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/WifiRobot/MbedSensors/MMA8451Q.cpp	Tue Dec 09 05:06:37 2014 +0000
@@ -0,0 +1,81 @@
+/* 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 REG_WHO_AM_I      0x0D
+#define REG_CTRL_REG_1    0x2A
+#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() {
+    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::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);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/WifiRobot/MbedSensors/MMA8451Q.h	Tue Dec 09 05:06:37 2014 +0000
@@ -0,0 +1,110 @@
+/* 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);
+
+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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/WifiRobot/MbedSensors/accelerometer.cpp	Tue Dec 09 05:06:37 2014 +0000
@@ -0,0 +1,26 @@
+#include "accelerometer.h"
+
+MMA8451Q AccelMeasure::accelerometer = MMA8451Q(PTE25, PTE24, MMA8451_I2C_ADDRESS);
+
+AccelMeasure::AccelMeasure(float x, float y, float z) : x_accel(x), y_accel(y), z_accel(z) {
+}
+
+void AccelMeasure::updateAccelerometerRead () {
+    x_accel = accelerometer.getAccX();
+    y_accel = accelerometer.getAccY();
+    z_accel = accelerometer.getAccZ();
+}
+
+AccelMeasure operator+ (AccelMeasure a, AccelMeasure b) {
+    return AccelMeasure(a.x_accel + b.x_accel, a.y_accel + b.y_accel,
+        a.z_accel + b.z_accel);
+}
+
+AccelMeasure operator* (float a, AccelMeasure b) {
+    return AccelMeasure(a * b.x_accel, a * b.y_accel, a * b.z_accel);
+}
+
+
+AccelMeasure operator* (AccelMeasure b, float a) {
+    return AccelMeasure(a * b.x_accel, a * b.y_accel, a * b.z_accel);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/WifiRobot/MbedSensors/accelerometer.h	Tue Dec 09 05:06:37 2014 +0000
@@ -0,0 +1,29 @@
+#include "mbed.h"
+#include "MMA8451Q.h"
+
+#ifndef MBED_ACCELEROMETER_H
+#define MBED_ACCELEROMETER_H
+
+
+#define MMA8451_I2C_ADDRESS (0x1d)
+
+class AccelMeasure {
+    private:
+        static MMA8451Q accelerometer;
+    public:
+        float x_accel;
+        float y_accel;
+        float z_accel;
+
+        AccelMeasure(float, float, float);
+        void updateAccelerometerRead ();
+};
+
+
+AccelMeasure operator+ (AccelMeasure a, AccelMeasure b);
+
+AccelMeasure operator* (float a, AccelMeasure b);
+
+AccelMeasure operator* (AccelMeasure b, float a);
+
+#endif
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/WifiRobot/README.md Tue Dec 09 05:06:37 2014 +0000 @@ -0,0 +1,6 @@ +WifiRobot +========= + +EECS C149 Project + +Code for a robot that finds spots with a strong wifi signal
Binary file WifiRobot/RoombaControl/.DS_Store has changed
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/WifiRobot/RoombaControl/MbedSerial/TimeoutMultipleSerial.cpp	Tue Dec 09 05:06:37 2014 +0000
@@ -0,0 +1,76 @@
+#include "TimeoutMultipleSerial.h"
+
+int TimeoutMultipleSerial::readMultChars (uint8_t* const dest, 
+    const size_t size) {
+
+    timer.reset();
+    timer.start();
+
+    size_t counter = 0;
+    while (counter < size 
+        && timer.read_ms() < timeout) {
+
+        while (!port.readable() 
+            && timer.read_ms() < timeout) wait_ms(1);
+
+        if (port.readable()) {
+            *(dest + counter) = (uint8_t) (port.getc());
+            ++counter;
+        }
+    }
+
+    timer.stop();
+
+    if (counter != size) {
+        return -1;
+    }
+
+    return 1;
+}
+
+int TimeoutMultipleSerial::writeMultChars (const uint8_t* source,
+    const size_t size) {
+
+    timer.reset();
+    timer.start();
+
+    size_t counter = 0;
+    while (counter < size
+        && timer.read_ms() < timeout) {
+        
+        while (!port.writeable()
+            && timer.read_ms() < timeout) wait_ms(1);
+
+        if (port.writeable()) {
+            port.putc((int) (*(source + counter)));
+            ++counter;
+        }
+    }
+
+    timer.stop();
+    if (counter != size) {
+        return -1;
+    }
+
+    return 1;
+}
+
+int TimeoutMultipleSerial::clearAll() {
+    while (port.readable()) port.getc();
+    return 1;
+}
+
+void TimeoutMultipleSerial::setTimeout (uint32_t tout) {
+    timeout = tout;
+}
+
+void TimeoutMultipleSerial::setBaud (uint32_t baud) {
+    port.baud(baud);
+}
+
+void TimeoutMultipleSerial::setFormat (int bits, 
+    SerialBase::Parity parity, 
+    int stop_bits) {
+
+    port.format(bits, parity, stop_bits);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/WifiRobot/RoombaControl/MbedSerial/TimeoutMultipleSerial.h	Tue Dec 09 05:06:37 2014 +0000
@@ -0,0 +1,53 @@
+/*
+Implementation of a serial connection for mbed
+
+Depends on Serial class provided by mbed sdk
+
+Written 2014-11-10 by Eric Wu
+
+This class writes/reads the specified number of symbols from the
+    serial connection, and times out if it takes longer than
+    a specified time to get the symbols
+*/
+
+#ifndef TIMEOUTMULTIPLESERIAL_H
+#define TIMEOUTMULTIPLESERIAL_H
+
+#include "mbed.h"
+#include <stdint.h>
+
+class TimeoutMultipleSerial {
+
+    public:
+        // constructor, @param tout is the timeout time in milliseconds
+        TimeoutMultipleSerial (PinName tx, PinName rx,
+            const char* name, uint32_t tout) : port(tx, rx, name),
+            timeout(tout), timer() { };
+        
+        // reads @param size number of symbols from the serial connection
+        //      into @param dest
+        int readMultChars (uint8_t* const dest, const size_t size);
+
+        // writes @param size number of symbols from @param source
+        //      into the serial connection
+        int writeMultChars (const uint8_t* source, const size_t size);
+
+        // clears all available symbols from the serial connection
+        int clearAll ();
+
+        // sets the timeout in milliseconds to @param tout
+        void setTimeout (uint32_t tout);
+
+        // sets the baud to @param baud
+        void setBaud (uint32_t baud);
+
+        // sets the format for port
+        void setFormat (int bits=8, SerialBase::Parity parity=SerialBase::None, int stop_bits=1);
+
+    private:
+        Serial port; // port
+        uint32_t timeout; // timeout time in millisecondes
+        Timer timer; // timer which tracks timeout time
+};
+
+#endif
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/WifiRobot/RoombaControl/irobot/irobot.cpp	Tue Dec 09 05:06:37 2014 +0000
@@ -0,0 +1,67 @@
+#include "irobotUART.h"
+#include "irobotSensor.h"
+#include "irobotSensorPoll.h"
+#include "irobotSensorStream.h"
+#include "irobotActuator.h"
+#include "irobotCommand.h"
+#include "irobotTime.h"
+
+int32_t irobotOpen(const irobotUARTPort_t port){
+	int32_t status = ERROR_SUCCESS;
+	
+	irobot_IfIsNotError(status, irobotUARTOpen(port, IROBOT_BAUD_57600));
+
+	// in case iRobot was just powered on, wait for it to start up
+	if(!irobot_IsError(status)){
+		irobotDelayMs(5000);
+	}
+	
+	// put robot into start mode; delay for startup
+	irobot_IfIsNotError(status, irobotStart(port));
+	if(!irobot_IsError(status)){
+		irobotDelayMs(1000);
+	}
+
+	irobot_IfIsNotError(status, irobotFull(port));
+
+	irobot_IfIsNotError(status, irobotStop(port));
+
+	// clear receive queue, which may have old sensor stream data
+	irobot_IfIsNotError(status, irobotSensorStreamPause(port, true));
+	if(!irobot_IsError(status)){
+		irobotDelayMs(250);
+	}
+	irobot_IfIsNotError(status, irobotUARTClear(port));
+
+	// set status LEDs
+	irobot_IfIsNotError(status, irobotLEDs(port, LED_ADVANCE_PLAY, 0, 255));
+
+	return status;
+}
+
+int32_t irobotClose(const irobotUARTPort_t port){
+	int32_t status = ERROR_SUCCESS;
+
+	// Always attempt to stop, even if an error has occurred
+	irobot_StatusMerge(&status, irobotStop(port));
+
+	// Clear sensor stream
+	irobot_IfIsNotError(status, irobotSensorStreamPause(port, true));
+	if(!irobot_IsError(status)){
+		irobotDelayMs(150);
+	}
+
+	// Clear UART
+	irobot_IfIsNotError(status, irobotUARTClear(port));
+
+	// reset LED state
+	irobot_IfIsNotError(status, irobotLEDs(port, LED_NONE, 255, 255));
+
+	// restore baud
+	irobot_IfIsNotError(status, irobotBaudChange(port, IROBOT_BAUD_57600));
+
+	// always close UART, even if an error has occurred
+	irobot_StatusMerge(&status, irobotUARTClose(port));
+
+	return status;
+}
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/WifiRobot/RoombaControl/irobot/irobot.h Tue Dec 09 05:06:37 2014 +0000 @@ -0,0 +1,40 @@ +/** \file irobot.h + * + * Top-level driver for the iRobot Create. + * Implements irobotOpen() and irobotClose() + * + * \author Jeff C. Jensen + * \date 2013-10-17 + * \copyright Copyright (C) 2013, Jeff C. Jensen, Edward A. Lee, and Sanjit A. Seshia. + * This software accompanies An Introductory Lab in Embedded and Cyber-Physical Systems + * and is licensed under a Creative Commons Attribution-NonCommercial-NoDerivs 3.0 + * Unported License. See http://leeseshia.org/lab. + */ + +#ifndef _IROBOT_H +#define _IROBOT_H + +#include "irobotUART.h" +#include "irobotSensor.h" +#include "irobotSensorPoll.h" +#include "irobotSensorStream.h" +#include "irobotActuator.h" +#include "irobotCommand.h" +#include <stdio.h> +#include <stdlib.h> +#include <time.h> + +/// Open UART serial port and initialize iRobot. +/// \return error code +int32_t irobotOpen( + const irobotUARTPort_t port ///< [in] UART port +); + +/// Close a session with an iRobot +/// \return error code +int32_t irobotClose( + const irobotUARTPort_t port ///< [in] UART port +); + + +#endif // _IROBOT_H
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/WifiRobot/RoombaControl/irobot/irobotActuator.cpp	Tue Dec 09 05:06:37 2014 +0000
@@ -0,0 +1,172 @@
+#include "irobotActuator.h"
+#include <stdlib.h>
+
+#ifndef MAX
+	#define MAX(x, y) (((x) > (y)) ? (x) : (y))
+#endif
+#ifndef MIN
+	#define MIN(x, y) (((x) < (y)) ? (x) : (y))
+#endif
+#ifndef coerce
+	#define coerce(xMin, x, xMax)	(MIN(MAX(xMin, x), xMax))
+#endif
+
+int32_t irobotDigitalOutputs(
+	const irobotUARTPort_t	port,
+	const uint8_t			output
+){
+	uint8_t packet[OP_DIGITAL_OUTPUTS_SIZE];
+	
+	packet[0] = OP_DIGITAL_OUTPUTS;
+	packet[1] = output;
+
+	return irobotUARTWriteRaw(port, packet, OP_DIGITAL_OUTPUTS_SIZE);
+}
+
+int32_t irobotDriveDirect(
+	const irobotUARTPort_t	port,
+	int16_t					leftWheelSpeed,
+	int16_t					rightWheelSpeed
+){
+	uint8_t packet[OP_DRIVE_DIRECT_SIZE];
+	
+	leftWheelSpeed = (int16_t)coerce(ACTUATOR_WHEEL_SPEED_MIN, leftWheelSpeed, ACTUATOR_WHEEL_SPEED_MAX);
+	rightWheelSpeed = (int16_t)coerce(ACTUATOR_WHEEL_SPEED_MIN, rightWheelSpeed, ACTUATOR_WHEEL_SPEED_MAX);
+
+	packet[0] = OP_DRIVE_DIRECT;
+	packet[1] = HO(rightWheelSpeed);
+	packet[2] = LO(rightWheelSpeed);
+	packet[3] = HO(leftWheelSpeed);
+	packet[4] = LO(leftWheelSpeed);
+
+	return irobotUARTWriteRaw(port, packet, OP_DRIVE_DIRECT_SIZE);
+}
+
+int32_t irobotDriveDirection(
+	const irobotUARTPort_t		port,
+	int16_t						velocity,
+	const irobotDirection_t		direction
+){
+	uint8_t packet[OP_DRIVE_SIZE];
+	
+	velocity = (int16_t)coerce(ACTUATOR_WHEEL_SPEED_MIN, velocity, ACTUATOR_WHEEL_SPEED_MAX);
+
+	packet[0] = OP_DRIVE;
+	packet[1] = HO(velocity);
+	packet[2] = LO(velocity);
+	packet[3] = HO((uint16_t)direction);
+	packet[4] = LO((uint16_t)direction);
+
+	return irobotUARTWriteRaw(port, packet, OP_DRIVE_SIZE);
+}
+
+int32_t irobotDriveRadius(
+	const irobotUARTPort_t	port,
+	int16_t					velocity,
+	int16_t					radius
+){
+	uint8_t packet[OP_DRIVE_SIZE];
+
+	velocity = (int16_t)coerce(ACTUATOR_WHEEL_SPEED_MIN, velocity, ACTUATOR_WHEEL_SPEED_MAX);
+	radius = (int16_t)coerce(ACTUATOR_DRIVE_RADIUS_MIN, radius, ACTUATOR_DRIVE_RADIUS_MAX);
+
+	// Special case: radius = 1mm is interpreted as CCW rotation;
+	//	iRobot Drive CCW covers this case, so a drive radius of 1mm is
+	//	interpreted as the next smallest radius, 2mm
+	if(radius == 1){
+		radius = 2;
+	}
+
+	packet[0] = OP_DRIVE;
+	packet[1] = HO(velocity);
+	packet[2] = LO(velocity);
+	packet[3] = HO(radius);
+	packet[4] = LO(radius);
+	
+	return irobotUARTWriteRaw(port, packet, OP_DRIVE_SIZE);
+}
+
+int32_t irobotLEDs(
+	const irobotUARTPort_t	port,
+	const irobotLED_t		leds,
+	const uint8_t			powerColor,
+	const uint8_t			powerIntensity
+){
+	uint8_t packet[OP_LEDS_SIZE];
+
+	packet[0] = OP_LEDS;
+	packet[1] = (uint8_t)leds;
+	packet[2] = powerColor;
+	packet[3] = powerIntensity;
+	
+	return irobotUARTWriteRaw(port, packet, OP_LEDS_SIZE);
+}
+
+int32_t irobotPWMLowSideDrivers(
+	const irobotUARTPort_t	port,
+	uint8_t					pwm0,
+	uint8_t					pwm1,
+	uint8_t					pwm2
+){
+	uint8_t packet[OP_PWM_LOW_SIDE_DRIVERS_SIZE];
+
+	pwm0 = (uint16_t)coerce(ACTUATOR_PWM_DUTY_MIN, pwm0, ACTUATOR_PWM_DUTY_MAX);
+	pwm1 = (uint16_t)coerce(ACTUATOR_PWM_DUTY_MIN, pwm1, ACTUATOR_PWM_DUTY_MAX);
+	pwm2 = (uint16_t)coerce(ACTUATOR_PWM_DUTY_MIN, pwm2, ACTUATOR_PWM_DUTY_MAX);
+
+	packet[0] = OP_PWM_LOW_SIDE_DRIVERS;
+	packet[1] = pwm0;
+	packet[2] = pwm1;
+	packet[3] = pwm2;
+	
+	return irobotUARTWriteRaw(port, packet, OP_PWM_LOW_SIDE_DRIVERS_SIZE);
+}
+
+/// opcode + song number + song length + n notes
+#define OP_SONG_MAX_LENGTH	(ACTUATOR_MAX_SONGS * ACTUATOR_MAX_NOTES_PER_SONG + 3)
+
+int32_t irobotSong(
+	const irobotUARTPort_t			port,
+	uint8_t							songNumber,
+	const irobotSongNote_t * const	songNotes,
+	uint8_t							nNotes
+){
+	uint8_t packet[OP_SONG_MAX_LENGTH];
+	uint8_t packetIndex = 0;
+	uint8_t noteIndex = 0;
+
+	if(!songNotes){
+		return ERROR_INVALID_PARAMETER;
+	}
+
+	songNumber = MIN(songNumber, ACTUATOR_MAX_SONGS - 1);
+	nNotes = MIN(nNotes, (ACTUATOR_MAX_SONGS - songNumber) * ACTUATOR_MAX_NOTES_PER_SONG);
+
+	packet[packetIndex++] = OP_SONG;
+	packet[packetIndex++] = songNumber;
+	packet[packetIndex++] = nNotes;
+	for(noteIndex = 0; noteIndex < nNotes; noteIndex++){
+		packet[packetIndex++] = songNotes[noteIndex].midiNote;
+		packet[packetIndex++] = songNotes[noteIndex].duration;
+	}
+	
+	return irobotUARTWriteRaw(port, packet, packetIndex);
+}
+
+int32_t irobotPlaySong(
+	const irobotUARTPort_t	port,
+	const uint8_t			songNumber
+){
+	uint8_t packet[OP_PLAY_SONG_SIZE];
+
+	packet[0] = OP_PLAY_SONG;
+	packet[1] = songNumber;
+	
+	return irobotUARTWriteRaw(port, packet, OP_PLAY_SONG_SIZE);
+}
+
+int32_t irobotStop(
+	const irobotUARTPort_t	port
+){
+	return irobotDriveDirect(port, 0, 0);
+}
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/WifiRobot/RoombaControl/irobot/irobotActuator.h Tue Dec 09 05:06:37 2014 +0000 @@ -0,0 +1,97 @@ +/** \file irobotActuator.h + * + * iRobot Create actuator functions. + * + * \author Jeff C. Jensen + * \date 2013-10-17 + * \copyright Copyright (C) 2013, Jeff C. Jensen, Edward A. Lee, and Sanjit A. Seshia. + * This software accompanies An Introductory Lab in Embedded and Cyber-Physical Systems + * and is licensed under a Creative Commons Attribution-NonCommercial-NoDerivs 3.0 + * Unported License. See http://leeseshia.org/lab. + */ + +#ifndef _IROBOTACTUATOR_H +#define _IROBOTACTUATOR_H + +#include "irobotError.h" +#include "irobotOpcode.h" +#include "irobotActuatorTypes.h" +#include "irobotUART.h" + +/// Write to the digital output bank of the cargo bay on iRobot. +/// \return error code +int32_t irobotDigitalOutputs( + const irobotUARTPort_t port, ///< [in] UART port + const uint8_t output ///< [in] Pins 0-7 +); + +/// Directly actuate left and right wheels. +/// \return error code +int32_t irobotDriveDirect( + const irobotUARTPort_t port, ///< [in] UART port + int16_t leftWheelSpeed, ///< [in] Left wheels speed, in mm/s + int16_t rightWheelSpeed ///< [in] Right wheel speed, in mm/s +); + +/// Drives in a fixed direction +/// \return error code +int32_t irobotDriveDirection( + const irobotUARTPort_t port, ///< [in] UART port + int16_t velocity, ///< [in] Velocity, in mm/s + const irobotDirection_t direction ///< [in] direction +); + +/// Drive the robot with a fixed linear speed, and turning through a fixed radius. +/// \warning Do not call this function for the special cases of driving straight, or clockwise +/// and counter-clockwise turning; this function instructs the robot to drive only nonzero radii. +/// \return error code +int32_t irobotDriveRadius( + const irobotUARTPort_t port, ///< [in] UART port + int16_t velocity, ///< [in] Velocity, in mm/s + int16_t radius ///< [in] Radius, in mm +); + +/// Change the state of the iRobot power, play, and advance LEDs. +/// \return error code +int32_t irobotLEDs( + const irobotUARTPort_t port, ///< [in] UART port + const irobotLED_t leds, ///< [in] LEDs to turn on + const uint8_t powerColor, ///< [in] Power LED color (G[0] - R[255]) + const uint8_t powerIntensity ///< [in] Power LED intensiy (0-255) +); + +/// Set the PWM duty cycle of the low-side drivers. +/// \return error code +int32_t irobotPWMLowSideDrivers( + const irobotUARTPort_t port, ///< [in] UART port + uint8_t pwm0, ///< [in] PWM for low-side driver 0 (0-128 duty cycle) + uint8_t pwm1, ///< [in] PWM for low-side driver 1 (0-128 duty cycle) + uint8_t pwm2 ///< [in] PWM for low-side driver 2 (0-128 duty cycle) +); + +/// Define a song. Each song is alloted 16 notes, but a song can "spill over" into +/// the next if so desired. The maximum number of notes that may be defined is +/// (16 - SongNumber) * 16. +/// \return error code +int32_t irobotSong( + const irobotUARTPort_t port, ///< [in] UART port + uint8_t songNumber, ///< [in] Song number + const irobotSongNote_t * const songNotes, ///< [in] Song notes + uint8_t nNotes ///< [in] Number of song notes +); + +/// Play a song +/// \return error code +int32_t irobotPlaySong( + const irobotUARTPort_t port, ///< [in] UART port + const uint8_t songNumber ///< [in] Song number +); + +/// Stops the wheels. +/// \return error code +int32_t irobotStop( + const irobotUARTPort_t port ///< [in] UART port +); + + +#endif // _IROBOTACTUATOR_H
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/WifiRobot/RoombaControl/irobot/irobotActuatorTypes.h	Tue Dec 09 05:06:37 2014 +0000
@@ -0,0 +1,60 @@
+/** \file irobotActuatorTypes.h
+ *
+ * iRobot actuator type definitions.
+ *
+ * \author Jeff C. Jensen
+ * \date 2013-12-09
+ * \copyright Copyright (C) 2013, Jeff C. Jensen, Edward A. Lee, and Sanjit A. Seshia.
+ * 			  This software accompanies An Introductory Lab in Embedded and Cyber-Physical Systems
+ * 			  and is licensed under a Creative Commons Attribution-NonCommercial-NoDerivs 3.0
+ * 			  Unported License. See http://leeseshia.org/lab.
+ */
+
+#ifndef _IROBOTACTUATORTYPES_H
+#define _IROBOTACTUATORTYPES_H
+
+#include "irobotTypes.h"
+
+/// iRobot drive directions
+typedef enum{
+	DRIVE_STRAIGHT			= 0x8000,	///< straight
+	DRIVE_CLOCKWISE			= 0xFFFF,	///< clockwise
+	DRIVE_COUNTERCLOCKWISE	= 0x0001	///< counter-clockwise
+} irobotDirection_t;
+
+/// iRobot LED selector
+typedef enum{
+	LED_NONE			= 0,	///< none
+	LED_PLAY			= 2,	///< play
+	LED_ADVANCE			= 8,	///< advance
+	LED_ADVANCE_PLAY	= 10	///< advance and play
+} irobotLED_t;
+
+/// iRobot song note
+typedef struct{
+	uint8_t midiNote;	///< MIDI note
+	uint8_t duration;	///< note duration
+} irobotSongNote_t;
+
+/// max wheel speed, in mm/s
+#define ACTUATOR_WHEEL_SPEED_MAX			500
+/// min wheel speed, in mm/s
+#define ACTUATOR_WHEEL_SPEED_MIN			-500
+
+/// max drive radius, in mm
+#define ACTUATOR_DRIVE_RADIUS_MAX			2000
+/// min drive radius, in mm
+#define ACTUATOR_DRIVE_RADIUS_MIN			-2000
+
+/// max PWM duty cycle (100%)
+#define ACTUATOR_PWM_DUTY_MAX				128
+/// min PWM duty cycle (0%)
+#define ACTUATOR_PWM_DUTY_MIN				0
+
+/// max number of songs that may be defined
+#define ACTUATOR_MAX_SONGS					16
+/// max number of notes per song
+#define ACTUATOR_MAX_NOTES_PER_SONG			16
+
+
+#endif	// _IROBOTTYPES_H
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/WifiRobot/RoombaControl/irobot/irobotCommand.cpp	Tue Dec 09 05:06:37 2014 +0000
@@ -0,0 +1,80 @@
+#include "irobotCommand.h"
+#include "irobotTime.h"
+
+int32_t irobotBaudChange(
+	const irobotUARTPort_t	port,
+	const irobotBaud_t		baud
+){
+	int32_t status = ERROR_SUCCESS;
+	uint8_t packet[OP_BAUD_SIZE];
+
+	packet[0] = OP_BAUD;
+	packet[1] = (uint8_t)baud;
+	
+	if(!irobot_IsError(status)){
+		irobot_StatusMerge(&status, irobotUARTWriteRaw(port, packet, OP_BAUD_SIZE));
+	}
+	if(!irobot_IsError(status)){
+		irobot_StatusMerge(&status, irobotUARTClose(port));
+	}
+	if(!irobot_IsError(status)){
+		irobot_StatusMerge(&status, irobotUARTOpen(port, baud));
+		irobotDelayMs(50); // delay 50ms
+	}
+
+	return status;
+}
+
+int32_t irobotDemoStop(
+	const irobotUARTPort_t	port
+){
+	uint8_t packet[OP_DEMO_SIZE];
+
+	packet[0] = OP_DEMO;
+	packet[1] = 0xFF;		/* special case; stop all demos */
+	
+	return irobotUARTWriteRaw(port, packet, OP_DEMO_SIZE);
+}
+
+int32_t irobotDemo(
+	const irobotUARTPort_t	port,
+	const irobotDemo_t		demo
+){
+	uint8_t packet[OP_DEMO_SIZE];
+
+	packet[0] = OP_DEMO;
+	packet[1] = (uint8_t)demo;
+	
+	return irobotUARTWriteRaw(port, packet, OP_DEMO_SIZE);
+}
+
+int32_t irobotFull(
+	const irobotUARTPort_t	port
+){
+	uint8_t packet[OP_FULL_SIZE];
+
+	packet[0] = OP_FULL;
+	
+	return irobotUARTWriteRaw(port, packet, OP_FULL_SIZE);
+}
+
+int32_t irobotSafe(
+	const irobotUARTPort_t	port
+){
+	uint8_t packet[OP_SAFE_SIZE];
+
+	packet[0] = OP_SAFE;
+	
+	return irobotUARTWriteRaw(port, packet, OP_SAFE_SIZE);
+}
+
+int32_t irobotStart(
+	const irobotUARTPort_t	port
+){
+	uint8_t packet[OP_START_SIZE];
+
+	packet[0] = OP_START;
+	
+	return irobotUARTWriteRaw(port, packet, OP_START_SIZE);
+}
+
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/WifiRobot/RoombaControl/irobot/irobotCommand.h	Tue Dec 09 05:06:37 2014 +0000
@@ -0,0 +1,70 @@
+/** \file irobotCommand.h
+ *
+ * iRobot general commands.
+ *
+ * \author Jeff C. Jensen
+ * \date 2013-12-09
+ * \copyright Copyright (C) 2013, Jeff C. Jensen, Edward A. Lee, and Sanjit A. Seshia.
+ * 			  This software accompanies An Introductory Lab in Embedded and Cyber-Physical Systems
+ * 			  and is licensed under a Creative Commons Attribution-NonCommercial-NoDerivs 3.0
+ * 			  Unported License. See http://leeseshia.org/lab.
+ */
+
+#ifndef _IROBOTCOMMAND_H
+#define _IROBOTCOMMAND_H
+
+#include "irobotOpcode.h"
+#include "irobotUART.h"
+#include "irobotError.h"
+
+/// Demo modes
+typedef enum{
+	DEMO_COVER				= 0,	///< Cover demo
+	DEMO_COVER_DOCK			= 1,	///< Cover & dock demo
+	DEMO_SPOT_COVER			= 2,	///< Spot cover demo
+	DEMO_MOUSE				= 3,	///< Mouse demo
+	DEMO_DRIVE_FIGURE_EIGHT	= 4,	///< Figure eight demo
+	DEMO_WIMP				= 5,	///< Wimp demo
+	DEMO_HOME				= 6,	///< Home demo
+	DEMO_TAG				= 7,	///< Tag demo
+	DEMO_PACHELBEL			= 8,	///< Pachelbel song demo
+	DEMO_BANJO				= 9		///< Banjo song demo
+} irobotDemo_t;
+
+/// Set the iRobot baud rate. The serial port will be reconfigured to this new
+/// baud rate and restarted, which will clear communication buffers and may introduce a delay.
+/// \warning baud 115200 appears to be unstable.
+/// \return error code
+int32_t irobotBaudChange(
+	const irobotUARTPort_t	port,		///< [in] UART port
+	const irobotBaud_t		baud		///< [in] iRobot baud code
+);
+
+/// Stop a running demo
+int32_t irobotDemoStop(
+	const irobotUARTPort_t	port		///< [in] UART port
+);
+
+/// Run a demo
+int32_t irobotDemo(
+	const irobotUARTPort_t	port,		///< [in] UART port
+	const irobotDemo_t		demo		///< [in] demo to run
+);
+
+/// Change to FULL mode
+int32_t irobotFull(
+	const irobotUARTPort_t	port		///< [in] UART port
+);
+
+/// Change to SAFE mode
+int32_t irobotSafe(
+	const irobotUARTPort_t	port		///< [in] UART port
+);
+
+/// Change to START mode
+int32_t irobotStart(
+	const irobotUARTPort_t	port		///< [in] UART port
+);
+
+
+#endif // _IROBOTCOMMAND_H
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/WifiRobot/RoombaControl/irobot/irobotError.cpp	Tue Dec 09 05:06:37 2014 +0000
@@ -0,0 +1,17 @@
+#include "irobotError.h"
+
+int32_t irobot_StatusMerge(
+	int32_t * const status,
+	const int32_t  newStatus
+){
+	if (!status){
+		return ERROR_INVALID_PARAMETER;
+	}
+	else if(!irobot_IsError(*status)
+		&& (*status == ERROR_SUCCESS || irobot_IsError(newStatus))
+	){
+		*status = newStatus;
+	}
+
+	return *status;
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/WifiRobot/RoombaControl/irobot/irobotError.h	Tue Dec 09 05:06:37 2014 +0000
@@ -0,0 +1,77 @@
+/** \file irobotError.h
+ *
+ * iRobot error handling and codes.
+ *
+ * \author Jeff C. Jensen
+ * \date 2013-12-09
+ * \copyright Copyright (C) 2013, Jeff C. Jensen, Edward A. Lee, and Sanjit A. Seshia.
+ * 			  This software accompanies An Introductory Lab in Embedded and Cyber-Physical Systems
+ * 			  and is licensed under a Creative Commons Attribution-NonCommercial-NoDerivs 3.0
+ * 			  Unported License. See http://leeseshia.org/lab.
+ */
+
+#ifndef _IROBOTERROR_H
+#define _IROBOTERROR_H
+
+#include "irobotTypes.h"
+
+#ifndef ERROR_SUCCESS
+/// Operation successful
+#define ERROR_SUCCESS				0
+#endif
+
+#ifndef ERROR_INVALID_PARAMETER
+/// Operation received an invalid parameter
+#define ERROR_INVALID_PARAMETER		-52005
+#endif
+
+#ifndef ERROR_TIMEOUT
+/// Operation timed out
+#define ERROR_TIMEOUT				-50400
+#endif
+
+
+/**
+ * Tests whether a status is an error.
+ *
+ * @param status status to check for an error
+ * @return whether the status was an error
+ */
+#define irobot_IsError(status)	((status) < ERROR_SUCCESS)
+
+/**
+ * Conditionally sets the status to a new value. The previous status is
+ * preserved unless the new status is more of an error, which means that
+ * warnings and errors overwrite successes, and errors overwrite warnings. New
+ * errors do not overwrite older errors, and new warnings do not overwrite
+ * older warnings.
+ *
+ * @param status status to conditionally set
+ * @param newStatus new status value that may be set
+ * @return the resulting status
+ */
+int32_t irobot_StatusMerge(int32_t * const status, const int32_t newStatus);
+
+/**
+ * This macro evaluates the expression only if the status is not an error. The
+ * expression must evaluate to a int32_t, because the status will be set to the
+ * returned status if the expression is evaluated.
+ *
+ * You can use this macro to mimic status chaining:
+ *
+ *    int32_t status = ERROR_SUCCESS;
+ *    IfIsNotError(&status, SendMessage(...));
+ *    IfIsNotError(&status, SendMessage(...));
+ *    IfIsNotError(&status, SendMessage(...));
+ *
+ * @param status status to check for an error
+ * @param expression expression to call if the incoming status is not an error
+ */
+#define irobot_IfIsNotError(status, expression) \
+   if(!irobot_IsError(status)) \
+   { \
+	   irobot_StatusMerge(&status, (expression)); \
+   }
+
+
+#endif // _IROBOTERROR_H
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/WifiRobot/RoombaControl/irobot/irobotOpcode.h	Tue Dec 09 05:06:37 2014 +0000
@@ -0,0 +1,79 @@
+/** \file irobotOpcode.h
+ *
+ * iRobot Open Interface Operation Codes (opcodes)
+ *
+ * \author Jeff C. Jensen
+ * \date 2013-12-09
+ * \copyright Copyright (C) 2013, Jeff C. Jensen, Edward A. Lee, and Sanjit A. Seshia.
+ * 			  This software accompanies An Introductory Lab in Embedded and Cyber-Physical Systems
+ * 			  and is licensed under a Creative Commons Attribution-NonCommercial-NoDerivs 3.0
+ * 			  Unported License. See http://leeseshia.org/lab.
+ */
+
+#ifndef _IROBOTOPCODE_H
+#define _IROBOTOPCODE_H
+
+/// OpCodes for iRobot open interface
+typedef enum{
+	OP_START				= 128,	///< Start mode
+	OP_BAUD					= 129,	///< Change baud rate
+	OP_CONTROL				= 130,	///< Control mode
+	OP_SAFE					= 131,	///< Safe mode
+	OP_FULL					= 132,	///< Full mode
+	OP_DEMO					= 136,	///< Demo mode
+	OP_DEMO_COVER			= 135,	///< Cover demo
+	OP_DEMO_COVER_DOCK		= 143,	///< Dock & cover demo
+	OP_DEMO_SPOT			= 134,	///< Spot demo
+	OP_DRIVE				= 137,	///< Drive a turn radius and speed
+	OP_DRIVE_DIRECT			= 145,	///< Directly drive left and right wheels
+	OP_LEDS					= 139,	///< Control LEDs
+	OP_DIGITAL_OUTPUTS		= 147,	///< Write digital outputs
+	OP_PWM_LOW_SIDE_DRIVERS	= 144,	///< Write PWM low-side drivers
+	OP_LOW_SIDE_DRIVERS		= 138,	///< Write analog low-side drivers
+	OP_SEND_IR				= 151,	///< Send IR signal
+	OP_SONG					= 140,	///< Define song
+	OP_PLAY_SONG			= 141,	///< Play song
+	OP_SENSORS				= 142,	///< Query sensors
+	OP_QUERY_LIST			= 149,	///< Set list of sensors to query
+	OP_STREAM				= 148,	///< Sensor stream
+	OP_PAUSE_RESUME_STREAM	= 150,	///< Pause or resume sensor stream
+	OP_SCRIPT				= 152,	///< Define action script
+	OP_PLAY_SCRIPT			= 153,	///< Play action script
+	OP_SHOW_SCRIPT			= 154,	///< Read the current action script
+	OP_WAIT_TIME			= 155,	///< Script: instruct the robot to wait for a specified time
+	OP_WAIT_DISTANCE		= 156,	///< Script: instruct the robot to wait for a specified distance
+	OP_WAIT_ANGLE			= 157,	///< Script: instruct the robot to wait for a specified angle
+	OP_WAIT_EVENT			= 158	///< Script: instruct the robot to wait for an event
+} irobotOpcode_t;
+
+#define OP_START_SIZE					1	///< Size of the START opcode and payload
+#define OP_BAUD_SIZE					2	///< Size of the BAUD opcode and payload
+#define OP_CONTROL_SIZE					1	///< Size of the CONTROL opcode and payload
+#define OP_SAFE_SIZE					1	///< Size of the SAFE opcode and payload
+#define OP_FULL_SIZE					1	///< Size of the FULL opcode and payload
+#define OP_DEMO_SIZE					2	///< Size of the DEMO opcode and payload
+#define OP_DEMO_COVER_SIZE				1	///< Size of the DEMO_COVER opcode and payload
+#define OP_DEMO_COVER_DOCK_SIZE			1	///< Size of the DEMO_COVER_DOCK opcode and payload
+#define OP_DEMO_SPOT_SIZE				1	///< Size of the DEMO_SPOT opcode and payload
+#define OP_DRIVE_SIZE					5	///< Size of the DRIVE opcode and payload
+#define OP_DRIVE_DIRECT_SIZE			5	///< Size of the DRIVE_DIRECT opcode and payload
+#define OP_LEDS_SIZE					4	///< Size of the LEDs opcode and payload
+#define OP_DIGITAL_OUTPUTS_SIZE			2	///< Size of the DIGITAL_OUTPUTS opcode and payload
+#define OP_PWM_LOW_SIDE_DRIVERS_SIZE	4	///< Size of the PWM_LOW_SIDE_DRIVERS opcode and payload
+#define OP_LOW_SIDE_DRIVERS_SIZE		2	///< Size of the LOW_SIDE_DRIVERS opcode and payload
+#define OP_SEND_IR_SIZE					2	///< Size of the SEND_IR opcode and payload
+// OP_SONG size is variable
+#define OP_PLAY_SONG_SIZE				2	///< Size of the PLAY_SONG opcode and payload
+#define OP_SENSORS_SIZE					2	///< Size of the SENSORS opcode and payload
+// OP_QUERY_LIST size is variable
+// OP_STREAM size is variable
+#define OP_PAUSE_RESUME_STREAM_SIZE		2	///< Size of the PAUSE_RESUME_STREAM opcode and payload
+// OP_SCRIPT size is variable
+#define OP_PLAY_SCRIPT_SIZE				1	///< Size of the PLAY_SCRIPT opcode and payload
+#define OP_SHOW_SCRIPT_SIZE				1	///< Size of the SHOW_SCRIPT opcode and payload
+#define OP_WAIT_TIME_SIZE				2	///< Size of the WAIT_TIME opcode and payload
+#define OP_WAIT_DISTANCE_SIZE			3	///< Size of the WAIT_DISTANCE opcode and payload
+#define OP_WAIT_ANGLE_SIZE				3	///< Size of the WAIT_ANGLE opcode and payload
+#define OP_WAIT_EVENT_SIZE				2	///< Size of the WAIT_EVENT opcode and payload
+
+#endif	// _IROBOTOPCODE_H
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/WifiRobot/RoombaControl/irobot/irobotSensor.cpp	Tue Dec 09 05:06:37 2014 +0000
@@ -0,0 +1,520 @@
+#include "irobotSensor.h"
+#include <stdio.h>
+
+int32_t irobotReadBumps_Wheeldrops(
+	xqueue_t * const queue,
+	irobotBumps_WheelDrops_t * const bumps_wheelDrops
+){
+	uint8_t packedValues = 0;
+
+	//check for NULL pointers
+	if(!queue || !bumps_wheelDrops){
+		return ERROR_INVALID_PARAMETER;
+	}
+	//verify packet size
+	if(xqueue_count(queue) < SENSOR_BUMPS_WHEELDROPS_SIZE){
+		return ERROR_INVALID_PARAMETER;
+	}
+
+	packedValues = xqueue_pop(queue);
+
+	bumps_wheelDrops->bumpRight = !!(packedValues & (1 << 0));
+	bumps_wheelDrops->bumpLeft = !!(packedValues & (1 << 1));
+	bumps_wheelDrops->wheeldropRight = !!(packedValues & (1 << 2));
+	bumps_wheelDrops->wheeldropLeft = !!(packedValues & (1 << 3));
+	bumps_wheelDrops->wheeldropCaster = !!(packedValues & (1 << 4));
+
+	return ERROR_SUCCESS;
+}
+
+int32_t irobotReadButtons(
+	xqueue_t * const queue,
+	irobotButtons_t * const buttons
+){
+	uint8_t packedValues = 0;
+
+	//check for NULL pointers
+	if(!queue || !buttons){
+		return ERROR_INVALID_PARAMETER;
+	}
+	//verify packet size
+	if(xqueue_count(queue) < SENSOR_BUTTONS_SIZE){
+		return ERROR_INVALID_PARAMETER;
+	}
+
+	packedValues = xqueue_pop(queue);
+
+	buttons->play = !!(packedValues & (1 << 0));
+	buttons->advance = !!(packedValues & (1 << 2));
+
+	return ERROR_SUCCESS;
+}
+
+int32_t irobotReadCargoBayDigitalInputs(
+	xqueue_t * const queue,
+	irobotCargoBayDigitalInputs_t * const digitalInputs
+){
+	uint8_t packedValues = 0;
+
+	//check for NULL pointers
+	if(!queue || !digitalInputs){
+		return ERROR_INVALID_PARAMETER;
+	}
+	//verify packet size
+	if(xqueue_count(queue) < SENSOR_CARGO_BAY_DIGITAL_INPUTS_SIZE){
+		return ERROR_INVALID_PARAMETER;
+	}
+
+	packedValues = xqueue_pop(queue);
+
+	digitalInputs->digitalInput0 = !!(packedValues & (1 << 0));
+	digitalInputs->digitalInput1 = !!(packedValues & (1 << 1));
+	digitalInputs->digitalInput2 = !!(packedValues & (1 << 2));
+	digitalInputs->digitalInput3 = !!(packedValues & (1 << 3));
+	digitalInputs->deviceDetect = !!(packedValues & (1 << 4));
+
+	return ERROR_SUCCESS;
+}
+
+int32_t irobotReadChargingSourcesAvailable(
+	xqueue_t * const queue,
+	irobotChargingSourcesAvailable_t * const sources
+){
+	uint8_t packedValues = 0;
+	//check for NULL pointers
+	if(!queue || !sources){
+		return ERROR_INVALID_PARAMETER;
+	}
+	//verify packet size
+	if(xqueue_count(queue) < SENSOR_CHARGING_SOURCES_AVAILABLE_SIZE){
+		return ERROR_INVALID_PARAMETER;
+	}
+
+	packedValues = xqueue_pop(queue);
+
+	sources->internalCharger = !!(packedValues & (1 << 0));
+	sources->homeBase = !!(packedValues & (1 << 1));
+
+	return ERROR_SUCCESS;
+}
+
+int32_t irobotReadLowSideDriver_WheelOvercurrent(
+	xqueue_t * const queue,
+	irobotLowSideDriver_WheelOvercurrent_t * const lsd_wo
+){
+	uint8_t packedValues = 0;
+
+	//check for NULL pointers
+	if(!queue || !lsd_wo){
+		return ERROR_INVALID_PARAMETER;
+	}
+	//verify packet size
+	if(xqueue_count(queue) < SENSOR_LOW_SIDE_DRIVER_WHEEL_OVERDRIVE_SIZE){
+		return ERROR_INVALID_PARAMETER;
+	}
+
+	packedValues = xqueue_pop(queue);
+
+	lsd_wo->lowSideDriver1 = !!(packedValues & (1 << 0));
+	lsd_wo->lowSideDriver0 = !!(packedValues & (1 << 1));
+	lsd_wo->lowSideDriver2 = !!(packedValues & (1 << 2));
+	lsd_wo->rightWheel = !!(packedValues & (1 << 3));
+	lsd_wo->leftWheel = !!(packedValues & (1 << 4));
+
+	return ERROR_SUCCESS;
+}
+
+int32_t irobotReadSensorGroup0(
+	xqueue_t * const queue,
+	irobotSensorGroup0_t * const sensorGroup0
+){
+	int32_t status = ERROR_SUCCESS;
+
+	//0 = 1 + 2 + 3
+	//at least in the binary field where 2:=1+1=0, 3:=2+1=1
+	irobotSensorGroup1_t	sensorGroup1;
+	irobotSensorGroup2_t	sensorGroup2;
+	irobotSensorGroup3_t	sensorGroup3;
+
+	//check for NULL pointers
+	if(!queue || !sensorGroup0){
+		return ERROR_INVALID_PARAMETER;
+	}
+	//verify packet size
+	if(xqueue_count(queue) < SENSOR_GROUP0_SIZE){
+		return ERROR_INVALID_PARAMETER;
+	}
+
+	if(!irobot_IsError(status)){
+		irobot_StatusMerge(&status, irobotReadSensorGroup1(queue, &sensorGroup1));
+	}
+	if(!irobot_IsError(status)){
+		irobot_StatusMerge(&status, irobotReadSensorGroup2(queue, &sensorGroup2));
+	}
+	if(!irobot_IsError(status)){
+		irobot_StatusMerge(&status, irobotReadSensorGroup3(queue, &sensorGroup3));
+	}
+	if(!irobot_IsError(status)){
+		sensorGroup0->bumps_wheelDrops = sensorGroup1.bumps_wheelDrops;
+		sensorGroup0->wall = sensorGroup1.wall;
+		sensorGroup0->cliffLeft = sensorGroup1.cliffLeft;
+		sensorGroup0->cliffFrontLeft = sensorGroup1.cliffFrontLeft;
+		sensorGroup0->cliffFrontRight = sensorGroup1.cliffFrontRight;
+		sensorGroup0->cliffRight = sensorGroup1.cliffRight;
+		sensorGroup0->virtualWall = sensorGroup1.virtualWall;
+		sensorGroup0->lowSideDriver_WheelOvercurrent = sensorGroup1.lowSideDriver_wheelovercurrent;
+
+		sensorGroup0->infrared = sensorGroup2.infrared;
+		sensorGroup0->buttons = sensorGroup2.buttons;
+		sensorGroup0->distance = sensorGroup2.distance;
+		sensorGroup0->angle = sensorGroup2.angle;
+
+		sensorGroup0->chargingState = sensorGroup3.chargingState;
+		sensorGroup0->voltage = sensorGroup3.voltage;
+		sensorGroup0->current = sensorGroup3.current;
+		sensorGroup0->batteryTemperature = sensorGroup3.batteryTemperature;
+		sensorGroup0->batteryCharge = sensorGroup3.batteryCharge;
+		sensorGroup0->batteryCapacity = sensorGroup3.batteryCapacity;
+	}
+
+	return status;
+}
+
+int32_t irobotReadSensorGroup1(
+	xqueue_t * const queue,
+	irobotSensorGroup1_t * const sensorGroup1
+){
+	int32_t status = ERROR_SUCCESS;
+	//check for NULL pointers
+	if(!queue || !sensorGroup1){
+		return ERROR_INVALID_PARAMETER;
+	}
+	//verify packet size
+	if(xqueue_count(queue) < SENSOR_GROUP1_SIZE){
+		return ERROR_INVALID_PARAMETER;
+	}
+
+	if(!irobot_IsError(status)){
+		irobot_StatusMerge(&status, irobotReadBumps_Wheeldrops(queue, &sensorGroup1->bumps_wheelDrops));
+	}
+
+	if(!irobot_IsError(status)){
+		sensorGroup1->wall				= (bool)xqueue_pop(queue);
+		sensorGroup1->cliffLeft			= (bool)xqueue_pop(queue);
+		sensorGroup1->cliffFrontLeft	= (bool)xqueue_pop(queue);
+		sensorGroup1->cliffFrontRight	= (bool)xqueue_pop(queue);
+		sensorGroup1->cliffRight		= (bool)xqueue_pop(queue);
+		sensorGroup1->virtualWall		= (bool)xqueue_pop(queue);
+	}
+	
+	if(!irobot_IsError(status)){
+		irobot_StatusMerge(&status, irobotReadLowSideDriver_WheelOvercurrent(queue, &sensorGroup1->lowSideDriver_wheelovercurrent));
+	}
+
+	xqueue_drop_many(queue, 2);	//unused
+
+	return status;
+}
+
+int32_t irobotReadSensorGroup2(
+	xqueue_t * const queue,
+	irobotSensorGroup2_t * const sensorGroup2
+){
+	int32_t status = ERROR_SUCCESS;
+
+	//check for NULL pointers
+	if(!queue || !sensorGroup2){
+		return ERROR_INVALID_PARAMETER;
+	}
+	//verify packet size
+	if(xqueue_count(queue) < SENSOR_GROUP2_SIZE){
+		return ERROR_INVALID_PARAMETER;
+	}
+
+	if(!irobot_IsError(status)){
+		sensorGroup2->infrared = xqueue_pop(queue);
+		irobot_StatusMerge(&status, irobotReadButtons(queue, &sensorGroup2->buttons));
+	}
+	if(!irobot_IsError(status)){
+		sensorGroup2->distance = (int16_t)xqueue_pop16(queue);
+		sensorGroup2->angle = (int16_t)xqueue_pop16(queue);
+	}
+
+	return status;
+}
+
+int32_t irobotReadSensorGroup3(
+	xqueue_t * const queue,
+	irobotSensorGroup3_t * const sensorGroup3
+){
+	//check for NULL pointers
+	if(!queue || !sensorGroup3){
+		return ERROR_INVALID_PARAMETER;
+	}
+	//verify packet size
+	if(xqueue_count(queue) < SENSOR_GROUP3_SIZE){
+		return ERROR_INVALID_PARAMETER;
+	}
+
+	sensorGroup3->chargingState		= (irobotChargingState_t)xqueue_pop(queue);
+	sensorGroup3->voltage			= xqueue_pop16(queue);
+	sensorGroup3->current			= (int16_t)xqueue_pop16(queue);
+	sensorGroup3->batteryTemperature= (int8_t)xqueue_pop(queue);
+	sensorGroup3->batteryCharge		= xqueue_pop16(queue);
+	sensorGroup3->batteryCapacity	= xqueue_pop16(queue);
+	
+	return ERROR_SUCCESS;
+}
+
+int32_t irobotReadSensorGroup4(
+	xqueue_t * const queue,
+	irobotSensorGroup4_t * const sensorGroup4
+){
+	int32_t status = ERROR_SUCCESS;
+	//check for NULL pointers
+	if(!queue || !sensorGroup4){
+		return ERROR_INVALID_PARAMETER;
+	}
+	//verify packet size
+	if(xqueue_count(queue) < SENSOR_GROUP4_SIZE){
+		return ERROR_INVALID_PARAMETER;
+	}
+
+	if(!irobot_IsError(status)){
+		sensorGroup4->wallSignal			= xqueue_pop16(queue);
+		sensorGroup4->cliffLeftSignal		= xqueue_pop16(queue);
+		sensorGroup4->cliffFrontLeftSignal	= xqueue_pop16(queue);
+		sensorGroup4->cliffFrontRightSignal	= xqueue_pop16(queue);
+		sensorGroup4->cliffRightSignal		= xqueue_pop16(queue);
+
+		irobot_StatusMerge(&status, irobotReadCargoBayDigitalInputs(queue, &sensorGroup4->cargoBayDigitalInputs));
+	}
+	if(!irobot_IsError(status)){
+		irobot_StatusMerge(&status, irobotReadChargingSourcesAvailable(queue, &sensorGroup4->chargingSourcesAvailable));
+	}
+	if(!irobot_IsError(status)){
+		sensorGroup4->cargoBayAnalogSignal	= xqueue_pop16(queue);
+	}
+
+	return status;
+}
+
+int32_t irobotReadSensorGroup5(
+	xqueue_t * const queue,
+	irobotSensorGroup5_t * const sensorGroup5
+){
+	//check for NULL pointers
+	if(!queue || !sensorGroup5){
+		return ERROR_INVALID_PARAMETER;
+	}
+	//verify packet size
+	if(xqueue_count(queue) < SENSOR_GROUP5_SIZE){
+		return ERROR_INVALID_PARAMETER;
+	}
+
+	sensorGroup5->oiState						= (irobotOIState_t)xqueue_pop(queue);
+	sensorGroup5->songNumber					= xqueue_pop(queue);
+	sensorGroup5->songPlaying					= (bool)xqueue_pop(queue);
+	sensorGroup5->nStreamPackets				= xqueue_pop(queue);
+	sensorGroup5->requestedVelocity				= (int16_t)xqueue_pop16(queue);
+	sensorGroup5->requestedRadius				= (int16_t)xqueue_pop16(queue);
+	sensorGroup5->requestedRightWheelVelocity	= (int16_t)xqueue_pop16(queue);
+	sensorGroup5->requestedLeftWheelVelocity	= (int16_t)xqueue_pop16(queue);
+
+	return ERROR_SUCCESS;
+}
+
+int32_t irobotReadSensorGroup6(
+	xqueue_t * const queue,
+	irobotSensorGroup6_t * const sensorGroup6
+){
+	int32_t status = ERROR_SUCCESS;
+	
+	//6 = 1 + 2 + 3 + 4 + 5  = 0 + 4 + 5
+	irobotSensorGroup0_t	sensorGroup0;
+	irobotSensorGroup4_t	sensorGroup4;
+	irobotSensorGroup5_t	sensorGroup5;
+
+	//check for NULL pointers
+	if(!queue || !sensorGroup6){
+		return ERROR_INVALID_PARAMETER;
+	}
+	//verify packet size
+	if(xqueue_count(queue) < SENSOR_GROUP6_SIZE){
+		return ERROR_INVALID_PARAMETER;
+	}
+
+	if(!irobot_IsError(status)){
+		irobot_StatusMerge(&status, irobotReadSensorGroup0(queue, &sensorGroup0));
+	}
+	if(!irobot_IsError(status)){
+		irobot_StatusMerge(&status, irobotReadSensorGroup4(queue, &sensorGroup4));
+	}
+	if(!irobot_IsError(status)){
+		irobot_StatusMerge(&status, irobotReadSensorGroup5(queue, &sensorGroup5));
+	}
+	if(!irobot_IsError(status)){
+		sensorGroup6->bumps_wheelDrops = sensorGroup0.bumps_wheelDrops;
+		sensorGroup6->wall = sensorGroup0.wall;
+		sensorGroup6->cliffLeft = sensorGroup0.cliffLeft;
+		sensorGroup6->cliffFrontLeft = sensorGroup0.cliffFrontLeft;
+		sensorGroup6->cliffFrontRight = sensorGroup0.cliffFrontRight;
+		sensorGroup6->cliffRight = sensorGroup0.cliffRight;
+		sensorGroup6->virtualWall = sensorGroup0.virtualWall;
+		sensorGroup6->lowSideDriver_WheelOvercurrent = sensorGroup0.lowSideDriver_WheelOvercurrent;
+
+		sensorGroup6->infrared = sensorGroup0.infrared;
+		sensorGroup6->buttons = sensorGroup0.buttons;
+		sensorGroup6->distance = sensorGroup0.distance;
+		sensorGroup6->angle = sensorGroup0.angle;
+
+		sensorGroup6->chargingState = sensorGroup0.chargingState;
+		sensorGroup6->voltage = sensorGroup0.voltage;
+		sensorGroup6->current = sensorGroup0.current;
+		sensorGroup6->batteryTemperature = sensorGroup0.batteryTemperature;
+		sensorGroup6->batteryCharge = sensorGroup0.batteryCharge;
+		sensorGroup6->batteryCapacity = sensorGroup0.batteryCapacity;
+
+		sensorGroup6->wallSignal = sensorGroup4.wallSignal;
+		sensorGroup6->cliffLeftSignal = sensorGroup4.cliffLeftSignal;
+		sensorGroup6->cliffFrontLeftSignal = sensorGroup4.cliffFrontLeftSignal;
+		sensorGroup6->cliffFrontRightSignal = sensorGroup4.cliffFrontRightSignal;
+		sensorGroup6->cliffRightSignal = sensorGroup4.cliffRightSignal;
+		sensorGroup6->cargoBayDigitalInputs = sensorGroup4.cargoBayDigitalInputs;
+		sensorGroup6->cargoBayAnalogSignal = sensorGroup4.cargoBayAnalogSignal;
+		sensorGroup6->chargingSourcesAvailable = sensorGroup4.chargingSourcesAvailable;
+
+		sensorGroup6->oiState = sensorGroup5.oiState;
+		sensorGroup6->songNumber = sensorGroup5.songNumber;
+		sensorGroup6->songPlaying = sensorGroup5.songPlaying;
+		sensorGroup6->nStreamPackets = sensorGroup5.nStreamPackets;
+		sensorGroup6->requestedVelocity = sensorGroup5.requestedVelocity;
+		sensorGroup6->requestedRadius = sensorGroup5.requestedRadius;
+		sensorGroup6->requestedRightWheelVelocity = sensorGroup5.requestedRightWheelVelocity;
+		sensorGroup6->requestedLeftWheelVelocity = sensorGroup5.requestedLeftWheelVelocity;
+	}
+
+	return status;
+}
+
+int32_t irobotPrintSensorGroup6(
+	const irobotSensorGroup6_t * const sensors
+){	
+	//catch NULL pointers
+	if(!sensors){
+		return ERROR_INVALID_PARAMETER;
+	}
+
+	printf("\n*********** iRobot Sensors ***********\n");
+	printf(
+		"Wheel Drops:\tCaster[%s] Left[%s] Right[%s]\n",
+		sensors->bumps_wheelDrops.wheeldropCaster ? "X" : " ",
+		sensors->bumps_wheelDrops.wheeldropLeft ? "X" : " ",
+		sensors->bumps_wheelDrops.wheeldropRight ? "X" : " "
+	);
+
+	printf(
+		"Bumps:\t\tLeft[%s] Right[%s]\n",
+		sensors->bumps_wheelDrops.bumpLeft ? "X" : " ",
+		sensors->bumps_wheelDrops.bumpRight ? "X" : " "
+	);
+
+	printf("Wall:\t\t[%s]\n", sensors->wall ? "X" : " ");
+
+	printf(
+		"Cliffs:\t\tLeft[%s] FrontLeft[%s] FrontRight[%s] Right[%s]\n",
+		sensors->cliffLeft ? "X" : " ",
+		sensors->cliffFrontLeft ? "X" : " ",
+		sensors->cliffFrontRight ? "X" : " ",
+		sensors->cliffRight ? "X" : " "
+	);
+
+	printf("Virtual Wall:\t[%s]\n", sensors->virtualWall ? "X" : " ");
+
+	printf(
+		"Overcurrent:\tLSD0[%s] LSD1[%s] LSD2[%s] LeftWheel[%s] RightWheel[%s]\n",
+		sensors->lowSideDriver_WheelOvercurrent.lowSideDriver0 ? "X" : " ",
+		sensors->lowSideDriver_WheelOvercurrent.lowSideDriver1 ? "X" : " ",
+		sensors->lowSideDriver_WheelOvercurrent.lowSideDriver2 ? "X" : " ",
+		sensors->lowSideDriver_WheelOvercurrent.leftWheel ? "X" : " ",
+		sensors->lowSideDriver_WheelOvercurrent.rightWheel ? "X" : " "
+	);
+
+	printf("Infrared:\t0x%02X\n", sensors->infrared);
+
+	printf(
+		"Buttons:\tAdvance[%s] Play[%s]\n",
+		sensors->buttons.advance ? "X" : " ",
+		sensors->buttons.play ? "X" : " "
+	);
+
+	printf("Position:\tDistance[%d mm] Angle[%d deg]\n", sensors->distance, sensors->angle);
+
+	printf("Charging State: ");
+	switch(sensors->chargingState){
+	case CHARGING_STATE_NOT_CHARGING:				printf("not charging\n");	break;
+	case CHARGING_STATE_RECONDITION_CHARGING:		printf("reconditioning\n");	break;
+	case CHARGING_STATE_FULL_CHARGING:				printf("full, charging\n");	break;
+	case CHARGING_STATE_TRICKLE_CHARGING:			printf("trickle\n");		break;
+	case CHARGING_STATE_WAITING:					printf("waiting\n");		break;
+	case CHARGING_STATE_CHARGING_FAULT_CONDITION:	printf("fault\n");			break;
+	default:										printf("unknown\n");		break;
+	}
+
+	printf(
+		"Battery:\tVoltage[%d mV] Current[%d mA]\n",
+		sensors->voltage,
+		sensors->current
+	);
+
+	printf(
+		"Battery:\tCharge[%d mAh] Capacity[%d mAh] Temp[%d C]\n",
+		sensors->batteryCharge,
+		sensors->batteryCapacity,
+		sensors->batteryTemperature
+	);
+
+	printf("Wall Signal:\t%d\n", sensors->wallSignal);
+	printf(
+		"Cliff Signals:\tLeft[%d] FrontLeft[%d] FrontRight[%d] Right[%d]\n",
+		sensors->cliffLeftSignal,
+		sensors->cliffFrontLeftSignal,
+		sensors->cliffFrontRightSignal,
+		sensors->cliffRightSignal
+	);
+
+	printf(
+		"Cargo DI:\tDI0[%s] DI1[%s] DI2[%s] DI3[%s] DeviceDetect[%s]\n",
+		sensors->cargoBayDigitalInputs.digitalInput0 ? "X" : " ",
+		sensors->cargoBayDigitalInputs.digitalInput1 ? "X" : " ",
+		sensors->cargoBayDigitalInputs.digitalInput2 ? "X" : " ",
+		sensors->cargoBayDigitalInputs.digitalInput3 ? "X" : " ",
+		sensors->cargoBayDigitalInputs.deviceDetect ? "X" : " "
+	);
+
+	printf("Cargo Analog:\t%d\n", sensors->cargoBayAnalogSignal);
+
+	printf(
+		"Charge Sources:\tInternal[%s] Base[%s]\n",
+		sensors->chargingSourcesAvailable.internalCharger ? "X" : " ",
+		sensors->chargingSourcesAvailable.homeBase ? "X" : " "
+	);
+
+	printf("OI State:\t");
+	switch(sensors->oiState){
+	case OISTATE_OFF:		printf("OFF\n");	break;
+	case OISTATE_PASSIVE:	printf("PASSIVE\n");break;
+	case OISTATE_SAFE:		printf("SAFE\n");	break;
+	case OISTATE_FULL:		printf("FULL\n");	break;
+	default:				printf("UNKNOWN\n");break;
+	}
+
+	printf("Song:\t\tNumber[%d] Playing[%s]\n", sensors->songNumber, sensors->songPlaying ? "X" : " ");
+	printf("Stream Packets:\t%d\n", sensors->nStreamPackets);
+	printf("Requested:\tVelocity [%d] Radius[%d]\n", sensors->requestedVelocity, sensors->requestedRadius);
+	printf("Requested:\tRight[%d] Left[%d]\n", sensors->requestedRightWheelVelocity, sensors->requestedLeftWheelVelocity);
+
+	printf("*********** iRobot Sensors ***********\n");
+
+	return ERROR_SUCCESS;
+}
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/WifiRobot/RoombaControl/irobot/irobotSensor.h Tue Dec 09 05:06:37 2014 +0000 @@ -0,0 +1,111 @@ +/** \file irobotSensor.h + * + * iRobot Create sensor operations. + * + * \author Jeff C. Jensen + * \date 2013-12-09 + * \copyright Copyright (C) 2013, Jeff C. Jensen, Edward A. Lee, and Sanjit A. Seshia. + * This software accompanies An Introductory Lab in Embedded and Cyber-Physical Systems + * and is licensed under a Creative Commons Attribution-NonCommercial-NoDerivs 3.0 + * Unported License. See http://leeseshia.org/lab. +*/ + +#ifndef _IROBOTSENSOR_H +#define _IROBOTSENSOR_H + +#include "irobotSensorTypes.h" +#include "irobotError.h" +#include "xqueue.h" + +/// read a sensor from a data queue +/// \return error code +int32_t irobotReadBumps_Wheeldrops( + xqueue_t * const queue, ///< [in/out] queue containing sensor packet + irobotBumps_WheelDrops_t * const bumps_wheelDrops ///< [out] sensor value +); + +/// read a sensor from a data queue +/// \return error code +int32_t irobotReadButtons( + xqueue_t * const queue, ///< [in/out] queue containing sensor packet + irobotButtons_t * const buttons ///< [out] sensor value +); + +/// read a sensor from a data queue +/// \return error code +int32_t irobotReadCargoBayDigitalInputs( + xqueue_t * const queue, ///< [in/out] queue containing sensor packet + irobotCargoBayDigitalInputs_t * const digitalInputs ///< [out] sensor value +); + +/// read a sensor from a data queue +/// \return error code +int32_t irobotReadChargingSourcesAvailable( + xqueue_t * const queue, ///< [in/out] queue containing sensor packet + irobotChargingSourcesAvailable_t * const sources ///< [out] sensor value +); + +/// read a sensor from a data queue +/// \return error code +int32_t irobotReadLowSideDriver_WheelOvercurrent( + xqueue_t * const queue, ///< [in/out] queue containing sensor packet + irobotLowSideDriver_WheelOvercurrent_t * const lsd_wo ///< [out] sensor value +); + +/// read a sensor group from a data queue +/// \return error code +int32_t irobotReadSensorGroup0( + xqueue_t * const queue, ///< [in/out] queue containing sensor packet + irobotSensorGroup0_t * const sensorGroup0 ///< [out] sensor value +); + +/// read a sensor group from a data queue +/// \return error code +int32_t irobotReadSensorGroup1( + xqueue_t * const queue, ///< [in/out] queue containing sensor packet + irobotSensorGroup1_t * const sensorGroup1 ///< [out] sensor value +); + +/// read a sensor group from a data queue +/// \return error code +int32_t irobotReadSensorGroup2( + xqueue_t * const queue, ///< [in/out] queue containing sensor packet + irobotSensorGroup2_t * const sensorGroup2 ///< [out] sensor value +); + +/// read a sensor group from a data queue +/// \return error code +int32_t irobotReadSensorGroup3( + xqueue_t * const queue, ///< [in/out] queue containing sensor packet + irobotSensorGroup3_t * const sensorGroup3 ///< [out] sensor value +); + +/// read a sensor group from a data queue +/// \return error code +int32_t irobotReadSensorGroup4( + xqueue_t * const queue, ///< [in/out] queue containing sensor packet + irobotSensorGroup4_t * const sensorGroup4 ///< [out] sensor value +); + +/// read a sensor group from a data queue +/// \return error code +int32_t irobotReadSensorGroup5( + xqueue_t * const queue, ///< [in/out] queue containing sensor packet + irobotSensorGroup5_t * const sensorGroup5 ///< [out] sensor value +); + +/// read a sensor group from a data queue +/// \return error code +int32_t irobotReadSensorGroup6( + xqueue_t * const queue, ///< [in/out] queue containing sensor packet + irobotSensorGroup6_t * const sensorGroup6 ///< [out] sensor value +); + +/// print all irobot sensors +/// \return error code +int32_t irobotPrintSensorGroup6( + const irobotSensorGroup6_t * const sensors +); + + +#endif /// _IROBOTSENSOR_H
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/WifiRobot/RoombaControl/irobot/irobotSensorPoll.cpp	Tue Dec 09 05:06:37 2014 +0000
@@ -0,0 +1,39 @@
+#include "irobotOpcode.h"
+#include "irobotSensor.h"
+#include "irobotSensorPoll.h"
+#include "xqueue.h"
+
+int32_t irobotSensorPollSensorGroup6(
+	const irobotUARTPort_t	port,
+	irobotSensorGroup6_t *	const sensorGroup6
+){
+	int32_t status = ERROR_SUCCESS;
+
+	// initialize communications buffer
+	uint8_t txBuffer[OP_SENSORS_SIZE];
+	uint8_t rxQueueBuffer[SENSOR_SIZE_UPPER_BOUND] = {0x00};
+	xqueue_t rxQueue;
+	xqueue_init(&rxQueue, rxQueueBuffer, SENSOR_SIZE_UPPER_BOUND);
+
+	// check for NULL pointer
+	if(!sensorGroup6){
+		return ERROR_INVALID_PARAMETER;
+	}
+
+	// request packet
+	txBuffer[0] = OP_SENSORS;
+	txBuffer[1] = SENSOR_GROUP6;
+	irobot_StatusMerge(&status, irobotUARTWriteRaw(port, txBuffer, OP_SENSORS_SIZE));
+	
+	// receive response
+	if(!irobot_IsError(status)){
+		irobot_StatusMerge(&status, irobotUARTRead(port, &rxQueue, SENSOR_GROUP6_SIZE));
+	}
+
+	// read response
+	if(!irobot_IsError(status)){
+		irobot_StatusMerge(&status, irobotReadSensorGroup6(&rxQueue, sensorGroup6));
+	}
+
+	return status;
+}
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/WifiRobot/RoombaControl/irobot/irobotSensorPoll.h Tue Dec 09 05:06:37 2014 +0000 @@ -0,0 +1,29 @@ +/** \file irobotSensorPoll.h + * + * Methods to poll iRobot sensors. + * + * \author Jeff C. Jensen + * \date 2013-12-09 + * \copyright Copyright (C) 2013, Jeff C. Jensen, Edward A. Lee, and Sanjit A. Seshia. + * This software accompanies An Introductory Lab in Embedded and Cyber-Physical Systems + * and is licensed under a Creative Commons Attribution-NonCommercial-NoDerivs 3.0 + * Unported License. See http://leeseshia.org/lab. + */ + +#ifndef _IROBOT_SENSORPOLL_H +#define _IROBOT_SENSORPOLL_H + +#include "irobotUART.h" +#include "irobotSensorTypes.h" + +/// Request sensor packet from iRobot and wait for response +/// \warning Polling requires both transmitting and receiving +/// to the UART port, hence these functions are *not* +/// thread safe with regard to other UART functions. +/// \return error code +int32_t irobotSensorPollSensorGroup6( + const irobotUARTPort_t port, ///< [in] iRobot UART port + irobotSensorGroup6_t * const sensorGroup6 ///< [in] Sensor group +); + +#endif // _IROBOT_SENSORPOLL_H
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/WifiRobot/RoombaControl/irobot/irobotSensorStream.cpp	Tue Dec 09 05:06:37 2014 +0000
@@ -0,0 +1,107 @@
+#include "irobotSensor.h"
+#include "irobotSensorStream.h"
+#include "irobotOpcode.h"
+#include "irobotError.h"
+#include "irobotUART.h"
+
+/// Upper-limit for the size of the OP_STREAM packet occurs when including all sensor IDs in a sensor packet
+#define OP_SENSOR_STREAM_MAX_CODES	43
+/// Maximum number of sensors, plus header and size bytes
+#define OP_SENSOR_STREAM_MAX_SIZE	OP_SENSOR_STREAM_MAX_CODES + 2
+/// header of a sensor stream packet
+#define SENSOR_STREAM_HEADER		19
+
+int32_t irobotSensorStreamConfigure(
+	const irobotUARTPort_t			port,
+	const irobotSensorCode * const	sensorCodes,
+	uint8_t							nSensorCodes
+){
+	uint8_t packet[OP_SENSOR_STREAM_MAX_SIZE];
+	uint8_t packetIndex = 0;
+	uint8_t sensorCodeIndex = 0;
+
+	// check for NULL pointers
+	if(nSensorCodes && !sensorCodes){
+		return ERROR_INVALID_PARAMETER;
+	}
+
+	nSensorCodes = nSensorCodes < OP_SENSOR_STREAM_MAX_CODES ? nSensorCodes : OP_SENSOR_STREAM_MAX_CODES;
+
+	packet[packetIndex++] = OP_STREAM;
+	packet[packetIndex++] = nSensorCodes;
+	for(sensorCodeIndex = 0; sensorCodeIndex < nSensorCodes; sensorCodeIndex++){
+		packet[packetIndex++] = sensorCodes[sensorCodeIndex];
+	}
+
+	return irobotUARTWriteRaw(port, packet, packetIndex);
+}
+
+int32_t irobotSensorStreamPause(
+	const irobotUARTPort_t port,
+	const bool pause
+){
+	uint8_t packet[OP_PAUSE_RESUME_STREAM_SIZE];
+
+	packet[0] = OP_PAUSE_RESUME_STREAM;
+	packet[1] = !pause;
+
+	return irobotUARTWriteRaw(port, packet, OP_PAUSE_RESUME_STREAM_SIZE);
+}
+
+int32_t irobotSensorStreamStartAll(
+	const irobotUARTPort_t			port
+){
+	int32_t status = ERROR_SUCCESS;
+	const irobotSensorCode allSensors = SENSOR_GROUP6;
+
+	irobot_IfIsNotError(status, irobotSensorStreamConfigure(port, &allSensors, 1));
+	irobot_IfIsNotError(status, irobotSensorStreamPause(port, false));
+
+	return status;
+}
+
+int32_t irobotSensorStreamProcessAll(
+	xqueue_t * const queue,
+	irobotSensorGroup6_t * const sensors,
+	bool * const packetFound
+){
+	int32_t status = ERROR_SUCCESS;
+
+	// check for NULL pointers
+	if(!queue || !sensors || !packetFound){
+		return ERROR_INVALID_PARAMETER;
+	}
+
+	*packetFound = false;
+
+	//	Align buffer with iRobot sensor stream, according to format:
+	//	[Header:19] [Len:27] [Packet ID:0] [SenGroup6 (52 bytes)] [CxSum]
+	while(!xqueue_empty(queue) && xqueue_front(queue) != SENSOR_STREAM_HEADER){
+		xqueue_drop(queue);
+	}
+
+	// Check for properly formatted header;
+	//	NOTE: iRobot OI spec incorrectly omits the header from the checksum
+	if( xqueue_count(queue) >= SENSOR_GROUP6_SIZE + 4	// size of entire packet		*/
+	 && xqueue_pop(queue) == SENSOR_STREAM_HEADER		// sensor stream packet			*/
+	 && xqueue_pop(queue) == SENSOR_GROUP6_SIZE + 1		// size of payload + checksum	*/
+	 && xqueue_pop(queue) == SENSOR_GROUP6){			// payload is sensor group 6	*/
+		 // Checksum: cxsum = [Header:19] + [n-bytes:Sen6Size+1=53] + [packet ID:6] + [data (Sen6Size)]
+		 uint8_t cxsum = 0;
+		 cxsum += SENSOR_STREAM_HEADER;
+		 cxsum += SENSOR_GROUP6_SIZE + 1;
+		 cxsum += SENSOR_GROUP6;
+		 cxsum += xqueue_checksum(queue, SENSOR_GROUP6_SIZE + 1, 0);	// payload and encoded checksum
+
+		 // checksum passed
+		 if(cxsum == 0){
+			 irobot_StatusMerge(&status, irobotReadSensorGroup6(queue, sensors));
+			 xqueue_pop(queue);		// clear checksum
+			 if(!irobot_IsError(status)){
+				 *packetFound = true;
+			 }
+		 }
+	}
+
+	return status;
+}
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/WifiRobot/RoombaControl/irobot/irobotSensorStream.h Tue Dec 09 05:06:37 2014 +0000 @@ -0,0 +1,54 @@ +/** \file irobotSensorStream.h + * + * iRobot sensor stream functions + * + * \author Jeff C. Jensen + * \date 2013-12-09 + * \copyright Copyright (C) 2013, Jeff C. Jensen, Edward A. Lee, and Sanjit A. Seshia. + * This software accompanies An Introductory Lab in Embedded and Cyber-Physical Systems + * and is licensed under a Creative Commons Attribution-NonCommercial-NoDerivs 3.0 + * Unported License. See http://leeseshia.org/lab. + */ + +#ifndef _IROBOTSTREAM_H +#define _IROBOTSTREAM_H + +#include "irobotUART.h" +#include "irobotSensorTypes.h" + +/// configure a sensors stream +/// \return error code +int32_t irobotSensorStreamConfigure( + const irobotUARTPort_t port, ///< [in] irobot UART port + const irobotSensorCode * const sensorCodes, ///< [in] array of sensor codes (must be nSensorCodes in size) + uint8_t nSensorCodes ///< [in] number of sensors in each stream packet +); + +/// pause or resume a sensor stream +/// \return error code +int32_t irobotSensorStreamPause( + const irobotUARTPort_t port, ///< [in] irobot UART port + const bool pause ///< [in] TRUE if set to pause +); + +/// begin a sensor stream containing all sensors (SensorGroup6) +/// +/// \warning Do not use this to measure distance and angle, +/// as these measurements are subject to roundoff +/// error in each packet; less frequent packets (polling) +/// are needed. +/// \return error code +int32_t irobotSensorStreamStartAll( + const irobotUARTPort_t port ///< [in] irobot UART port +); + +/// process a sensors stream that has been configured +/// to transmit SensorGroup6 (all sensors) +int32_t irobotSensorStreamProcessAll( + xqueue_t * const queue, ///< [in/out] raw byte stream + irobotSensorGroup6_t * const sensors, ///< [out] sensors + bool * const packetFound ///< [out] packet found +); + + +#endif /// _IROBOTSTREAM_H
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/WifiRobot/RoombaControl/irobot/irobotSensorTypes.h	Tue Dec 09 05:06:37 2014 +0000
@@ -0,0 +1,407 @@
+/** \file irobotSensorTypes.h
+ *
+ * Sensor packet IDs and structures for the iRobot Create Open Interface
+ *
+ * \author Jeff C. Jensen
+ * \date 2013-12-09
+ * \copyright Copyright (C) 2013, Jeff C. Jensen, Edward A. Lee, and Sanjit A. Seshia.
+ * 			  This software accompanies An Introductory Lab in Embedded and Cyber-Physical Systems
+ * 			  and is licensed under a Creative Commons Attribution-NonCommercial-NoDerivs 3.0
+ * 			  Unported License. See http://leeseshia.org/lab.
+ */
+
+#ifndef _IROBOT_SENSORTYPES_H
+#define _IROBOT_SENSORTYPES_H
+
+#include "irobotTypes.h"
+
+/// iRobot sensor packet IDs
+typedef enum{
+	SENSOR_GROUP0							= 0,	///< Sensor Group 0
+	SENSOR_GROUP1							= 1,	///< Sensor Group 1
+	SENSOR_GROUP2							= 2,	///< Sensor Group 2
+	SENSOR_GROUP3							= 3,	///< Sensor Group 3
+	SENSOR_GROUP4							= 4,	///< Sensor Group 4
+	SENSOR_GROUP5							= 5,	///< Sensor Group 5
+	SENSOR_GROUP6							= 6,	///< Sensor Group 6
+	SENSOR_BUMPS_WHEELDROPS					= 7,	///< Bumps & wheel drops
+	SENSOR_WALL								= 8,	///< Wall
+	SENSOR_CLIFF_LEFT						= 9,	///< Left cliff
+	SENSOR_CLIFF_FRONT_LEFT					= 10,	///< Front left cliff
+	SENSOR_CLIFF_FRONT_RIGHT				= 11,	///< Front right cliff
+	SENSOR_CLIFF_RIGHT						= 12,	///< Right cliff
+	SENSOR_VIRTUAL_WALL						= 13,	///< Virtual wall
+	SENSOR_LOW_SIDE_DRIVER_WHEEL_OVERDRIVE	= 14,	///< Low-side driver and wheel overdrive
+	SENSOR_UNUSED0							= 15,	///< Unused
+	SENSOR_UNUSED1							= 16,	///< Unused
+	SENSOR_INFRARED							= 17,	///< Infrared receiver
+	SENSOR_BUTTONS							= 18,	///< Buttons
+	SENSOR_DISTANCE							= 19,	///< Distance travelled
+	SENSOR_ANGLE							= 20,	///< Angle turned
+	SENSOR_CHARGING_STATE					= 21,	///< Charging state
+	SENSOR_VOLTAGE							= 22,	///< Battery voltage
+	SENSOR_CURRENT							= 23,	///< Battery current
+	SENSOR_BATTERY_TEMPERATURE				= 24,	///< Battery temperature
+	SENSOR_BATTERY_CHARGE					= 25,	///< Battery charge
+	SENSOR_BATTERY_CAPACITY					= 26,	///< Battery capacity
+	SENSOR_WALL_SIGNAL						= 27,	///< Wall analog signal
+	SENSOR_CLIFF_LEFT_SIGNAL				= 28,	///< Left cliff analog signal
+	SENSOR_CLIFF_FRONT_LEFT_SIGNAL			= 29,	///< Front left cliff analog signal
+	SENSOR_CLIFF_FRONT_RIGHT_SIGNAL			= 30,	///< Front right cliff analog signal
+	SENSOR_CLIFF_RIGHT_SIGNAL				= 31,	///< Right cliff analog signal
+	SENSOR_CARGO_BAY_DIGITAL_INPUTS			= 32,	///< Cargo bay digital inputs
+	SENSOR_CARGO_BAY_ANALOG_SIGNAL			= 33,	///< Cargo bay analog input
+	SENSOR_CHARGING_SOURCES_AVAILABLE		= 34,	///< Charging sources available
+	SENSOR_OI_MODE							= 35,	///< Open Interface (OI) mode
+	SENSOR_SONG_NUMBER						= 36,	///< Song number
+	SENSOR_SONG_PLAYING						= 37,	///< Song playing?
+	SENSOR_NUMBER_OF_STREAM_PACKETS			= 38,	///< Number of packets in sensor stream
+	SENSOR_REQUESTED_VELOCITY				= 39,	///< Requested drive velocity
+	SENSOR_REQUESTED_RADIUS					= 40,	///< Requested drive radius
+	SENSOR_REQUESTED_RIGHT_VELOCITY			= 41,	///< Requested right wheel velocity
+	SENSOR_REQUESTED_LEFT_VELOCITY			= 42	///< Requested left wheel velocity
+} irobotSensorCode;
+
+// iRobot sensor packet sizes
+#define SENSOR_GROUP0_SIZE							26	///< Size of the SENSOR_GROUP0 packet
+#define SENSOR_GROUP1_SIZE							10	///< Size of the SENSOR_GROUP1 packet
+#define SENSOR_GROUP2_SIZE							6	///< Size of the SENSOR_GROUP2 packet
+#define SENSOR_GROUP3_SIZE							10	///< Size of the SENSOR_GROUP3 packet
+#define SENSOR_GROUP4_SIZE							14	///< Size of the SENSOR_GROUP4 packet
+#define SENSOR_GROUP5_SIZE							12	///< Size of the SENSOR_GROUP5 packet
+#define SENSOR_GROUP6_SIZE							52	///< Size of the SENSOR_GROUP6 packet
+#define SENSOR_BUMPS_WHEELDROPS_SIZE				1	///< Size of the BUMPS_WHEELDROPS packet
+#define SENSOR_WALL_SIZE							1	///< Size of the WALL_SIZE packet
+#define SENSOR_CLIFF_LEFT_SIZE						1	///< Size of the CLIFF_LEFT packet
+#define SENSOR_CLIFF_FRONT_LEFT_SIZE				1	///< Size of the CLIFF_FRONT_LEFT packet
+#define SENSOR_CLIFF_FRONT_RIGHT_SIZE				1 	///< Size of the CLIFF_FRONT_RIGHT packet
+#define SENSOR_CLIFF_RIGHT_SIZE						1 	///< Size of the CLIFF_RIGHT packet
+#define SENSOR_VIRTUAL_WALL_SIZE					1 	///< Size of the VIRUAL_WALL packet
+#define SENSOR_LOW_SIDE_DRIVER_WHEEL_OVERDRIVE_SIZE	1 	///< Size of the LOW_SIDE_DRIVER_WHEEL_OVERDRIVE packet
+#define SENSOR_UNUSED0_SIZE							1 	///< Size of the UNUSED0 packet
+#define SENSOR_UNUSED1_SIZE							1 	///< Size of the UNUSED1 packet
+#define SENSOR_INFRARED_SIZE						1 	///< Size of the INFRARED packet
+#define SENSOR_BUTTONS_SIZE							1 	///< Size of the BUTTONS packet
+#define SENSOR_DISTANCE_SIZE						2 	///< Size of the DISTANCE packet
+#define SENSOR_ANGLE_SIZE							2 	///< Size of the ANGLE packet
+#define SENSOR_CHARGING_STATE_SIZE					1 	///< Size of the CHARGING_STATE packet
+#define SENSOR_VOLTAGE_SIZE							2 	///< Size of the VOLTAGE packet
+#define SENSOR_CURRENT_SIZE							2 	///< Size of the CURRENT packet
+#define SENSOR_BATTERY_TEMPERATURE_SIZE				1 	///< Size of the BATTERY_TEMPERATURE packet
+#define SENSOR_BATTERY_CHARGE_SIZE					2 	///< Size of the BATTERY_CHARGE packet
+#define SENSOR_BATTERY_CAPACITY_SIZE				2 	///< Size of the BATTERY_CAPACITY packet
+#define SENSOR_WALL_SIGNAL_SIZE						2 	///< Size of the WALL_SIGNAL packet
+#define SENSOR_CLIFF_LEFT_SIGNAL_SIZE				2 	///< Size of the CLIFF_LEFT_SIGNAL packet
+#define SENSOR_CLIFF_FRONT_LEFT_SIGNAL_SIZE			2 	///< Size of the CLIFF_FRONT_LEFT_SIGNAL packet
+#define SENSOR_CLIFF_FRONT_RIGHT_SIGNAL_SIZE		2 	///< Size of the CLIFF_FRONT_RIGHT_SIGNAL packet
+#define SENSOR_CLIFF_RIGHT_SIGNAL_SIZE				2 	///< Size of the CLIFF_RIGHT_SIGNAL packet
+#define SENSOR_CARGO_BAY_DIGITAL_INPUTS_SIZE		1 	///< Size of the CARGO_BAY_DIGITAL_INPUTS packet
+#define SENSOR_CARGO_BAY_ANALOG_SIGNAL_SIZE			2 	///< Size of the CARGO_BAY_ANALOG_SIGNAL packet
+#define SENSOR_CHARGING_SOURCES_AVAILABLE_SIZE		1 	///< Size of the CHARGING_SOURCES_AVAILABLE packet
+#define SENSOR_OI_MODE_SIZE							1 	///< Size of the OI_MODE packet
+#define SENSOR_SONG_NUMBER_SIZE						1 	///< Size of the SONG_NUMBER packet
+#define SENSOR_SONG_PLAYING_SIZE					1 	///< Size of the SONG_PLAYING packet
+#define SENSOR_NUMBER_OF_STREAM_PACKETS_SIZE		1 	///< Size of the NUMBER_OF_STREAM_PACKETS packet
+#define SENSOR_REQUESTED_VELOCITY_SIZE				2 	///< Size of the REQUESTED_VELOCITY packet
+#define SENSOR_REQUESTED_RADIUS_SIZE				2 	///< Size of the REQUESTED_RADIUS packet
+#define SENSOR_REQUESTED_RIGHT_VELOCITY_SIZE		2 	///< Size of the REQUESTED_RIGHT_VELOCITY packet
+#define SENSOR_REQUESTED_LEFT_VELOCITY_SIZE			2 	///< Size of the REQUESTED_LEFT_VELOCITY packet
+
+/// Minimum sensor update period, in ms
+#define SENSOR_MIN_UPDATE_PERIOD	15
+
+/// Next highest power of 2 that is greater than any iRobot packet size;
+///		used to create stream buffers large enough to hold any packet.
+#define SENSOR_SIZE_UPPER_BOUND		64
+
+/// iRobot bump and wheel-drop sensors.
+typedef struct{
+	bool	wheeldropCaster;	///< State of the caster wheeldrop sensor; when true, indicates the wheel is not in contact with the ground.
+	bool	wheeldropLeft;		///< State of the left wheeldrop sensor; when true, indicates the wheel is not in contact with the ground.
+	bool	wheeldropRight;		///< State of the right wheeldrop sensor; when true, indicates the wheel is not in contact with the ground.
+	bool	bumpLeft;			///< State of the left bump sensor; if true, the left side of the robot is in contact with an object.
+	bool	bumpRight;			///< State of the right bump sensor; if true, the right side of the robot is in contact with an object.
+} irobotBumps_WheelDrops_t;
+
+/// iRobot button sensors.
+typedef struct{
+	bool	advance;			///< advance button
+	bool	play;				///< play button
+} irobotButtons_t;
+
+/// iRobot cargo bay digital inputs.
+typedef struct{
+	bool	digitalInput0;		///< digital input pin 0
+	bool	digitalInput1;		///< digital input pin 1
+	bool	digitalInput2;		///< digital input pin 2
+	bool	digitalInput3;		///< digital input pin 3
+	bool	deviceDetect;		///< device detect pin
+} irobotCargoBayDigitalInputs_t;
+
+/// iRobot charging source sensors.
+typedef struct{
+	bool	internalCharger;	///< internal charger
+	bool	homeBase;			///< home docking station
+} irobotChargingSourcesAvailable_t;
+
+/// iRobot charging state sensor.
+typedef enum{
+	CHARGING_STATE_NOT_CHARGING				= 0,	///< Robot is not charging
+	CHARGING_STATE_RECONDITION_CHARGING		= 1,	///< Robot is in reconditioning charge mode
+	CHARGING_STATE_FULL_CHARGING			= 2,	///< Robot has full charge and is charging
+	CHARGING_STATE_TRICKLE_CHARGING			= 3,	///< Robot is trickle charging
+	CHARGING_STATE_WAITING					= 4,	///< Robot is waiting to charge
+	CHARGING_STATE_CHARGING_FAULT_CONDITION	= 5		///< Robot has a charge fault
+} irobotChargingState_t;
+
+/// iRobot low-side driver and wheel overcurrent sensors.
+typedef struct{
+	bool	lowSideDriver0;		///< Overcurrent sensor for low-side driver 0; if true, the device has drawn too much current and has been shut down.
+	bool	lowSideDriver1;		///< Overcurrent sensor for low-side driver 1; if true, the device has drawn too much current and has been shut down.
+	bool	lowSideDriver2;		///< Overcurrent sensor for low-side driver 2; if true, the device has drawn too much current and has been shut down.
+	bool	leftWheel;			///< Overcurrent sensor for the left wheel; if true, the device has drawn too much current and has been shut down.
+	bool	rightWheel;			///< Overcurrent sensor for the right wheel; if true, the device has drawn too much current and has been shut down.
+} irobotLowSideDriver_WheelOvercurrent_t;
+
+/// Mode (full, safe, passive) of the iRobot.
+typedef enum{
+	OISTATE_OFF		= 0,	///< Off mode
+	OISTATE_PASSIVE	= 1,	///< Passive mode
+	OISTATE_SAFE	= 2,	///< Safe mode
+	OISTATE_FULL	= 3		///< Full mode
+} irobotOIState_t;
+
+/// Sensor Group 0
+struct irobotSensorGroup0_t{
+	/// iRobot bump and wheel-drop sensors.
+	irobotBumps_WheelDrops_t bumps_wheelDrops;
+
+	///Binary interpretation of the infrared wall sensor; if true, the sensor has read above a predefined threshold and indicates a wall (or object) is in	front of the robot.
+	bool wall;
+
+	/// Binary interpretation of the left cliff sensor; if true, the sensor has read below a predefined threshold and indicates the sensor is not immediately above ground.
+	bool cliffLeft;
+	/// Binary interpretation of the front left cliff sensor; if true, the sensor has read below a predefined threshold and indicates the sensor is not immediately above ground.
+	bool cliffFrontLeft;
+	/// Binary interpretation of the front right cliff sensor; if true, the sensor has read below a predefined threshold and indicates the sensor is not immediately above ground.
+	bool cliffFrontRight;
+	/// Binary interpretation of the right cliff sensor; if true, the sensor has read below a predefined threshold and indicates the sensor is not immediately above ground.
+	bool cliffRight;
+
+	/// Virtual Wall sensor is a particular infrared packet omitted by a virtual wall device, and received by the IR on top of the robot. If the signal is received, the value is true.
+	bool virtualWall;
+
+	/// iRobot low-side driver and wheel overcurrent sensors.
+	irobotLowSideDriver_WheelOvercurrent_t lowSideDriver_WheelOvercurrent;
+
+	/// Most recently received byte from the IR receiver. A value of 0xFF (255) indicates no byte is being received.
+	uint8_t infrared;
+
+	/// iRobot button sensors.
+	irobotButtons_t buttons;
+
+	/// Distance (in mm) the robot has traveled since the last sensor packet.
+	int16_t distance;
+
+	/// Angle (in degrees) through which the robot has rotated since the last sensor packet.
+	int16_t angle;
+
+	/// iRobot charging state sensor.
+	irobotChargingState_t chargingState;
+	
+	/// Voltage of the iRobot battery, in mV.
+	uint16_t voltage;
+
+	/// Current (mA) flowing into or out of the battery. Negative currents indicate current is leaving the battery; positive currents (present in charging) indicate current is entering the battery.
+	int16_t current;
+	
+	/// Temperature of the battery, in degrees Celcius.
+	int8_t batteryTemperature;
+
+	/// Current charge of the create battery, in mAh.
+	uint16_t batteryCharge;
+	
+	/// Estimated charging capacity of the battery, in mAh.
+	uint16_t batteryCapacity;
+};
+
+/// Sensor Group 1
+struct irobotSensorGroup1_t {
+	/// iRobot bump and wheel-drop sensors.
+	irobotBumps_WheelDrops_t bumps_wheelDrops;
+
+	/// Binary interpretation of the infrared wall sensor; if true, the sensor has read above a predefined threshold and indicates a wall (or object) is in	front of the robot.
+	bool wall;
+
+	/// Binary interpretation of the left cliff sensor; if true, the sensor has read below a predefined threshold and indicates the sensor is not immediately above ground.
+	bool cliffLeft;
+	/// Binary interpretation of the front left cliff sensor; if true, the sensor has read below a predefined threshold and indicates the sensor is not immediately above ground.
+	bool cliffFrontLeft;
+	/// Binary interpretation of the front right cliff sensor; if true, the sensor has read below a predefined threshold and indicates the sensor is not immediately above ground.
+	bool cliffFrontRight;
+	/// Binary interpretation of the right cliff sensor; if true, the sensor has read below a predefined threshold and indicates the sensor is not immediately above ground.
+	bool cliffRight;
+
+	/// Virtual Wall sensor is a particular infrared packet omitted by a virtual wall device, and received by the IR on top of the robot. If the signal is received, the value is true.
+	bool virtualWall;
+
+	/// iRobot low-side driver and wheel overcurrent sensors.
+	irobotLowSideDriver_WheelOvercurrent_t lowSideDriver_wheelovercurrent;
+};
+
+/// Sensor Group 2
+struct irobotSensorGroup2_t {
+	/// Most recently received byte from the IR receiver. A value of 0xFF (255) indicates no byte is being received.
+	uint8_t infrared;
+
+	/// iRobot button sensors.
+	irobotButtons_t buttons;
+
+	/// Distance (in mm) the robot has traveled since the last sensor packet.
+	int16_t distance;
+
+	/// Angle (in degrees) through which the robot has rotated since the last sensor packet.
+	int16_t angle;
+};
+
+/// Sensor Group 3
+struct irobotSensorGroup3_t {
+	/// iRobot charging state sensor.
+	irobotChargingState_t chargingState;
+	
+	/// Voltage of the iRobot battery, in mV.
+	uint16_t voltage;
+
+	/// Current (mA) flowing into or out of the battery. Negative currents indicate current is leaving the battery; positive currents (present in charging) indicate current is entering the battery.
+	int16_t current;
+	
+	/// Temperature of the battery, in degrees Celcius.
+	int8_t batteryTemperature;
+
+	/// Current charge of the create battery, in mAh.
+	uint16_t batteryCharge;
+	
+	/// Estimated charging capacity of the battery, in mAh.
+	uint16_t batteryCapacity;
+};
+
+/// Sensor Group 4
+struct irobotSensorGroup4_t {
+	uint16_t	wallSignal;				///< Sampled value of the analog wall sensor, range 0-4095.
+	uint16_t	cliffLeftSignal;		///< Sampled value of the analog left cliff sensor, range 0-4095.
+	uint16_t	cliffFrontLeftSignal;	///< Sampled value of the analog front left cliff sensor, range 0-4095.
+	uint16_t	cliffFrontRightSignal;	///< Sampled value of the analog front right cliff sensor, range 0-4095.
+	uint16_t	cliffRightSignal;		///< Sampled value of the analog right cliff sensor, range 0-4095.
+
+	/// digital inputs
+	irobotCargoBayDigitalInputs_t	cargoBayDigitalInputs;
+
+	/// sampled cargo bay analog line; range 0-1023
+	uint16_t	cargoBayAnalogSignal;
+
+	/// charging sources available
+	irobotChargingSourcesAvailable_t	chargingSourcesAvailable;
+};
+
+/// Sensor Group 5
+struct irobotSensorGroup5_t {
+	/// irobot OI mode
+	irobotOIState_t	oiState;
+
+	uint8_t			songNumber;		///< index of the song that is loaded or is playing
+	bool			songPlaying;	///< song is playing?
+
+	uint8_t			nStreamPackets;	///< number of packets in each stream broadcast
+
+	int16_t			requestedVelocity;	///< requested velocity, in mm/s for DRIVE mode
+	int16_t			requestedRadius;	///< requested radius, in mm for DRIVE mode
+
+	int16_t			requestedRightWheelVelocity;	///< requested right wheel velocity in mm/s for DRIVE_DIRECT mode
+	int16_t			requestedLeftWheelVelocity;		///< requested left wheel velocity in mm/s for DRIVE_DIRECT mode
+};
+
+/// Sensor Group 6
+struct irobotSensorGroup6_t {
+	/// iRobot bump and wheel-drop sensors.
+	irobotBumps_WheelDrops_t bumps_wheelDrops;
+
+	/// Binary interpretation of the infrared wall sensor; if true, the sensor has read above a predefined threshold and indicates a wall (or object) is in	front of the robot.
+	bool wall;
+
+	/// Binary interpretation of the left cliff sensor; if true, the sensor has read below a predefined threshold and indicates the sensor is not immediately above ground.
+	bool cliffLeft;
+	/// Binary interpretation of the front left cliff sensor; if true, the sensor has read below a predefined threshold and indicates the sensor is not immediately above ground.
+	bool cliffFrontLeft;
+	/// Binary interpretation of the front right cliff sensor; if true, the sensor has read below a predefined threshold and indicates the sensor is not immediately above ground.
+	bool cliffFrontRight;
+	/// Binary interpretation of the right cliff sensor; if true, the sensor has read below a predefined threshold and indicates the sensor is not immediately above ground.
+	bool cliffRight;
+
+	/// Virtual Wall sensor is a particular infrared packet omitted by a virtual wall device, and received by the IR on top of the robot. If the signal is received, the value is true.
+	bool virtualWall;
+
+	/// iRobot low-side driver and wheel overcurrent sensors.
+	irobotLowSideDriver_WheelOvercurrent_t lowSideDriver_WheelOvercurrent;
+
+	/// Most recently received byte from the IR receiver. A value of 0xFF (255) indicates no byte is being received.
+	uint8_t infrared;
+
+	/// iRobot button sensors.
+	irobotButtons_t buttons;
+
+	/// Distance (in mm) the robot has traveled since the last sensor packet.
+	int16_t distance;
+
+	/// Angle (in degrees) through which the robot has rotated since the last sensor packet.
+	int16_t angle;
+
+	/// iRobot charging state sensor.
+	irobotChargingState_t chargingState;
+	
+	/// Voltage of the iRobot battery, in mV.
+	uint16_t voltage;
+
+	/// Current (mA) flowing into or out of the battery. Negative currents indicate current is leaving the battery; positive currents (present in charging) indicate current is entering the battery.
+	int16_t current;
+	
+	/// Temperature of the battery, in degrees Celcius.
+	int8_t batteryTemperature;
+
+	/// Current charge of the create battery, in mAh.
+	uint16_t batteryCharge;
+	
+	///  Estimated charging capacity of the battery, in mAh.
+	uint16_t batteryCapacity;
+
+	uint16_t	wallSignal;				///< Sampled value of the analog wall sensor, range 0-4095.
+	uint16_t	cliffLeftSignal;		///< Sampled value of the analog left cliff sensor, range 0-4095.
+	uint16_t	cliffFrontLeftSignal;	///< Sampled value of the analog front left cliff sensor, range 0-4095.
+	uint16_t	cliffFrontRightSignal;	///< Sampled value of the analog front right cliff sensor, range 0-4095.
+	uint16_t	cliffRightSignal;		///< Sampled value of the analog right cliff sensor, range 0-4095.
+
+	/// digital inputs
+	irobotCargoBayDigitalInputs_t	cargoBayDigitalInputs;
+
+	/// sampled cargo bay analog line; range 0-1023
+	uint16_t	cargoBayAnalogSignal;
+
+	/// charging sources available
+	irobotChargingSourcesAvailable_t	chargingSourcesAvailable;
+
+	/// irobot OI mode
+	irobotOIState_t	oiState;
+
+	uint8_t			songNumber;		///< index of the song that is loaded or is playing
+	bool			songPlaying;	///< song is playing?
+
+	uint8_t			nStreamPackets;	///< number of packets in each stream broadcast
+
+	int16_t			requestedVelocity;	///< requested velocity, in mm/s for DRIVE mode
+	int16_t			requestedRadius;	///< requested radius, in mm for DRIVE mode
+
+	int16_t			requestedRightWheelVelocity;	///< requested right wheel velocity in mm/s for DRIVE_DIRECT mode
+	int16_t			requestedLeftWheelVelocity;		///< requested left wheel velocity in mm/s for DRIVE_DIRECT mode
+};
+
+
+#endif // _IROBOT_SENSORTYPES_H
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/WifiRobot/RoombaControl/irobot/irobotTime.cpp	Tue Dec 09 05:06:37 2014 +0000
@@ -0,0 +1,15 @@
+#include "irobotTime.h"
+
+#ifdef _WIN32
+	#include <windows.h>
+#elif defined(__unix__)
+	#include <unistd.h>
+#endif
+
+void irobotDelayMs(const int32_t ms){
+	#ifdef _WIN32
+		Sleep(ms);
+	#elif defined(__unix__)
+		usleep((ms) * 1000);
+	#endif
+}
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/WifiRobot/RoombaControl/irobot/irobotTime.h Tue Dec 09 05:06:37 2014 +0000 @@ -0,0 +1,25 @@ +/** \file irobotTime.h + * + * Abstraction layer for timing functions; architecture or OS-specific timing + * functions are referenced here. + * + * \author Jeff C. Jensen + * \date 2013-12-09 + * \copyright Copyright (C) 2013, Jeff C. Jensen, Edward A. Lee, and Sanjit A. Seshia. + * This software accompanies An Introductory Lab in Embedded and Cyber-Physical Systems + * and is licensed under a Creative Commons Attribution-NonCommercial-NoDerivs 3.0 + * Unported License. See http://leeseshia.org/lab. + */ + +#ifndef IROBOT_TIME_H +#define IROBOT_TIME_H + +#include <stdint.h> + +/// delay this process a fixed number of milliseconds +void irobotDelayMs( + const int32_t ms ///< delay in ms +); + + +#endif /* IROBOT_TIME_H */
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/WifiRobot/RoombaControl/irobot/irobotTypes.h Tue Dec 09 05:06:37 2014 +0000 @@ -0,0 +1,50 @@ +/** \file irobotTypes.h + * + * Boolean and bit-level functions; common data types + * + * \author Jeff C. Jensen + * \date 2013-12-09 + * \copyright Copyright (C) 2013, Jeff C. Jensen, Edward A. Lee, and Sanjit A. Seshia. + * This software accompanies An Introductory Lab in Embedded and Cyber-Physical Systems + * and is licensed under a Creative Commons Attribution-NonCommercial-NoDerivs 3.0 + * Unported License. See http://leeseshia.org/lab. + */ + +#ifndef _IROBOTTYPES_H +#define _IROBOTTYPES_H + +#include <stdint.h> +#ifdef _MSC_VER + #ifndef __BOOL_DEFINED + typedef uint8_t bool; + #define true ( (bool)1 ) + #define false ( (bool)0 ) + #define __BOOL_DEFINED + #endif +#else + #include <stdbool.h> +#endif +#include <stddef.h> + +// Byte-level operations - extract bytes from 16 and 32-bit numbers +#define LO(x) ((x) & 0xFF) ///< Low order byte of a 16 bit number +#define HO(x) ((x) >> 0x08) ///< High order byte of a 16 bit number +#define LLO(x) ((x) & 0xFF) ///< Byte 0 (lowest order) byte of a 32-bit number +#define LHO(x) (((x) >> 0x08) & 0xFF) ///< Byte 1 of a 32-bit number +#define HLO(x) (((x) >> 0x10) & 0xFF) ///< Byte 2 of a 32-bit number +#define HHO(x) ((x) >> 0x18) ///< Byte 3 (highest order) byte of a 32-bit number + +// Byte-level operations - reconstruct 16 and 32-bit numbers from constituent bytes +#define MLO(x) ((uint16_t)( ((uint8_t)(x)) & 0xFF )) ///< Convert a byte to Byte 0 of a 16-bit number +#define MHO(x) ((uint16_t)( MLO(x) << 0x08 ) ) ///< Convert a byte to Byte 1 of a 16-bit number +#define MLLO(x) ((uint32_t)( MLO(x) ) ) ///< Convert a byte to Byte 0 of a 32-bit number +#define MLHO(x) ((uint32_t)( (uint32_t)MHO(x) ) ) ///< Convert a byte to Byte 1 of a 32-bit number +#define MHLO(x) ((uint32_t)( ((uint32_t)MLO(x)) << 0x10 ) ) ///< Convert a byte to Byte 2 of a 32-bit number +#define MHHO(x) ((uint32_t)( ((uint32_t)MLO(x)) << 0x18 ) ) ///< Convert a byte to Byte 3 of a 32-bit number + +// Gives a byte-level checksum of a number +#define CX8(x) ((uint8_t)x) ///< Byte-level checksum of an 8-bit number (identity function) +#define CX16(x) ((uint8_t)(HO(x) + LO(x)) ) ///< Byte-level checksum of a 16-bit number; sum of two bytes +#define CX32(x) ((uint8_t)(HHO(x) + HLO(x) + LHO(x) + LLO(x))) ///< Byte-level checksum of a 32-bit number; sum of four bytes + +#endif // _IROBOTTYPES_H
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/WifiRobot/RoombaControl/irobot/irobotUART.cpp	Tue Dec 09 05:06:37 2014 +0000
@@ -0,0 +1,150 @@
+#include "irobotUART.h"
+
+/*
+Implementation for iRobot Create UART connection using mbed, Freescale KL25Z
+
+(This implementation is architecture specific and relies on the Serial class
+    in the mbed SDK and TimeoutMultipleSerial, which was written for this project)
+
+The interface was written by Jeff C. Jensen, 2013-12-09 and is 
+    Copyright (C) 2013, Jeff C. Jensen, Edward A. Lee, and Sanjit A. Seshia.
+ 	This software accompanies An Introductory Lab in Embedded and Cyber-Physical Systems 			      and is licensed under a Creative Commons Attribution-NonCommercial-NoDerivs 3.0
+
+The implementation was written by Eric Wu, 2014-11-10, and is based heavily off of the 
+    original implementation by Jeff C. Jensen.
+*/
+
+/// Convert a baud code into its actual rate
+/// \return error code
+static int32_t irobotUARTBaudCodeToRate(
+	const irobotBaud_t	baud,		///< [in]	baud code
+	int* const	rate		///< [out]	baud rate
+){
+	if(!rate){
+		return ERROR_INVALID_PARAMETER;
+	}
+	else{
+		switch(baud){
+		case IROBOT_BAUD_300:	*rate = 300;	break;
+		case IROBOT_BAUD_600:	*rate = 600;	break;
+		case IROBOT_BAUD_1200:	*rate = 1200;	break;
+		case IROBOT_BAUD_2400:	*rate = 2400;	break;
+		case IROBOT_BAUD_4800:	*rate = 4800;	break;
+		case IROBOT_BAUD_9600:	*rate = 9600;	break;
+		case IROBOT_BAUD_14400:	*rate = 14400;	break;
+		case IROBOT_BAUD_19200:	*rate = 19200;	break;
+		case IROBOT_BAUD_28800:	*rate = 28800;	break;
+		case IROBOT_BAUD_38400:	*rate = 38400;	break;
+		case IROBOT_BAUD_57600:	*rate = 57600;	break;
+		case IROBOT_BAUD_115200:*rate = 115200;	break;	// WARNING: UNSTABLE
+		default:
+			*rate = 0;
+			return ERROR_INVALID_PARAMETER;
+			break;
+		}
+
+		return ERROR_SUCCESS;
+	}
+}
+
+int32_t irobotUARTOpen(
+    const irobotUARTPort_t port,
+    const irobotBaud_t baud) {
+
+    int32_t status = ERROR_SUCCESS;
+    int baudRate = 0;
+
+    irobot_StatusMerge(&status, irobotUARTBaudCodeToRate(baud, &baudRate));
+
+    if (!irobot_IsError(status)) {
+        port->setBaud(baudRate);
+        port->setFormat(8, Serial::None, 1);
+    }
+
+    return status;
+}
+
+int32_t irobotUARTClose(const irobotUARTPort_t port) {
+    return ERROR_SUCCESS;
+}
+
+int32_t irobotUARTRead(
+    const irobotUARTPort_t port,
+    xqueue_t* const queue,
+    size_t nData) {
+
+    // catch NULL pointers
+    int32_t status = ERROR_SUCCESS;
+    if (!queue) {
+        irobot_StatusMerge(&status, ERROR_INVALID_PARAMETER);
+    }
+
+    // read
+    while (!irobot_IsError(status) && nData--) {
+        uint8_t rxByte = 0;
+        irobot_StatusMerge(&status, irobotUARTReadRaw(port, &rxByte, 1));
+        if (!irobot_IsError(status)) {
+            xqueue_push8(queue, rxByte);
+        }
+    }
+
+    return status;
+}
+
+int32_t irobotUARTReadRaw(
+    const irobotUARTPort_t port,
+    uint8_t* const data,
+    const size_t nData) {
+
+    if (!data) {
+        return ERROR_INVALID_PARAMETER;
+    } else {
+        int status = port->readMultChars(data, nData);
+        if (status == -1) return ERROR_TIMEOUT;
+        return ERROR_SUCCESS;
+    }
+}
+
+int32_t irobotUARTWrite(
+    const irobotUARTPort_t port,
+    xqueue_t* const queue) {
+
+	int32_t status = ERROR_SUCCESS;
+
+	// catch NULL pointers
+	if(!queue){
+		irobot_StatusMerge(&status, ERROR_INVALID_PARAMETER);
+	}
+	
+	// write
+	while(!irobot_IsError(status) && !xqueue_empty(queue)){
+		uint8_t txByte = xqueue_front(queue);
+		irobot_StatusMerge(&status, irobotUARTWriteRaw(port, &txByte, 1));
+		if(!irobot_IsError(status)){
+			xqueue_drop(queue);
+		}
+	}
+
+	return status;
+
+}
+
+int32_t irobotUARTWriteRaw(
+    const irobotUARTPort_t port,
+    const uint8_t* const data,
+    const size_t nData) {
+
+    if (!data) {
+        return ERROR_INVALID_PARAMETER;
+    } else {
+        int status = port->writeMultChars(data, nData);
+        if (status == -1) return ERROR_TIMEOUT;
+        return ERROR_SUCCESS;
+    }
+}
+
+int32_t irobotUARTClear(
+    const irobotUARTPort_t port) {
+    port->clearAll();
+    return ERROR_SUCCESS;
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/WifiRobot/RoombaControl/irobot/irobotUART.h	Tue Dec 09 05:06:37 2014 +0000
@@ -0,0 +1,104 @@
+/** \file irobotUART.h
+ *
+ * UART wrappers for the iRobot Create. This library is not architecture
+				specific, so these are only wrappers for UART functions that must
+				be defined for your architecture.
+ *
+ * \author Jeff C. Jensen
+ * \date 2013-12-09
+ * \copyright Copyright (C) 2013, Jeff C. Jensen, Edward A. Lee, and Sanjit A. Seshia.
+ * 			  This software accompanies An Introductory Lab in Embedded and Cyber-Physical Systems
+ * 			  and is licensed under a Creative Commons Attribution-NonCommercial-NoDerivs 3.0
+ * 			  Unported License. See http://leeseshia.org/lab.
+
+ * Dependencies and typedef for irobotUARTPort_t modified to
+        support implementation for mbed
+ */
+
+#ifndef _IROBOT_UART_H
+#define _IROBOT_UART_H
+
+#include "irobotTypes.h"
+#include "irobotError.h"
+#include "xqueue.h"
+#include "mbed.h"
+#include "TimeoutMultipleSerial.h"
+//#include "UART.h"
+
+/// UART port wrapper; change for your UART API
+//typedef MyRio_Uart * irobotUARTPort_t;
+typedef TimeoutMultipleSerial* irobotUARTPort_t;
+
+/// Baud rate codes
+typedef enum{
+	IROBOT_BAUD_300		= 0,	///< UART baud rate 300bps
+	IROBOT_BAUD_600		= 1,	///< UART baud rate 600bps
+	IROBOT_BAUD_1200	= 2,	///< UART baud rate 1200bps
+	IROBOT_BAUD_2400	= 3,	///< UART baud rate 2400bps
+	IROBOT_BAUD_4800	= 4,	///< UART baud rate 4800bps
+	IROBOT_BAUD_9600	= 5,	///< UART baud rate 9600bps
+	IROBOT_BAUD_14400	= 6,	///< UART baud rate 14400bps
+	IROBOT_BAUD_19200	= 7,	///< UART baud rate 19200bps
+	IROBOT_BAUD_28800	= 8,	///< UART baud rate 28800bps
+	IROBOT_BAUD_38400	= 9,	///< UART baud rate 38400bps
+	IROBOT_BAUD_57600	= 10,	///< UART baud rate 57600bps
+	IROBOT_BAUD_115200	= 11	///< UART baud rate 115200bps	\warning UNSTABLE
+} irobotBaud_t;
+
+/// Opens a UART session configured for the iRobot
+/// \return error code
+int32_t irobotUARTOpen(
+	const irobotUARTPort_t	port,		///< [in] UART port
+	const irobotBaud_t		baud		///< [in] baud rate of the port
+);
+
+/// Closes the UART port connected to iRobot. The port must be reinitialized before reuse.
+/// \return error code
+int32_t irobotUARTClose(
+	const irobotUARTPort_t	port		///< [in] UART port
+);
+
+/// Read data from the UART receive buffer until # have been
+/// received, or until a timeout occurs. A negative timeout means wait indefinitely.
+/// Read bytes are pushed to the queue; if the queue is full, its oldest bytes are dropped.
+/// \return error code
+int32_t irobotUARTRead(
+	const irobotUARTPort_t	port,		///< [in] UART port
+	xqueue_t * const		queue,		///< [out]Queue to receive read data
+	size_t					nData		///< [in] Number of bytes to read
+);
+
+/// Read data from the UART receive buffer until # have been
+/// received, or until a timeout occurs. A negative timeout means wait indefinitely.
+/// \return error code
+int32_t irobotUARTReadRaw(
+	const irobotUARTPort_t	port,		///< [in] UART port
+	uint8_t * const			data,		///< [out]Buffer to receive read data
+	const size_t			nData		///< [in] Number of bytes to read
+);
+
+/// Writes a queue to the UART port. If not enough space is available in the FIFO,
+/// this function blocks until sufficient space is available or a timeout occurs.
+/// Elements written are popped from the queue.
+/// \return error code
+int32_t irobotUARTWrite(
+	const irobotUARTPort_t	port,		///< [in] UART port to access
+	xqueue_t * const		queue		///< [in] Queue data to write; all will be written
+);
+
+/// Writes data to the UART port. If not enough space is available in the FIFO,
+/// this function blocks until sufficient space is available or a timeout occurs.
+/// \return error code
+int32_t irobotUARTWriteRaw(
+	const irobotUARTPort_t	port,		///< [in] UART port to access
+	const uint8_t * const	data,		///< [in] Array of data to write
+	const size_t			nData		///< [in] Size of data array
+);
+
+/// Clears the UART receive buffer.
+/// \return error code
+int32_t irobotUARTClear(
+	const irobotUARTPort_t	port		///< [in] UART port to access
+);
+
+#endif	// _IROBOT_UART_H
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/WifiRobot/RoombaControl/irobot/xqueue.cpp	Tue Dec 09 05:06:37 2014 +0000
@@ -0,0 +1,143 @@
+#include "xqueue.h"
+
+#ifndef MIN
+	#define MIN(x,y) ( (x) < (y) ? (x) : (y) )
+#endif
+
+void xqueue_init(xqueue_t * const queue, uint8_t * const dataBuffer, const size_t size){
+	queue->capacity = size;
+	queue->capacityMask = size-1;
+	queue->data = dataBuffer;
+	queue->rCount = 0;
+	queue->wCount = 0;
+	queue->head = 0;
+	queue->tail = 0;
+}
+
+size_t xqueue_count(const xqueue_t * const queue){
+	return queue->wCount - queue->rCount;
+}
+
+bool xqueue_empty(const xqueue_t * const queue){
+	return queue->wCount == queue->rCount;
+}
+
+bool xqueue_full(const xqueue_t * const queue){
+	return xqueue_count(queue) >= queue->capacity;
+}
+
+size_t xqueue_space(const xqueue_t * const queue){
+	return queue->capacity - xqueue_count(queue);
+}
+
+uint8_t xqueue_front(const xqueue_t * const queue){
+	return queue->data[queue->tail];
+}
+
+uint8_t xqueue_back(const xqueue_t * const queue){
+	return queue->data[(queue->head - 1) & queue->capacityMask];
+}
+
+uint8_t xqueue_at(const xqueue_t * const queue, const size_t index){
+	return queue->data[(queue->tail + index) & queue->capacityMask];
+}
+
+void xqueue_clear(xqueue_t * const queue){
+	queue->rCount = 0;
+	queue->wCount = 0;
+	queue->head = 0;
+	queue->tail = 0;
+}
+
+uint8_t xqueue_push(xqueue_t * const queue, const uint8_t value){
+	if(xqueue_full(queue))
+		xqueue_drop(queue);
+
+	*(queue->data + queue->head) = value;
+	queue->head = (queue->head + 1) & queue->capacityMask;
+	queue->wCount++;
+	return value;
+}
+
+void xqueue_push16(xqueue_t * const queue, const uint16_t value){
+	xqueue_push8(queue, HO(value));
+	xqueue_push8(queue, LO(value));
+}
+
+void xqueue_push32(xqueue_t * const queue, const uint32_t value){
+	xqueue_push8(queue, HHO(value));
+	xqueue_push8(queue, HLO(value));
+	xqueue_push8(queue, LHO(value));
+	xqueue_push8(queue, LLO(value));
+}
+
+void xqueue_push_buffer(xqueue_t * const queue, const uint8_t * values, const size_t nvalues){
+	size_t ii;
+	if(nvalues >= queue->capacity)
+		return;
+	else if(nvalues > xqueue_space(queue))
+		xqueue_drop_many(queue, nvalues - xqueue_space(queue));
+	
+	for(ii = 0; ii < nvalues; ii++){
+		*(queue->data + queue->head) = *values++;
+		queue->head = (queue->head + 1) & queue->capacityMask;
+	}
+	queue->wCount += ii;
+}
+
+void xqueue_push_string(xqueue_t * const queue, const unsigned char * str){
+	size_t ii;
+	for(ii = 0; *str; ii++){
+		if(xqueue_full(queue))
+			xqueue_drop(queue);
+		*(queue->data + queue->head) = *str++;
+		queue->head = (queue->head + 1) & queue->capacityMask;
+		queue->wCount++;
+	}
+}
+
+uint8_t xqueue_pop(xqueue_t * const queue){
+	uint8_t value = *(queue->data + queue->tail);
+	queue->tail = (queue->tail + 1) & queue->capacityMask;
+	queue->rCount++;
+	return value;
+}
+
+uint16_t xqueue_pop16(xqueue_t * const queue){
+	return MHO(xqueue_pop8(queue)) | MLO(xqueue_pop8(queue));
+}
+
+uint32_t xqueue_pop32(xqueue_t * const queue){
+	return MHHO(xqueue_pop8(queue)) | MHLO(xqueue_pop8(queue)) | MLHO(xqueue_pop8(queue)) | MLLO(xqueue_pop8(queue));
+}
+
+void xqueue_pop_buffer(xqueue_t * const queue,	uint8_t * values, const size_t nvalues){
+	size_t ii;
+	for(ii = 0; ii < nvalues && !xqueue_empty(queue); ii++){
+		*values++ = *(queue->data + queue->tail);
+		queue->tail = (queue->tail + 1) & queue->capacityMask;
+		queue->rCount++;
+	}
+}
+
+void xqueue_drop(xqueue_t * const queue){
+	queue->tail = (queue->tail + 1) & queue->capacityMask;
+	queue->rCount++;
+}
+
+void xqueue_drop_many(xqueue_t * const queue, size_t n){
+	n = MIN(n, xqueue_count(queue));
+
+	queue->tail = (queue->tail + n) & queue->capacityMask;
+	queue->rCount += n;
+}
+
+uint8_t xqueue_checksum(const xqueue_t * const queue, size_t nvalues, const size_t nAdvance){
+	uint8_t cxsum = 0;
+	size_t ii;
+	nvalues = MIN(nvalues, xqueue_count(queue) - nAdvance);
+	for(ii = 0; ii < nvalues; ii++){
+		cxsum += xqueue_at(queue, ii + nAdvance);
+	}
+	return cxsum;
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/WifiRobot/RoombaControl/irobot/xqueue.h	Tue Dec 09 05:06:37 2014 +0000
@@ -0,0 +1,175 @@
+/** \file xqueue.h
+ * 
+ * Definition and prototypes for xqueue data structure. xqueue is designed for use
+ * in communication systems and concurrent environments where two processes may
+ * access the queue, though exclusively one will read and one will write. Read and
+ * write counts are tracked separately for this reason.
+ * 
+ * xqueues are initialized with the address of a buffer and its size, which must
+ * be a power of two. This is to allow for simple circular access to the buffer
+ * via masking, instead using a costly modulo operator.
+ *
+ * \author Jeff C. Jensen
+ * \date 2013-12-09
+ * \copyright Copyright (C) 2013, Jeff C. Jensen, Edward A. Lee, and Sanjit A. Seshia.
+ * 			  This software accompanies An Introductory Lab in Embedded and Cyber-Physical Systems
+ * 			  and is licensed under a Creative Commons Attribution-NonCommercial-NoDerivs 3.0
+ * 			  Unported License. See http://leeseshia.org/lab.
+ */
+
+#ifndef _XQUEUE_H
+#define _XQUEUE_H
+
+#include "irobotTypes.h"
+
+/// xqueue_t structure: queue with arbitrary length.
+/// Separation of write/read count allows for use in concurrent environments
+typedef struct{
+	uint8_t		*data;				///< Assigned on initialization to existing buffer
+	size_t		head;				///< Buffer write index
+	size_t		tail;				///< Buffer read index
+	size_t		rCount;				///< Read count
+	size_t		wCount;				///< Write count
+	size_t		capacity;			///< Maximum size of the data buffer (must be a power of 2, <= 0x8000)
+	size_t		capacityMask;		///< Mask used instead of costly modulo operator
+} xqueue_t;
+
+/// Initialize a queue
+void xqueue_init(
+	xqueue_t * const queue,			///< [out]	Queue struct to initialize
+	uint8_t * const dataBuffer,		///< [out]	Raw buffer to which queue will attach
+	const size_t size				///< [in]	Size of the raw buffer
+);
+
+/// Number of used elements in the queue
+/// \return number of elements in the queue
+size_t xqueue_count(
+	const xqueue_t * const queue	///< [in]	Target queue
+);
+
+/// Whether or not the queue is empty
+/// \return Queue is empty?
+bool xqueue_empty(
+	const xqueue_t * const queue	///< [in]	Target queue
+);
+
+/// Whether or not the queue is full
+/// \return Queue is full?
+bool xqueue_full(
+	const xqueue_t * const queue	///< [in]	Target queue
+);
+
+/// Number of free elements in the queue
+/// \return number of free elements in the queue
+size_t xqueue_space(
+	const xqueue_t * const queue	///< [in]	Target queue
+);
+
+/// Front element of the queue
+/// \return Front element of the queue
+uint8_t xqueue_front(
+	const xqueue_t * const queue	///< [in]	Target queue
+);
+
+/// Return the back (most recently added) element of the queue
+/// \return Back element of the queue
+uint8_t xqueue_back(
+	const xqueue_t * const queue	///< [in]	Target queue
+);
+
+/// Index an element of the queue
+/// \return Indexed element of the queue
+uint8_t xqueue_at(
+	const xqueue_t * const queue,	///< [in]	Target queue
+	const size_t index				///< [in]	Element index
+);
+
+/// Clears a queue; retains buffer address and maximum size
+void xqueue_clear(
+	xqueue_t * const queue			///< [in/out]	Target queue
+);
+
+/// Push a single element on to a queue
+/// \return Value pushed
+uint8_t xqueue_push(
+	xqueue_t * const queue,			///< [in/out]	Target queue
+	const uint8_t value				///< [in]	byte to add to queue
+);
+
+/// Push 8 bits (one element) to a queue
+#define xqueue_push8 xqueue_push
+
+/// Push a 16-bit number to the queue (2 elements)
+void xqueue_push16(
+	xqueue_t * const queue,			///< [in/out]	Target queue
+	const uint16_t value			///< [in]	Element to push
+);
+
+/// Push a 32-bit number to the queue (4 elements)
+void xqueue_push32(
+	xqueue_t * const queue,			///< [in/out]	Target queue
+	const uint32_t value			///< [in]	Element to push
+);
+
+/// Push a stream on to a queue (faster than push_string)
+void xqueue_push_buffer(
+	xqueue_t * const queue,			///< [in/out]	Target queue
+	const uint8_t * values,			///< [in]	Stream to push to queue
+	const size_t nvalues			///< [in]	Number of elements to push
+);
+
+/// Push a (null-terminated) string on to a queue
+void xqueue_push_string(
+	xqueue_t * const queue,			///< [in/out]	Target queue
+	const unsigned char * str		///< [in]	String to push to queue (NULL element is not pushed)
+);
+
+/// Pop an element from a queue
+/// \return Front (removed) element of the queue
+uint8_t xqueue_pop(
+	xqueue_t * const queue			///< [in/out]	Target queue
+);
+
+/// Pop an 8-bit value from a queue
+#define xqueue_pop8	xqueue_pop
+
+/// Pop 16 bits (two elements) from a queue
+/// \return Packed 16-bit integer containing front two (removed) elements of the queue.
+uint16_t xqueue_pop16(
+	xqueue_t * const queue			///< [in/out]	Target queue
+);
+
+/// Pop 32 bits (four elements) from a queue
+/// \return Packed 32-bit integer containing front four (removed) elements of the queue.
+uint32_t xqueue_pop32(
+	xqueue_t * const queue			///< [in/out]	Target queue
+);
+
+/// Pop a sequence of elements from a queue
+void xqueue_pop_buffer(
+	xqueue_t * const queue,			///< [in/out]	Target queue
+	uint8_t * values,				///< [out]	Stream to fill with values
+	const size_t nvalues			///< [in]	Number of elements to pop
+);
+
+/// Pop an element from a queue; do not return value (fast)
+void xqueue_drop(
+	xqueue_t * const queue			///< [in/out]	Target queue
+);
+
+/// Pop many elements from a queue (fast)
+void xqueue_drop_many(
+	xqueue_t * const queue,			///< [in/out]	Target queue
+	size_t nvalues					///< [in]	Number of elements to pop
+);
+
+/// Checksum of n elements currently in the queue
+/// \returns 8-bit checksum of n front elements of the queue, queue[fromCount] to queue[fromCount + nvalues]
+uint8_t xqueue_checksum(
+	const xqueue_t * const queue,	///< [in]	Target queue
+	size_t nvalues,					///< [in]	Number of values over which to sum
+	const size_t nAdvance			///< [in]	Number of elements to advance before calculating checksum
+);
+
+
+#endif	// _XQUEUE_H
Binary file WifiRobot/cc3000/.cc3000.cpp.swp has changed
Binary file WifiRobot/cc3000/.cc3000.h.swp has changed
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/WifiRobot/cc3000/.hg_archival.txt Tue Dec 09 05:06:37 2014 +0000 @@ -0,0 +1,5 @@ +repo: 615c697c33b02e1028cfb99e991857ca8806d8ca +node: ca8c234997c03237b5edf01e8df771254779b98e +branch: default +latesttag: null +latesttagdistance: 41
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/WifiRobot/cc3000/Helper/def.h Tue Dec 09 05:06:37 2014 +0000 @@ -0,0 +1,24 @@ +/* Copyright (C) 2013 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 DEF_H +#define DEF_H + +#include "cmsis.h" + +#endif
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/WifiRobot/cc3000/Socket/Endpoint.cpp	Tue Dec 09 05:06:37 2014 +0000
@@ -0,0 +1,138 @@
+/* Copyright (C) 2013 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 "Socket/Socket.h"
+#include "Socket/Endpoint.h"
+#include "Helper/def.h"
+#include <cstring>
+
+ #include "cc3000.h"
+
+/* Copied from lwip */
+static char *cc3000_inet_ntoa_r(const in_addr addr, char *buf, int buflen)
+{
+  uint32_t s_addr;
+  char inv[3];
+  char *rp;
+  uint8_t *ap;
+  uint8_t rem;
+  uint8_t n;
+  uint8_t i;
+  int len = 0;
+
+  s_addr = addr.s_addr;
+
+  rp = buf;
+  ap = (uint8_t *)&s_addr;
+  for(n = 0; n < 4; n++) {
+    i = 0;
+    do {
+      rem = *ap % (uint8_t)10;
+      *ap /= (uint8_t)10;
+      inv[i++] = '0' + rem;
+    } while(*ap);
+    while(i--) {
+      if (len++ >= buflen) {
+        return NULL;
+      }
+      *rp++ = inv[i];
+    }
+    if (len++ >= buflen) {
+      return NULL;
+    }
+    *rp++ = '.';
+    ap++;
+  }
+  *--rp = 0;
+  return buf;
+}
+
+Endpoint::Endpoint()  {
+    _cc3000_module = cc3000::get_instance();
+    if (_cc3000_module == NULL) {
+        error("Endpoint constructor error: no cc3000 instance available!\r\n");
+    }
+    reset_address();
+}
+Endpoint::~Endpoint() {}
+
+void Endpoint::reset_address(void) {
+    _ipAddress[0] = '\0';
+    std::memset(&_remote_host, 0, sizeof(sockaddr_in));
+}
+
+int Endpoint::set_address(const char* host, const int port) {
+    reset_address();
+
+    char address[5];
+    char *p_address = address;
+
+    signed int add[5];
+
+    // Dot-decimal notation
+    int result = std::sscanf(host, "%3u.%3u.%3u.%3u", &add[0], &add[1], &add[2], &add[3]);
+    for (int i=0;i<4;i++) {
+      address[i] = add[i];
+    }
+    std::memset(_ipAddress,0,sizeof(_ipAddress));
+
+    if (result != 4) {
+ #ifndef CC3000_TINY_DRIVER
+        //Resolve DNS address or populate hard-coded IP address
+        uint32_t address_integer;
+        int resolveRetCode;
+        resolveRetCode = _cc3000_module->_socket.gethostbyname((uint8_t *)host, strlen(host) , &address_integer);
+
+        if ((resolveRetCode > -1) && (0 != address_integer)) {
+            _remote_host.sin_addr.s_addr = htonl(address_integer);
+            cc3000_inet_ntoa_r(_remote_host.sin_addr, _ipAddress, sizeof(_ipAddress));
+        } else {
+            // Failed to resolve the address
+            DBG_SOCKET("Failed to resolve the hostname : %s",host);
+            return (-1);
+        }
+#else
+        return -1;
+#endif
+    } else {
+        std::memcpy((char*)&_remote_host.sin_addr.s_addr, p_address, 4);
+    }
+
+    _remote_host.sin_family = AF_INET;
+    _remote_host.sin_port = htons(port);
+
+    DBG_SOCKET("remote host address (string): %s",get_address());
+    DBG_SOCKET("remote host address from s_addr : %d.%d.%d.%d",
+            int(_remote_host.sin_addr.s_addr & 0xFF),
+            int((_remote_host.sin_addr.s_addr & 0xFF00) >> 8),
+            int((_remote_host.sin_addr.s_addr & 0xFF0000) >> 16),
+            int((_remote_host.sin_addr.s_addr & 0xFF000000) >> 24));
+    DBG_SOCKET("port: %d", port);
+
+    return 0;
+}
+
+char* Endpoint::get_address() {
+    if ((_ipAddress[0] == '\0') && (_remote_host.sin_addr.s_addr != 0))
+            cc3000_inet_ntoa_r(_remote_host.sin_addr, _ipAddress, sizeof(_ipAddress));
+    return _ipAddress;
+}
+
+
+int   Endpoint::get_port() {
+    return ntohs(_remote_host.sin_port);
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/WifiRobot/cc3000/Socket/Endpoint.h	Tue Dec 09 05:06:37 2014 +0000
@@ -0,0 +1,67 @@
+/* Copyright (C) 2013 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 ENDPOINT_H
+#define ENDPOINT_H
+
+#include "cc3000.h"
+
+using namespace mbed_cc3000;
+
+class UDPSocket;
+
+/**
+IP Endpoint (address, port)
+*/
+class Endpoint {
+    friend class UDPSocket;
+
+public:
+    /** IP Endpoint (address, port)
+     */
+    Endpoint(void);
+
+    ~Endpoint(void);
+
+    /** Reset the address of this endpoint
+     */
+    void reset_address(void);
+
+    /** Set the address of this endpoint
+    \param host The endpoint address (it can either be an IP Address or a hostname that will be resolved with DNS).
+    \param port The endpoint port
+    \return 0 on success, -1 on failure (when an hostname cannot be resolved by DNS).
+     */
+    int  set_address(const char* host, const int port);
+
+    /** Get the IP address of this endpoint
+    \return The IP address of this endpoint.
+     */
+    char* get_address(void);
+
+    /** Get the port of this endpoint
+    \return The port of this endpoint
+     */
+    int get_port(void);
+
+protected:
+    char _ipAddress[17];
+    sockaddr_in _remote_host;
+    cc3000 *_cc3000_module;
+};
+
+#endif
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/WifiRobot/cc3000/Socket/Socket.cpp	Tue Dec 09 05:06:37 2014 +0000
@@ -0,0 +1,114 @@
+/* Copyright (C) 2013 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 "Socket.h"
+#include <cstring>
+
+Socket::Socket() : _sock_fd(-1), _blocking(true), _timeout(1500) {
+    _cc3000_module = cc3000::get_instance();
+    if (_cc3000_module == NULL) {
+        error("Socket constructor error: no cc3000 instance available!\r\n");
+    }
+}
+
+int Socket::init_socket(int type, int protocol) {
+    if (_sock_fd != -1) {
+        DBG_SOCKET("Socket was initialized previously");
+        return -1;
+    }
+
+    int fd = _cc3000_module->_socket.socket(AF_INET, type, protocol);
+    if (fd < -1) {
+        DBG_SOCKET("Failed to create new socket (type: %d, protocol: %d)",type, protocol);
+        return -1;
+    }
+
+    DBG_SOCKET("Socket created (fd: %d type: %d, protocol: %d)",fd, type, protocol);
+    _sock_fd = fd;
+
+    return 0;
+}
+
+void Socket::set_blocking(bool blocking, unsigned int timeout) {
+    _blocking = blocking;
+    _timeout = timeout;
+}
+
+int Socket::set_option(int level, int optname, const void *optval, socklen_t optlen) {
+#ifndef CC3000_TINY_DRIVER
+    return _cc3000_module->_socket.setsockopt(_sock_fd, level, optname, optval, optlen);
+#else
+    return -1;
+#endif
+}
+
+int Socket::get_option(int level, int optname, void *optval, socklen_t *optlen) {
+    return _cc3000_module->_socket.getsockopt(_sock_fd, level, optname, optval, optlen);
+}
+
+int Socket::select(struct timeval *timeout, bool read, bool write) {
+    if (_sock_fd < 0) {
+        return -1;
+    }
+
+    fd_set fdSet;
+    FD_ZERO(&fdSet);
+    FD_SET(_sock_fd, &fdSet);
+
+    fd_set* readset  = (read ) ? (&fdSet) : (NULL);
+    fd_set* writeset = (write) ? (&fdSet) : (NULL);
+
+    int ret = _cc3000_module->_socket.select(_sock_fd+1, readset, writeset, NULL, timeout);
+
+    DBG_SOCKET("Select on sock_fd: %d, returns %d. fdSet: %d", _sock_fd, ret, FD_ISSET(_sock_fd, &fdSet));
+
+    // TODO
+    //return (ret <= 0 || !FD_ISSET(_sock_fd, &fdSet)) ? (-1) : (0);
+    if (FD_ISSET(_sock_fd, &fdSet)) {
+        return 0;
+    } else {
+        return -1;
+    }
+}
+
+int Socket::wait_readable(TimeInterval& timeout) {
+    return select(&timeout._time, true, false);
+}
+
+int Socket::wait_writable(TimeInterval& timeout) {
+    return select(&timeout._time, false, true);
+}
+
+int Socket::close() {
+    if (_sock_fd < 0 ) {
+        return -1;
+    }
+
+    _cc3000_module->_socket.closesocket(_sock_fd);
+    _sock_fd = -1;
+    return 0;
+}
+
+Socket::~Socket() {
+    close();
+}
+
+TimeInterval::TimeInterval(unsigned int ms) {
+    _time.tv_sec = ms / 1000;
+    _time.tv_usec = (ms - (_time.tv_sec * 1000)) * 1000;
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/WifiRobot/cc3000/Socket/Socket.h	Tue Dec 09 05:06:37 2014 +0000
@@ -0,0 +1,98 @@
+/* Copyright (C) 2013 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 SOCKET_H
+#define SOCKET_H
+
+#include "cc3000.h"
+
+using namespace mbed_cc3000;
+
+class TimeInterval;
+
+/** Socket file descriptor and select wrapper
+  */
+class Socket {
+public:
+    /** Socket
+     */
+    Socket();
+
+    /** Set blocking or non-blocking mode of the socket and a timeout on
+        blocking socket operations
+    \param blocking  true for blocking mode, false for non-blocking mode.
+    \param timeout   timeout in ms [Default: (1500)ms].
+    */
+    void set_blocking(bool blocking, unsigned int timeout=1500);
+
+    /** Set socket options
+    \param level     stack level (see: lwip/sockets.h)
+    \param optname   option ID
+    \param optval    option value
+    \param socklen_t length of the option value
+    \return 0 on success, -1 on failure
+    */
+    int set_option(int level, int optname, const void *optval, socklen_t optlen);
+
+    /** Get socket options
+        \param level     stack level (see: lwip/sockets.h)
+        \param optname   option ID
+        \param optval    buffer pointer where to write the option value
+        \param socklen_t length of the option value
+        \return 0 on success, -1 on failure
+        */
+    int get_option(int level, int optname, void *optval, socklen_t *optlen);
+
+
+    /** Close the socket file descriptor
+     */
+    int close();
+
+    ~Socket();
+
+protected:
+    int _sock_fd;
+
+    int init_socket(int type, int protocol);
+
+    int wait_readable(TimeInterval& timeout);
+    int wait_writable(TimeInterval& timeout);
+
+    bool _blocking;
+    int _timeout;
+
+    cc3000 *_cc3000_module;
+private:
+    int select(struct timeval *timeout, bool read, bool write);
+};
+
+/** Time interval class used to specify timeouts
+ */
+class TimeInterval {
+    friend class Socket;
+
+public:
+    /** Time Interval
+     \param ms time interval expressed in milliseconds
+      */
+    TimeInterval(unsigned int ms);
+
+private:
+    struct timeval _time;
+};
+
+#endif /* SOCKET_H */
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/WifiRobot/cc3000/Socket/TCPSocketConnection.cpp	Tue Dec 09 05:06:37 2014 +0000
@@ -0,0 +1,149 @@
+/* Copyright (C) 2013 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 "TCPSocketConnection.h"
+#include <algorithm>
+
+TCPSocketConnection::TCPSocketConnection() : _is_connected(false) {
+    _cc3000_module = cc3000::get_instance();
+    if (_cc3000_module == NULL) {
+        error("Endpoint constructor error: no cc3000 instance available!\r\n");
+    }
+}
+
+int TCPSocketConnection::connect(const char *host, const int port) {
+    if (init_socket(SOCK_STREAM, IPPROTO_TCP) < 0) {
+        DBG_SOCKET("Failed to create tcp socket");
+        return -1;
+    }
+
+    if (set_address(host, port) != 0) {
+        DBG_SOCKET("Failed to set address (tcp)");
+        return -1;
+    }
+
+    if (_cc3000_module->_socket.connect(_sock_fd, (const sockaddr *)&_remote_host, sizeof(_remote_host)) < 0) {
+        DBG_SOCKET("Failed to connect (tcp)");
+        close();
+        return -1;
+    }
+
+    _is_connected = true;
+
+    return 0;
+}
+
+bool TCPSocketConnection::is_connected(void) {
+    return _is_connected;
+}
+
+int TCPSocketConnection::send(char* data, int length) {
+    if ((_sock_fd < 0) || !_is_connected) {
+        return -1;
+    }
+
+    if (!_blocking) {
+        TimeInterval timeout(_timeout);
+        if (wait_writable(timeout) != 0) {
+            return -1;
+        }
+    }
+
+    int n = _cc3000_module->_socket.send(_sock_fd, data, length, 0);
+    _is_connected = (n != 0);
+
+    return n;
+}
+
+int TCPSocketConnection::send_all(char *data, int length) {
+    if ((_sock_fd < 0) || !_is_connected) {
+        return -1;
+    }
+
+    int writtenLen = 0;
+    TimeInterval timeout(_timeout);
+    while (writtenLen < length) {
+        if (!_blocking) {
+            // Wait for socket to be writeable
+            if (wait_writable(timeout) != 0) {
+                return writtenLen;
+            }
+        }
+
+        int ret = _cc3000_module->_socket.send(_sock_fd, data + writtenLen, length - writtenLen, 0);
+        if (ret > 0) {
+            writtenLen += ret;
+            continue;
+        } else if (ret == 0) {
+            _is_connected = false;
+            return writtenLen;
+        } else {
+            return -1; //Connnection error
+        }
+    }
+
+    return writtenLen;
+}
+
+int TCPSocketConnection::receive(char *data, int length) {
+    if ((_sock_fd < 0) || !_is_connected) {
+        return -1;
+    }
+
+    if (!_blocking) {
+        TimeInterval timeout(_timeout);
+        if (wait_readable(timeout) != 0)
+            return -1;
+    }
+
+    int n = _cc3000_module->_socket.recv(_sock_fd, data, length, 0);
+    if (n >= 0) {
+        _is_connected = 1;
+    } else {
+        _is_connected = 0;
+    }
+
+    return n;
+}
+
+int TCPSocketConnection::receive_all(char *data, int length) {
+    if ((_sock_fd < 0) || !_is_connected) {
+        return -1;
+    }
+
+    int readLen = 0;
+    TimeInterval timeout(_timeout);
+    while (readLen < length) {
+        if (!_blocking) {
+            //Wait for socket to be readable
+            if (wait_readable(timeout) != 0)
+                return readLen;
+        }
+
+        int ret = _cc3000_module->_socket.recv(_sock_fd, data + readLen, length - readLen, 0);
+        if (ret > 0) {
+            readLen += ret;
+        } else if (ret == 0) {
+            _is_connected = false;
+            return readLen;
+        } else {
+            return -1; //Connnection error
+        }
+    }
+    return readLen;
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/WifiRobot/cc3000/Socket/TCPSocketConnection.h	Tue Dec 09 05:06:37 2014 +0000
@@ -0,0 +1,80 @@
+/* Copyright (C) 2013 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 TCPSOCKET_H
+#define TCPSOCKET_H
+
+#include "Socket.h"
+#include "Endpoint.h"
+
+/**
+TCP socket connection
+*/
+class TCPSocketConnection: public Socket, public Endpoint {
+    friend class TCPSocketServer;
+
+public:
+    /** TCP socket connection
+    */
+    TCPSocketConnection();
+
+    /** Connects this TCP socket to the server
+    \param host The host to connect to. It can either be an IP Address or a hostname that will be resolved with DNS.
+    \param port The host's port to connect to.
+    \return 0 on success, -1 on failure.
+    */
+    int connect(const char *host, const int port);
+
+    /** Check if the socket is connected
+    \return true if connected, false otherwise.
+    */
+    bool is_connected(void);
+
+    /** Send data to the remote host.
+    \param data The buffer to send to the host.
+    \param length The length of the buffer to send.
+    \return the number of written bytes on success (>=0) or -1 on failure
+     */
+    int send(char *data, int length);
+
+    /** Send all the data to the remote host.
+    \param data The buffer to send to the host.
+    \param length The length of the buffer to send.
+    \return the number of written bytes on success (>=0) or -1 on failure
+    */
+    int send_all(char *data, int length);
+
+    /** Receive data from the remote host.
+    \param data The buffer in which to store the data received from the host.
+    \param length The maximum length of the buffer.
+    \return the number of received bytes on success (>=0) or -1 on failure
+     */
+    int receive(char *data, int length);
+
+    /** Receive all the data from the remote host.
+    \param data The buffer in which to store the data received from the host.
+    \param length The maximum length of the buffer.
+    \return the number of received bytes on success (>=0) or -1 on failure
+    */
+    int receive_all(char *data, int length);
+private:
+    bool _is_connected;
+    cc3000 *_cc3000_module;
+};
+
+#endif
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/WifiRobot/cc3000/Socket/TCPSocketServer.cpp	Tue Dec 09 05:06:37 2014 +0000
@@ -0,0 +1,84 @@
+/* Copyright (C) 2013 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 "TCPSocketServer.h"
+#include <string>
+
+TCPSocketServer::TCPSocketServer() {
+
+}
+
+int TCPSocketServer::bind(int port) {
+    if (init_socket(SOCK_STREAM, IPPROTO_TCP) < 0) {
+        return -1;
+    }
+
+    sockaddr_in localHost;
+    memset(&localHost, 0, sizeof(localHost));
+
+    localHost.sin_family = AF_INET;
+    localHost.sin_port = htons(port);
+    localHost.sin_addr.s_addr = 0;
+
+    if (_cc3000_module->_socket.bind(_sock_fd, (const sockaddr *)&localHost, sizeof(localHost)) < 0) {
+        close();
+        return -1;
+    }
+
+    return 0;
+}
+
+int TCPSocketServer::listen(int max) {
+    if (_sock_fd < 0) {
+        return -1;
+    }
+
+    if (_cc3000_module->_socket.listen(_sock_fd, max) < 0) {
+        close();
+        return -1;
+    }
+
+    return 0;
+}
+
+
+int TCPSocketServer::accept(TCPSocketConnection& connection) {
+    if (_sock_fd < 0) {
+        return -1;
+    }
+
+    if (!_blocking) {
+        TimeInterval timeout(_timeout);
+        if (wait_readable(timeout) != 0) {
+            return -1;
+        }
+    }
+
+    connection.reset_address();
+    socklen_t newSockRemoteHostLen = sizeof(connection._remote_host);
+    int fd = _cc3000_module->_socket.accept(_sock_fd, (sockaddr *) &connection._remote_host, &newSockRemoteHostLen);
+    if (fd < 0) {
+        return -1;
+    }
+    /* s_addr is returned in the little endian */
+    connection._remote_host.sin_addr.s_addr = htonl(connection._remote_host.sin_addr.s_addr);
+    connection._sock_fd = fd;
+    connection._is_connected = true;
+
+    return 0;
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/WifiRobot/cc3000/Socket/TCPSocketServer.h	Tue Dec 09 05:06:37 2014 +0000
@@ -0,0 +1,52 @@
+/* Copyright (C) 2013 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 TCPSOCKETSERVER_H
+#define TCPSOCKETSERVER_H
+
+#include "Socket/Socket.h"
+#include "TCPSocketConnection.h"
+
+/** TCP Server.
+  */
+class TCPSocketServer : public Socket {
+  public:
+    /** Instantiate a TCP Server.
+    */
+    TCPSocketServer();
+
+    /** Bind a socket to a specific port.
+    \param port The port to listen for incoming connections on.
+    \return 0 on success, -1 on failure.
+    */
+    int bind(int port);
+
+    /** Start listening for incoming connections.
+    \param backlog number of pending connections that can be queued up at any
+                   one time [Default: 1].
+    \return 0 on success, -1 on failure.
+    */
+    int listen(int backlog=1);
+
+    /** Accept a new connection.
+    \param connection A TCPSocketConnection instance that will handle the incoming connection.
+    \return 0 on success, -1 on failure.
+    */
+    int accept(TCPSocketConnection& connection);
+};
+
+#endif
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/WifiRobot/cc3000/Socket/UDPSocket.cpp	Tue Dec 09 05:06:37 2014 +0000
@@ -0,0 +1,91 @@
+/* Copyright (C) 2013 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 "UDPSocket.h"
+
+#include <string>
+#include <algorithm>
+
+UDPSocket::UDPSocket() {
+
+}
+
+int UDPSocket::init(void) {
+    return init_socket(SOCK_DGRAM, IPPROTO_UDP);
+}
+
+int UDPSocket::bind(int port) {
+    if (init_socket(SOCK_DGRAM, IPPROTO_UDP) < 0) {
+        return -1;
+    }
+
+    sockaddr_in localHost;
+    std::memset(&localHost, 0, sizeof(sockaddr_in));
+
+    localHost.sin_family = AF_INET;
+    localHost.sin_port = htons(port);
+    localHost.sin_addr.s_addr = 0;
+
+    if (_cc3000_module->_socket.bind(_sock_fd, (sockaddr *)&localHost, sizeof(sockaddr_in)) != 0) {
+        DBG_SOCKET("Failed to bind a socket (udp). Closing socket");
+        _cc3000_module->_socket.closesocket(_sock_fd);
+        _sock_fd = -1;
+        return -1;
+    }
+
+    return 0;
+}
+
+int UDPSocket::sendTo(Endpoint &remote, char *packet, int length)
+{
+    if (_sock_fd < 0) {
+        return -1;
+    }
+    // TODO - seems to be a bug, waiting for TI to respond
+    // if (!_blocking) {
+    //     TimeInterval timeout(_timeout);
+    //     if (wait_writable(timeout) != 0) {
+    //         DBG_SOCKET("The socket is not writeable. _sock_fd: %d", _sock_fd);
+    //         return 0;
+    //     }
+    // }
+
+    return _cc3000_module->_socket.sendto(_sock_fd, packet, length, 0, (sockaddr *)&remote._remote_host, sizeof(sockaddr));
+}
+
+int UDPSocket::receiveFrom(Endpoint &remote, char *buffer, int length)
+{
+    if (_sock_fd < 0) {
+        return -1;
+    }
+
+    if (!_blocking) {
+        TimeInterval timeout(_timeout);
+        if (wait_readable(timeout) != 0) {
+            DBG_SOCKET("The socket is not readable. _sock_fd: %d", _sock_fd);
+            return 0;
+        }
+    }
+
+    remote.reset_address();
+    socklen_t remote_host_length = sizeof(remote._remote_host);
+
+    return _cc3000_module->_socket.recvfrom(_sock_fd, buffer, length, 0, (sockaddr *)&remote._remote_host, &remote_host_length);
+}
+
+
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/WifiRobot/cc3000/Socket/UDPSocket.h	Tue Dec 09 05:06:37 2014 +0000
@@ -0,0 +1,68 @@
+/* Copyright (C) 2013 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 UDPSOCKET_H
+#define UDPSOCKET_H
+
+#include "Endpoint.h"
+#include "Socket.h"
+
+#include <cstdint>
+
+/**
+UDP Socket
+*/
+class UDPSocket: public Socket {
+
+public:
+    /** Instantiate an UDP Socket.
+    */
+    UDPSocket();
+
+    /** Init the UDP Client Socket without binding it to any specific port
+    \return 0 on success, -1 on failure.
+    */
+    int init(void);
+
+    /** Bind a UDP Server Socket to a specific port
+    \param port The port to listen for incoming connections on
+    \return 0 on success, -1 on failure.
+    */
+    int bind(int port = -1);
+
+    /** Send a packet to a remote endpoint
+    \param remote   The remote endpoint
+    \param packet   The packet to be sent
+    \param length   The length of the packet to be sent
+    \return the number of written bytes on success (>=0) or -1 on failure
+    */
+    int sendTo(Endpoint &remote, char *packet, int length);
+
+    /** Receive a packet from a remote endpoint
+    \param remote   The remote endpoint
+    \param buffer   The buffer for storing the incoming packet data. If a packet
+           is too long to fit in the supplied buffer, excess bytes are discarded
+    \param length   The length of the buffer
+    \return the number of received bytes on success (>=0) or -1 on failure
+    */
+    int receiveFrom(Endpoint &remote, char *buffer, int length);
+};
+
+#include "def.h"
+
+#endif
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/WifiRobot/cc3000/cc3000.cpp	Tue Dec 09 05:06:37 2014 +0000
@@ -0,0 +1,522 @@
+/*****************************************************************************
+*
+*  C++ interface/implementation created by Martin Kojtal (0xc0170). Thanks to
+*  Jim Carver and Frank Vannieuwkerke for their inital cc3000 mbed port and
+*  provided help.
+*
+*  This version of "host driver" uses CC3000 Host Driver Implementation. Thus
+*  read the following copyright:
+*
+*  Copyright (C) 2011 Texas Instruments Incorporated - http://www.ti.com/
+*
+*  Redistribution and use in source and binary forms, with or without
+*  modification, are permitted provided that the following conditions
+*  are met:
+*
+*    Redistributions of source code must retain the above copyright
+*    notice, this list of conditions and the following disclaimer.
+*
+*    Redistributions in binary form must reproduce the above copyright
+*    notice, this list of conditions and the following disclaimer in the
+*    documentation and/or other materials provided with the
+*    distribution.
+*
+*    Neither the name of Texas Instruments Incorporated nor the names of
+*    its contributors may be used to endorse or promote products derived
+*    from this software without specific prior written permission.
+*
+*  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+*  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+*  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
+*  A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
+*  OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
+*  SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
+*  LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
+*  DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
+*  THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+*  (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
+*  OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+*
+*****************************************************************************/
+#include "cc3000.h"
+#include "cc3000_event.h"
+
+namespace mbed_cc3000 {
+
+/* TODO this prefix remove? verify */
+static uint8_t cc3000_prefix[] = {'T', 'T', 'T'};
+cc3000 *cc3000::_inst;
+
+cc3000::cc3000(PinName cc3000_irq, PinName cc3000_en, PinName cc3000_cs, SPI cc3000_spi)
+             : _event(_simple_link, _hci, _spi, *this), _socket(_simple_link, _hci, _event),
+               _spi(cc3000_irq, cc3000_en, cc3000_cs, cc3000_spi, _event, _simple_link), _hci(_spi),
+               _nvmem(_hci, _event, _simple_link), _netapp(_simple_link, _nvmem, _hci, _event),
+               _wlan(_simple_link, _event, _spi, _hci) {
+    _simple_link.set_tx_complete_signal(1);
+    memset(&_status, 0, sizeof(_status));
+    _inst = this;
+}
+
+cc3000::~cc3000() {
+}
+
+#if (CC3000_ETH_COMPAT == 1)
+cc3000::cc3000(PinName cc3000_irq, PinName cc3000_en, PinName cc3000_cs, SPI cc3000_spi, const char *ssid,
+               const char *phrase, Security sec, bool smart_config)
+             : _event(_simple_link, _hci, _spi, *this), _socket(_simple_link, _hci, _event),
+               _spi(cc3000_irq, cc3000_en, cc3000_cs, cc3000_spi, _event, _simple_link), _hci(_spi),
+               _nvmem(_hci, _event, _simple_link), _netapp(_simple_link, _nvmem, _hci, _event),
+               _wlan(_simple_link, _event, _spi, _hci), _sec(sec), _smart_config(smart_config) {
+    _simple_link.set_tx_complete_signal(1);
+    memset(&_status, 0, sizeof(_status));
+    strcpy((char *)_ssid, ssid);
+    strcpy((char *)_phrase, phrase);
+    _inst = this;
+}
+
+// Ethernet library compatible, functions return strings
+// Caches the ipconfig from the usync callback
+static char mac_addr[19]= "\0";
+static char ip_addr[17] = "\0";
+static char gateway[17] = "\0";
+static char networkmask[17] = "\0";
+
+void cc3000::init() {
+    _wlan.start(0);
+
+    uint32_t subnet[4] = {0};
+    uint32_t ip[4] = {0};
+    uint32_t getway[4] = {0};
+    uint32_t dns[4] = {0};
+
+    _netapp.dhcp(ip, subnet, getway, dns);
+    _wlan.stop();
+    wait(1);
+    _wlan.start(0);
+
+    _status.enabled = 1;
+    _wlan.set_event_mask(HCI_EVNT_WLAN_UNSOL_INIT | HCI_EVNT_WLAN_KEEPALIVE);
+}
+
+void cc3000::init(const char *ip, const char *mask, const char *gateway) {
+    _netapp.dhcp((uint32_t *)ip, (uint32_t *)mask, (uint32_t *)gateway, (uint32_t *)ip); //dns = ip
+    _wlan.stop();
+    wait(1);
+    _wlan.start(0);
+
+    _status.enabled = 1;
+    _wlan.set_event_mask(HCI_EVNT_WLAN_UNSOL_INIT | HCI_EVNT_WLAN_KEEPALIVE);
+}
+
+int cc3000::connect(unsigned int timeout_ms) {
+    Timer t;
+    int ret = 0;
+
+    if (_smart_config == false) {
+        _wlan.ioctl_set_connection_policy(0, 0, 0);
+    } else {
+        tUserFS user_info;
+        get_user_file_info((uint8_t *)&user_info, sizeof(user_info));
+        if (user_info.FTC == 1) {
+            _wlan.ioctl_set_connection_policy(0, 1, 1);
+        } else {
+            DBG_CC("Smart config is not set. Please run the first time configuration.");
+            return -1;
+        }
+    }
+
+    t.start();
+    while (is_connected() == false) {
+        if (strlen((const char *)_phrase) < 8) {
+            if (connect_open(_ssid)) {
+                break;
+            }
+        } else {
+#ifndef CC3000_TINY_DRIVER
+            if (connect_secure(_ssid,_phrase, _sec)) {
+                break;
+            }
+#else
+            return -1; /* secure connection not supported with TINY_DRIVER */
+#endif
+        }
+
+        if (t.read_ms() > timeout_ms) {
+            ret = -1;
+            DBG_CC("Connection to AP failed");
+            break;
+        }
+    }
+
+    while (is_dhcp_configured() == false)
+    {
+        if (t.read_ms() > timeout_ms) {
+            ret = -1;
+            DBG_CC("Connection to AP failed");
+            break;
+        }
+    }
+
+    return ret;
+}
+
+char* cc3000::getMACAddress() {
+    return mac_addr;
+}
+
+char* cc3000::getIPAddress() {
+    return ip_addr;
+}
+
+char* cc3000::getGateway() {
+    return gateway;
+}
+
+char* cc3000::getNetworkMask() {
+    return networkmask;
+}
+
+int cc3000::disconnect(void){
+    if (_wlan.disconnect()) {
+        return -1;
+    } else {
+        return 0;
+    }
+}
+
+#endif
+
+void cc3000::usync_callback(int32_t event_type, uint8_t *data, uint8_t length) {
+    if (event_type == HCI_EVNT_WLAN_ASYNC_SIMPLE_CONFIG_DONE) {
+        DBG_CC("Callback : HCI_EVNT_WLAN_ASYNC_SIMPLE_CONFIG_DONE");
+        _status.smart_config_complete = 1;
+        _status.stop_smart_config = 1;
+    }
+
+    if (event_type == HCI_EVNT_WLAN_UNSOL_CONNECT) {
+        DBG_CC("Callback : HCI_EVNT_WLAN_UNSOL_CONNECT");
+        _status.connected = 1;
+        // Connect message is always followed by a DHCP message, connection is not useable until then
+        _status.dhcp      = 0;
+    }
+
+    if (event_type == HCI_EVNT_WLAN_UNSOL_DISCONNECT) {
+        DBG_CC("Callback : HCI_EVNT_WLAN_UNSOL_DISCONNECT");
+        _status.connected = 0;
+        _status.dhcp      = 0;
+        _status.dhcp_configured = 0;
+    }
+
+    if (event_type == HCI_EVNT_WLAN_UNSOL_DHCP) {
+#if (CC3000_ETH_COMPAT == 1)
+        _socket.inet_ntoa_r( htonl(*((uint32_t *)(&data[NETAPP_IPCONFIG_IP_OFFSET]))), ip_addr, 17);
+        _socket.inet_ntoa_r( htonl(*((uint32_t *)(&data[NETAPP_IPCONFIG_GW_OFFSET]))), gateway, 17);
+        _socket.inet_ntoa_r( htonl(*((uint32_t *)(&data[NETAPP_IPCONFIG_SUBNET_OFFSET]))), networkmask, 17);
+        _socket.inet_ntoa_r( htonl(*((uint32_t *)(&data[NETAPP_IPCONFIG_MAC_OFFSET]))), mac_addr, 19);
+#endif
+        if (*(data + NETAPP_IPCONFIG_MAC_OFFSET) == 0) {
+            _status.dhcp = 1;
+            DBG_CC("Callback : HCI_EVNT_WLAN_UNSOL_DHCP %i.%i.%i.%i", data[3], data[2], data[1], data[0]);
+        } else {
+            DBG_CC("Callback : HCI_EVNT_WLAN_UNSOL_DHCP - Disconnecting");
+            _status.dhcp = 0;
+        }
+    }
+
+    if (event_type == HCI_EVENT_CC3000_CAN_SHUT_DOWN) {
+        // Note this means the modules is idle, so it could be shutdown..
+        //DBG_CC("Callback : HCI_EVENT_CC3000_CAN_SHUT_DOWN");
+        _status.ok_to_shut_down = 1;
+    }
+
+    if (event_type == HCI_EVNT_WLAN_ASYNC_PING_REPORT) {
+        DBG_CC("Callback : HCI_EVNT_WLAN_ASYNC_PING_REPORT");
+        memcpy(&_ping_report, data, length);
+    }
+
+    if (event_type == HCI_EVNT_BSD_TCP_CLOSE_WAIT) {
+        uint8_t socketnum = data[0];
+        DBG_CC("Callback : HCI_EVNT_BSD_TCP_CLOSE_WAIT - Socket : %d", socketnum);
+        if (socketnum < MAX_SOCKETS) {
+            _closed_sockets[socketnum] = true; /* clients socket is closed */
+        }
+    }
+}
+
+void cc3000::start_smart_config(const uint8_t *smart_config_key) {
+    _status.smart_config_complete = 0;
+    _wlan.ioctl_set_connection_policy(0, 0, 0);
+
+    if (_status.connected == 1) {
+        disconnect();
+    }
+
+    //Wait until CC3000 is disconected
+    while (_status.connected == 1) {
+        wait_us(5);
+        _event.hci_unsolicited_event_handler();
+    }
+
+    // Trigger the Smart Config process
+    _wlan.smart_config_set_prefix(cc3000_prefix);
+    // Start the Smart Config process with AES disabled
+    _wlan.smart_config_start(0);
+
+    DBG_CC("Waiting for smartconfig to be completed");
+
+    // Wait for Smart config finished
+    while (_status.smart_config_complete == 0) {
+        wait_ms(100);
+    }
+
+    DBG_CC("Smartconfig finished");
+
+#ifndef CC3000_UNENCRYPTED_SMART_CONFIG
+    // create new entry for AES encryption key
+    _nvmem.create_entry(NVMEM_AES128_KEY_FILEID, 16);
+    // write AES key to NVMEM
+    _security.aes_write_key((uint8_t *)(&smart_config_key[0]));
+    // Decrypt configuration information and add profile
+    _wlan.smart_config_process();
+#endif
+
+    // Configure to connect automatically to the AP retrieved in the
+    // Smart config process
+    _wlan.ioctl_set_connection_policy(0, 0, 1);
+
+    // reset the CC3000
+    _wlan.stop();
+    _status.enabled = 0;
+    wait(5);
+    _wlan.start(0);
+    _status.enabled = 1;
+
+    // Mask out all non-required events
+    _wlan.set_event_mask(HCI_EVNT_WLAN_KEEPALIVE | HCI_EVNT_WLAN_UNSOL_INIT);
+}
+
+bool cc3000::connect_secure(const uint8_t *ssid, const uint8_t *key, int32_t security_mode) {
+#ifdef CC3000_TINY_DRIVER
+    return false; /* not supported*/
+#else
+    uint32_t ret;
+
+    //_wlan.disconnect();
+    wait_ms(3);
+    ret = _wlan.connect(security_mode, ssid, strlen((const char *)ssid), 0, (uint8_t *)key, strlen((const char *)key));
+    if (ret == 0) { /* TODO static internal cc3000 state 0 to TRUE */
+      ret = true;
+    } else {
+      ret = false;
+    }
+    return ret;
+#endif
+}
+
+bool cc3000::connect_non_blocking(const uint8_t *ssid, const uint8_t *key, int32_t security_mode)
+{
+    bool ret = false;
+
+    if (key == 0) {
+        if (connect_open(ssid)) {
+            ret = true;
+        }
+    } else {
+    #ifndef CC3000_TINY_DRIVER
+        if (connect_secure(ssid,key,security_mode)) {
+            ret = true;
+        }
+    #else
+        /* secure connection not supported with TINY_DRIVER */
+    #endif
+    }
+
+    return ret;
+}
+
+bool cc3000::connect_to_AP(const uint8_t *ssid, const uint8_t *key, int32_t security_mode) {
+    Timer t;
+    bool ret = true;
+
+    t.start();
+    while (is_connected() == false) {
+        if (key == 0) {
+            if (connect_open(ssid)) {
+                break;
+            }
+        } else {
+#ifndef CC3000_TINY_DRIVER
+            if (connect_secure(ssid,key,security_mode)) {
+                break;
+            }
+#else
+            return false; /* secure connection not supported with TINY_DRIVER */
+#endif
+        }
+
+        /* timeout 10 seconds */
+        if (t.read_ms() > 10000) {
+            ret = false;
+            DBG_CC("Connection to AP failed");
+            break;
+        }
+    }
+
+    return ret;
+}
+
+void cc3000::start(uint8_t patch) {
+    _wlan.start(patch);
+    _status.enabled = 1;
+    _wlan.set_event_mask(HCI_EVNT_WLAN_UNSOL_INIT | HCI_EVNT_WLAN_KEEPALIVE);
+}
+
+void cc3000::stop(void) {
+    _wlan.stop();
+    _status.enabled = 0;
+}
+
+void cc3000::restart(uint8_t patch) {
+    _wlan.stop();
+    _status.enabled = 0;
+    wait_ms(500);
+    _wlan.start(patch);
+    _status.enabled = 1;
+}
+
+bool cc3000::connect_open(const uint8_t *ssid) {
+    _wlan.disconnect();
+    wait_ms(3);
+    uint32_t ret;
+#ifndef CC3000_TINY_DRIVER
+    ret = _wlan.connect(0,ssid, strlen((const char *)ssid), 0, 0, 0);
+#else
+    ret = _wlan.connect(ssid, strlen((const char *)ssid));
+#endif
+    if (ret == 0) {
+        ret = true;
+    } else {
+        ret = false;
+    }
+    return ret;
+}
+
+bool cc3000::is_enabled()
+{
+    return _status.enabled;
+}
+
+bool cc3000::is_connected() {
+    if (( _status.connected ) && ( _status.dhcp )) {
+        return 1;
+    } else {
+        return 0;
+    }
+}
+
+bool cc3000::is_dhcp_configured() {
+    return _status.dhcp;
+}
+
+bool cc3000::is_smart_confing_completed() {
+    return _status.smart_config_complete;
+}
+
+uint8_t cc3000::get_mac_address(uint8_t address[6]) {
+    return _nvmem.get_mac_address(address);
+}
+
+uint8_t cc3000::set_mac_address(uint8_t address[6]) {
+    return _nvmem.set_mac_address(address);
+}
+
+void cc3000::get_user_file_info(uint8_t *info_file, size_t size) {
+    _nvmem.read( NVMEM_USER_FILE_1_FILEID, size, 0, info_file);
+}
+
+#ifndef CC3000_TINY_DRIVER
+bool cc3000::get_ip_config(tNetappIpconfigRetArgs *ip_config) {
+    if ((_status.dhcp == false) || (_status.connected == false)) {
+        return false;
+    }
+
+    _netapp.ipconfig(ip_config);
+    return true;
+}
+#endif
+
+void cc3000::delete_profiles(void) {
+    _wlan.ioctl_set_connection_policy(0, 0, 0);
+    _wlan.ioctl_del_profile(255);
+
+    tUserFS user_info;
+    get_user_file_info((uint8_t *)&user_info, sizeof(user_info));
+    user_info.FTC = 0;
+    set_user_file_info((uint8_t *)&user_info, sizeof(user_info));
+}
+
+void cc3000::set_user_file_info(uint8_t *info_file, size_t size) {
+    _nvmem.write( NVMEM_USER_FILE_1_FILEID, size, 0, info_file);
+}
+
+uint32_t cc3000::ping(uint32_t ip, uint8_t attempts, uint16_t timeout, uint8_t size) {
+#ifndef CC3000_TINY_DRIVER
+    uint32_t reversed_ip = (ip >> 24) | ((ip >> 8) & 0xFF00) | ((ip << 8) & 0xFF0000) | (ip << 24);
+
+    _ping_report.packets_received = 0;
+    if (_netapp.ping_send(&reversed_ip, attempts, size, timeout) == -1) {
+        DBG_CC("Failed to send ping");
+        return 0;
+    }
+    wait_ms(timeout*attempts*2);
+
+    /* known issue of cc3000 - sent number is send + received */
+    // TODO : Remove the Sent/recv'd counts until ti fix the firmware issue?
+    DBG_CC("Sent: %d",_ping_report.packets_sent);
+    DBG_CC("Received: %d",_ping_report.packets_received);
+    DBG_CC("Min time: %d",_ping_report.min_round_time);
+    DBG_CC("Max time: %d",_ping_report.max_round_time);
+    DBG_CC("Avg time: %d",_ping_report.avg_round_time);
+
+    return _ping_report.packets_received;
+#else
+    return 0;
+#endif
+}
+
+/* Conversion between uint types and C strings */
+uint8_t* UINT32_TO_STREAM_f (uint8_t *p, uint32_t u32)
+{
+    *(p)++ = (uint8_t)(u32);
+    *(p)++ = (uint8_t)((u32) >> 8);
+    *(p)++ = (uint8_t)((u32) >> 16);
+    *(p)++ = (uint8_t)((u32) >> 24);
+    return p;
+}
+
+
+uint8_t* UINT16_TO_STREAM_f (uint8_t *p, uint16_t u16)
+{
+    *(p)++ = (uint8_t)(u16);
+    *(p)++ = (uint8_t)((u16) >> 8);
+    return p;
+}
+
+
+uint16_t STREAM_TO_UINT16_f(uint8_t *p, uint16_t offset)
+{
+    return (uint16_t)((uint16_t)((uint16_t)
+           (*(p + offset + 1)) << 8) + (uint16_t)(*(p + offset)));
+}
+
+
+uint32_t STREAM_TO_UINT32_f(uint8_t *p, uint16_t offset)
+{
+    return (uint32_t)((uint32_t)((uint32_t)
+           (*(p + offset + 3)) << 24) + (uint32_t)((uint32_t)
+           (*(p + offset + 2)) << 16) + (uint32_t)((uint32_t)
+           (*(p + offset + 1)) << 8) + (uint32_t)(*(p + offset)));
+}
+
+} // mbed_cc3000 namespace
+
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/WifiRobot/cc3000/cc3000.h	Tue Dec 09 05:06:37 2014 +0000
@@ -0,0 +1,1826 @@
+/*****************************************************************************
+*
+*  C++ interface/implementation created by Martin Kojtal (0xc0170). Thanks to
+*  Jim Carver and Frank Vannieuwkerke for their inital cc3000 mbed port and
+*  provided help.
+*
+*  This version of "host driver" uses CC3000 Host Driver Implementation. Thus
+*  read the following copyright:
+*
+*  Copyright (C) 2011 Texas Instruments Incorporated - http://www.ti.com/
+*
+*  Redistribution and use in source and binary forms, with or without
+*  modification, are permitted provided that the following conditions
+*  are met:
+*
+*    Redistributions of source code must retain the above copyright
+*    notice, this list of conditions and the following disclaimer.
+*
+*    Redistributions in binary form must reproduce the above copyright
+*    notice, this list of conditions and the following disclaimer in the
+*    documentation and/or other materials provided with the
+*    distribution.
+*
+*    Neither the name of Texas Instruments Incorporated nor the names of
+*    its contributors may be used to endorse or promote products derived
+*    from this software without specific prior written permission.
+*
+*  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+*  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+*  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
+*  A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
+*  OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
+*  SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
+*  LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
+*  DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
+*  THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+*  (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
+*  OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+*
+*****************************************************************************/
+#ifndef CC3000_H
+#define CC3000_H
+
+#include "mbed.h"
+#include "cc3000_common.h"
+#include "cc3000_spi.h"
+#include "cc3000_simplelink.h"
+#include "cc3000_netapp.h"
+#include "cc3000_nvmem.h"
+#include "cc3000_socket.h"
+
+#define MAX_SOCKETS 4
+// cc3000 Ethernet Interface - enabled by default
+#define CC3000_ETH_COMPAT   1
+
+/** Enable debug messages - set 1  */
+// Debug - Socket interface messages
+#define CC3000_DEBUG_SOCKET 0
+// Debug - HCI TX messages
+#define CC3000_DEBUG_HCI_TX 0
+// Debug - HCI Rx messages
+#define CC3000_DEBUG_HCI_RX 0
+// Debug - General Debug
+#define CC3000_DEBUG        0
+// Add colour to the debug messages, requires a VT100 terminal like putty, comment out to remove
+#define VT100_COLOUR        0
+
+#if (CC3000_DEBUG_SOCKET == 1)
+    #if (VT100_COLOUR == 1)
+        #define DBG_SOCKET(x, ...) std::printf("\x1b[2;32;40m[CC3000 : SOCKET] "x"\x1b[0;37;40m\r\n", ##__VA_ARGS__);
+    #else
+        #define DBG_SOCKET(x, ...) std::printf("[CC3000 : SOCKET] "x"\r\n", ##__VA_ARGS__);
+    #endif
+#else
+    #define DBG_SOCKET(x, ...)
+#endif
+
+#if (CC3000_DEBUG_HCI_TX == 1)
+    #if (VT100_COLOUR == 1)
+        #define DBG_HCI(x, ...) std::printf("\x1b[2;35;40m[CC3000 : HCI RX] "x"\x1b[0;37;40m\r\n", ##__VA_ARGS__);
+    #else
+        #define DBG_HCI(x, ...) std::printf("[CC3000 : HCI RX] "x"\r\n", ##__VA_ARGS__);
+    #endif
+#else
+    #define DBG_HCI(x, ...)
+#endif
+
+#if (CC3000_DEBUG_HCI_RX == 1)
+    #if (VT100_COLOUR == 1)
+        #define DBG_HCI_CMD(x, ...) std::printf("\x1b[2;36;40m[CC3000 : HCI TX] "x"\x1b[0;37;40m\r\n", ##__VA_ARGS__);
+    #else
+        #define DBG_HCI_CMD(x, ...) std::printf("[CC3000 : HCI TX] "x"\r\n", ##__VA_ARGS__);
+    #endif
+#else
+    #define DBG_HCI_CMD(x, ...)
+#endif
+
+#if (CC3000_DEBUG == 1)
+    #if (VT100_COLOUR == 1)
+        #define DBG_CC(x, ...) std::printf("\x1b[2;32;40m[CC3000] "x"\x1b[0;37;40m\r\n", ##__VA_ARGS__);
+    #else
+        #define DBG_CC(x, ...) std::printf("[CC3000] "x"\r\n", ##__VA_ARGS__);
+    #endif
+#else
+    #define DBG_CC(x, ...)
+#endif
+
+namespace mbed_cc3000 {
+
+/** User info structure
+ */
+typedef struct {
+    uint8_t FTC;           // First time config performed
+    uint8_t PP_version[2]; // Patch Programmer version
+    uint8_t SERV_PACK[2];  // Service Pack Version
+    uint8_t DRV_VER[3];    // Driver Version
+    uint8_t FW_VER[3];     // Firmware Version
+    uint8_t validCIK;      // CIK[] is valid (Client Interface Key)
+    uint8_t CIK[40];
+} tUserFS;
+
+/** Function pointers which are not yet implemented
+ */
+enum FunctionNumber {
+    FW_PATCHES          = 0,
+    DRIVER_PATCHES      = 1,
+    BOOTLOADER_PATCHES  = 2,
+};
+
+/** AP security
+ */
+enum Security {
+    NONE = 0,
+    WEP  = 1,
+    WPA  = 2,
+    WPA2 = 3
+};
+
+/** CC3000 Simple Link class which contains status of cc3000.
+ */
+class cc3000_simple_link {
+public:
+    /**
+     *  \brief ctor - sets magic number in the buffers (overflow mark).
+     *  \param none
+     *  \return none
+     */
+    cc3000_simple_link();
+    /**
+     *  \brief dtor
+     *  \param none
+     *  \return none
+     */
+    ~cc3000_simple_link();
+    /**
+     *  \brief Returns data received flag.
+     *  \return Data received flag.
+     */
+    uint8_t get_data_received_flag();
+    /**
+     *  \brief Set data received flag.
+     *  \param value The value to be set.
+     */
+    void set_data_received_flag(uint8_t value);
+    /** Returns if tx was completed.
+     *  \return
+     *    true if tx was completed,
+     *    false otherwise.
+     */
+    bool get_tx_complete_signal();
+    /**
+     *  \brief Sets flag that tx was completed.
+     *  \param value Value to be set
+     *  \return none
+     */
+    void set_tx_complete_signal(bool value);
+    /**
+     *  \brief Get receive buffer.
+     *  \param none
+     *  \return Pointer to the receive buffer.
+     */
+    uint8_t *get_received_buffer();
+    /**
+     *  \brief Get transmit buffer.
+     *  \param none
+     *  \return Pointer to the transmit buffer.
+     */
+    uint8_t *get_transmit_buffer();
+    /**
+     *  \brief Get number of free buffers.
+     *  \param none
+     *  \return
+     *      Number of free buffers.
+     */
+    uint16_t get_number_free_buffers();
+    /**
+     *  \brief Set number of free buffers.
+     *  \param value Number of free buffers.
+     *  \return none
+     */
+    void set_number_free_buffers(uint16_t value);
+    /**
+     *  \brief Retrieve buffer length.
+     *  \param none
+     *  \return Buffer length
+     */
+    uint16_t get_buffer_length();
+    /**
+     *  \brief Set buffer length
+     *  \param value The length
+     *  \return none
+     */
+    void set_buffer_length(uint16_t value);
+    /**
+     *  \brief Retrieve pending data flag.
+     *  \param none
+     *  \return Pending data flag
+     */
+    uint16_t get_pending_data();
+    /**
+     *  \brief Set pending data flag.
+     *  \param value Pending data value.
+     *  \return none
+     */
+    void set_pending_data(uint16_t value);
+    /**
+     *  \brief Retreive op code.
+     *  \param none
+     *  \return Op code
+     */
+    uint16_t get_op_code();
+    /**
+     *  \brief Set op code.
+     *  \param code op code.
+     *  \return none
+     */
+    void set_op_code(uint16_t code);
+    /**
+     *  \brief Get number of released packets.
+     *  \param none
+     *  \return Number of released packets.
+     */
+    uint16_t get_released_packets();
+    /**
+     *  \brief Set number of released packets.
+     *  \param value Number of released packets.
+     *  \return none
+     */
+    void set_number_of_released_packets(uint16_t value);
+    /**
+     *  \brief Get number of sent packats
+     *  \param none
+     *  \return Number of sent packets.
+     */
+    uint16_t get_sent_packets();
+    /**
+     *  \brief Set number of sent packets
+     *  \param value Number of sent packets.
+     *  \return none
+     */
+    void set_sent_packets(uint16_t value);
+    /**
+     *  \brief Retrieve transmit error
+     *  \param none
+     *  \return Transmit error
+     */
+    int32_t get_transmit_error();
+    /**
+     *  \brief Set transmit error.
+     *  \param value Error to be set.
+     *  \return none
+     */
+    void set_transmit_error(int32_t value);
+    /**
+     *  \brief Get buffer size.
+     *  \param none
+     *  \return Size of buffer.
+     */
+    uint16_t get_buffer_size();
+    /**
+     *  \brief Set buffer size.
+     *  \param value Buffer size.
+     *  \return none
+     */
+    void set_buffer_size(uint16_t value);
+    /**
+     *  \brief Not used currently.
+     *  \param function Number of desired function.
+     *  \return void pointer to the function (need to recast).
+     */
+    void *get_func_pointer(FunctionNumber function);
+    /**
+     *  \brief Retreive pointer to the received data.
+     *  \param none
+     *  \return Pointer to the received data buffer.
+     */
+    uint8_t *get_received_data();
+    /**
+     *  \brief Set received data pointer.
+     *  \param pointer Pointer to the buffer.
+     *  \return none
+     */
+    void set_received_data(uint8_t *pointer);
+private:
+    uint8_t  _data_received_flag;
+    bool     _tx_complete_signal;
+    uint16_t _rx_event_opcode;
+    uint16_t _free_buffers;
+    uint16_t _buffer_length;
+    uint16_t _buffer_size;
+    uint16_t _rx_data_pending;
+    uint16_t _sent_packets;
+    uint16_t _released_packets;
+    int32_t  _transmit_data_error;
+    uint8_t  *_received_data;
+    uint8_t  _rx_buffer[CC3000_RX_BUFFER_SIZE];
+    uint8_t  _tx_buffer[CC3000_TX_BUFFER_SIZE];
+private:
+    /* Not used currently */
+    int8_t *(* _fFWPatches)(uint32_t *length);
+    int8_t *(* _fDriverPatches)(uint32_t *length);
+    int8_t *(* _fBootLoaderPatches)(uint32_t *length);
+};
+
+/** Forward declaration classes
+ */
+class cc3000_hci;
+class cc3000_nvmem;
+class cc3000_spi;
+class cc3000;
+
+/** Event layer
+ */
+class cc3000_event {
+public:
+    /**
+     *  \brief Ctor
+     *  \param simplelink Reference to simple link object.
+     *  \param hci        Reference to hci object.
+     *  \param spi        Reference to spi object.
+     *  \param cc3000     Reference to cc3000 object.
+     *  \return none
+     */
+    cc3000_event(cc3000_simple_link &simplelink, cc3000_hci &hci, cc3000_spi &spi, cc3000 &cc3000);
+    /**
+     *  \brief Dtor
+     *  \param none
+     *  \return none
+     */
+     ~cc3000_event();
+    /**
+     *  \brief Handle unsolicited event from type patch request.
+     *  \param  event_hdr  event header
+     *  \return none
+     */
+    void hci_unsol_handle_patch_request(uint8_t *event_hdr);
+    /**
+    *  \brief  Parse the incoming event packets and issue corresponding event handler from global array of handlers pointers.
+    *  \param  ret_param      incoming data buffer
+    *  \param  from           from information (in case of data received)
+    *  \param  fromlen        from information length (in case of data received)
+    *  \return                none
+    */
+    uint8_t* hci_event_handler(void *ret_param, uint8_t *from, uint8_t *fromlen);
+    /**
+    *  \brief  Handle unsolicited events.
+    *  \param  event_hdr Event header
+    *  \return           1 if event supported and handled
+    *  \return           0 if event is not supported
+    */
+    int32_t hci_unsol_event_handler(uint8_t *event_hdr);
+    /**
+    *  \brief   Parse the incoming unsolicited event packets and start corresponding event handler.
+    *  \param   None
+    *  \return  ESUCCESS if successful, EFAIL if an error occurred.
+    */
+    int32_t hci_unsolicited_event_handler(void);
+    /**
+    *  \brief  Get the socket status.
+    *  \param  Sd Socket IS
+    *  \return Current status of the socket.
+    */
+    int32_t get_socket_active_status(int32_t sd);
+    /**
+    *  \brief Check if the socket ID and status are valid and set the global socket status accordingly.
+    *  \param Sd Sock descr
+    *  \param Status status to be set
+    *  \return  none
+    */
+    void set_socket_active_status(int32_t sd, int32_t status);
+    /**
+    *  \brief Keep track on the number of packets transmitted and update the number of free buffer in the SL device.
+    *  \brief Called when unsolicited event = HCI_EVNT_DATA_UNSOL_FREE_BUFF has received.
+    *  \param event pointer to the string contains parameters for IPERF.
+    *  \return ESUCCESS if successful, EFAIL if an error occurred.
+    */
+    int32_t hci_event_unsol_flowcontrol_handler(uint8_t *event);
+    /**
+    *  \brief Update the socket status.
+    *  \param resp_params Socket IS
+    *  \return Current status of the socket.
+    */
+    void update_socket_active_status(uint8_t *resp_params);
+    /**
+     *  \brief  Wait for event, pass it to the hci_event_handler and update the event opcode in a global variable.
+     *  \param  op_code   Command operation code
+     *  \param  ret_param Command return parameters
+     *  \return none
+     */
+    void simplelink_wait_event(uint16_t op_code, void *ret_param);
+    /**
+     *  \brief  Wait for data, pass it to the hci_event_handler and set the data available flag.
+     *  \param  buffer  Data buffer
+     *  \param  from    From information
+     *  \param  fromlen From information length
+     *  \return none
+     */
+    void simplelink_wait_data(uint8_t *buffer, uint8_t *from, uint8_t *fromlen);
+    /**
+     *  \brief Trigger Received event/data processing - called from the SPI library to receive the data
+     *  \param buffer pointer to the received data buffer\n
+     *                The function triggers Received event/data processing\n
+     *  \return none
+     */
+    void received_handler(uint8_t *buffer);
+private:
+    uint32_t            socket_active_status;
+    cc3000_simple_link  &_simple_link;
+    cc3000_hci          &_hci;
+    cc3000_spi          &_spi;
+    cc3000              &_cc3000;
+};
+
+/** Netapp layer
+ */
+class cc3000_netapp {
+public:
+    /**
+     *  \brief Ctor
+     *  \param simple_link Reference to the simple link object.
+     *  \param nvmem       Reference to the nvmem object.
+     *  \param hci         Reference to the hci object.
+     *  \param event       Reference to the event object.
+     *  \return none
+     */
+    cc3000_netapp(cc3000_simple_link &simple_link, cc3000_nvmem &nvmem, cc3000_hci &hci, cc3000_event &event);
+    /**
+     *  \brief Dtor
+     *  \param none
+     *  \return none
+     */
+    ~cc3000_netapp();
+    /**
+     *  \brief Configure device MAC address and store it in NVMEM.
+     *         The value of the MAC address configured through the API will be\n
+     *         stored in CC3000 non volatile memory, thus preserved over resets.\n
+     *  \param  mac   device mac address, 6 bytes. Saved: yes
+     *  \return       return on success 0, otherwise error.
+     */
+    int32_t config_mac_adrress(uint8_t *mac);
+    /**
+     *  \brief Configure the network interface, static or dynamic (DHCP).
+     *         In order to activate DHCP mode, ip, subnet_mask, default_gateway must be 0.\n
+     *         The default mode of CC3000 is DHCP mode. The configuration is saved in non volatile memory\n
+     *         and thus preserved over resets.\n
+     *  \param  ip                device mac address, 6 bytes. Saved: yes
+     *  \param  subnet_mask       device mac address, 6 bytes. Saved: yes
+     *  \param  default_gateway   device mac address, 6 bytes. Saved: yes
+     *  \param  dns_server        device mac address, 6 bytes. Saved: yes
+     *  \return 0 on success, otherwise error.
+     *  \note   If the mode is altered, a reset of CC3000 device is required to apply the changes.\n
+     *          Also note that an asynchronous event of type 'DHCP_EVENT' is generated only when\n
+     *          a connection to the AP was established. This event is generated when an IP address\n
+     *          is allocated either by the DHCP server or by static allocation.\n
+     */
+    int32_t dhcp(uint32_t *ip, uint32_t *subnet_mask,uint32_t *default_gateway, uint32_t *dns_server);
+#ifndef CC3000_TINY_DRIVER
+    /**
+     *  \brief Get the CC3000 Network interface information.
+     *        This information is only available after establishing a WLAN connection.\n
+     *        Undefined values are returned when this function is called before association.\n
+     *  \param  ipconfig  pointer to a tNetappIpconfigRetArgs structure for storing the network interface configuration.\n
+     *          tNetappIpconfigRetArgs: aucIP             - ip address,\n
+     *                                  aucSubnetMask     - mask
+     *                                  aucDefaultGateway - default gateway address\n
+     *                                  aucDHCPServer     - dhcp server address\n
+     *                                  aucDNSServer      - dns server address\n
+     *                                  uaMacAddr         - mac address\n
+     *                                  uaSSID            - connected AP ssid\n
+     *  \return  none
+     *  \note    This function is useful for figuring out the IP Configuration of\n
+     *           the device when DHCP is used and for figuring out the SSID of\n
+     *           the Wireless network the device is associated with.\n
+     */
+    void ipconfig(tNetappIpconfigRetArgs *ipconfig);
+    /**
+     *  \brief Set new timeout values for DHCP lease timeout, ARP  refresh timeout, keepalive event timeout and socket inactivity timeout
+     *  \param  dhcp       DHCP lease time request, also impact\n
+     *                     the DHCP renew timeout.\n
+     *                     Range:               [0-0xffffffff] seconds,\n
+     *                                          0 or 0xffffffff = infinite lease timeout.\n
+     *                     Resolution:          10 seconds.\n
+     *                     Influence:           only after reconnecting to the AP. \n
+     *                     Minimal bound value: MIN_TIMER_VAL_SECONDS - 20 seconds.\n
+     *                     The parameter is saved into the CC3000 NVMEM.\n
+     *                     The default value on CC3000 is 14400 seconds.\n
+     *
+     *  \param  arp        ARP refresh timeout, if ARP entry is not updated by\n
+     *                     incoming packet, the ARP entry will be  deleted by\n
+     *                     the end of the timeout. \n
+     *                     Range:               [0-0xffffffff] seconds, 0 = infinite ARP timeout\n
+     *                     Resolution:          10 seconds.\n
+     *                     Influence:           at runtime.\n
+     *                     Minimal bound value: MIN_TIMER_VAL_SECONDS - 20 seconds\n
+     *                     The parameter is saved into the CC3000 NVMEM.\n
+     *                     The default value on CC3000 is 3600 seconds.\n
+     *
+     *  \param  keep_alive     Keepalive event sent by the end of keepalive timeout\n
+     *                         Range:               [0-0xffffffff] seconds, 0 == infinite timeout\n
+     *                         Resolution:          10 seconds.\n
+     *                         Influence:           at runtime.\n
+     *                         Minimal bound value: MIN_TIMER_VAL_SECONDS - 20 sec\n
+     *                         The parameter is saved into the CC3000 NVMEM. \n
+     *                         The default value on CC3000 is 10 seconds.\n
+     *
+     *  \param  inactivity      Socket inactivity timeout, socket timeout is\n
+     *                          refreshed by incoming or outgoing packet, by the\n
+     *                          end of the socket timeout the socket will be closed\n
+     *                          Range:               [0-0xffffffff] sec, 0 == infinite timeout.\n
+     *                          Resolution:          10 seconds.\n
+     *                          Influence:           at runtime.\n
+     *                          Minimal bound value: MIN_TIMER_VAL_SECONDS - 20 sec\n
+     *                          The parameter is saved into the CC3000 NVMEM.\n
+     *                          The default value on CC3000 is 60 seconds.\n
+     *
+     *  \return 0 on success,otherwise error.
+     *
+     *  \note   A parameter set to a non zero value less than 20s automatically changes to 20s.
+     */
+    int32_t timeout_values(uint32_t *dhcp, uint32_t *arp,uint32_t *keep_alive, uint32_t *inactivity);
+    /**
+     *  \brief send ICMP ECHO_REQUEST to network hosts
+     *  \param  ip              destination IP address
+     *  \param  ping_attempts   number of echo requests to send
+     *  \param  ping_size       send buffer size which may be up to 1400 bytes
+     *  \param  ping_timeout    Time to wait for a response,in milliseconds.
+     *  \return 0 on success, otherwise error.
+     *
+     *  \note     A succesful operation will generate an asynchronous ping report event.\n
+     *            The report structure is defined by structure netapp_pingreport_args_t.\n
+     *  \warning  Calling this function while a Ping Request is in progress will kill the ping request in progress.
+     */
+    int32_t ping_send(uint32_t *ip, uint32_t ping_attempts, uint32_t ping_size, uint32_t ping_timeout);
+    /**
+     *  \brief Ping status request.
+     *         This API triggers the CC3000 to send asynchronous events: HCI_EVNT_WLAN_ASYNC_PING_REPORT.\n
+     *         This event will create the report structure in netapp_pingreport_args_t.\n
+     *         This structure is filled with ping results until the API is triggered.\n
+     *         netapp_pingreport_args_t: packets_sent     - echo sent\n
+     *                                   packets_received - echo reply\n
+     *                                   min_round_time   - minimum round time\n
+     *                                   max_round_time   - max round time\n
+     *                                   avg_round_time   - average round time\n
+     *
+     *  \param   none
+     *  \return  none
+     *  \note    When a ping operation is not active, the returned structure fields are 0.
+     */
+    void ping_report();
+    /**
+     *  \brief Stop any ping request.
+     *  \param none
+     *  \return 0 on success
+     *         -1 on error
+     */
+    int32_t ping_stop();
+    /**
+     *  \brief Flush ARP table
+     *  \param none
+     *  \return none
+     */
+    int32_t arp_flush();
+#endif
+private:
+    cc3000_simple_link  &_simple_link;
+    cc3000_nvmem        &_nvmem;
+    cc3000_hci          &_hci;
+    cc3000_event        &_event;
+};
+
+#ifndef CC3000_UNENCRYPTED_SMART_CONFIG
+/** Security class used only if encrypted smart config is set
+ */
+class cc3000_security {
+public:
+    /**
+     *  \brief Expand a 16 bytes key for AES128 implementation.
+     *  \param expanded_key expanded AES128 key
+     *  \param key AES128 key - 16 bytes
+     *  \return none
+     */
+    void expandKey(uint8_t *expanded_key, uint8_t *key);
+    /**
+     *  \brief multiply by 2 in the galois field.
+     *  \param value Argument to multiply
+     *  \return multiplied argument
+     */
+    uint8_t galois_mul2(uint8_t value);
+    /**
+     *  \brief internal implementation of AES128 encryption.
+     *      straight forward aes encryption implementation\n
+     *      first the group of operations
+     *      - addRoundKey
+     *      - subbytes
+     *      - shiftrows
+     *      - mixcolums\n
+     *
+     *      is executed 9 times, after this addroundkey to finish the 9th\n
+     *      round, after that the 10th round without mixcolums\n
+     *      no further subfunctions to save cycles for function calls\n
+     *      no structuring with "for (....)" to save cycles.\n
+     *  \param[in]     expanded_key expanded AES128 key
+     *  \param[in/out] state 16 bytes of plain text and cipher text
+     *  \return  none
+     */
+    void aes_encr(uint8_t *state, uint8_t *expanded_key);
+    /**
+     *  \brief internal implementation of AES128 decryption.
+     *      straightforward aes decryption implementation\n
+     *      the order of substeps is the exact reverse of decryption\n
+     *      inverse functions:
+     *      - addRoundKey is its own inverse
+     *      - rsbox is inverse of sbox
+     *      - rightshift instead of leftshift
+     *      - invMixColumns = barreto + mixColumns\n
+     *
+     *      no further subfunctions to save cycles for function calls\n
+     *      no structuring with "for (....)" to save cycles\n
+     *  \param[in]     expanded_key expanded AES128 key
+     *  \param[in\out] state 16 bytes of cipher text and plain text
+     *  \return  none
+     */
+    void aes_decr(uint8_t *state, uint8_t *expanded_key);
+    /**
+     *  \brief AES128 encryption.
+     *      Given AES128 key and 16 bytes plain text, cipher text of 16 bytes is computed.\n
+     *      The AES implementation is in mode ECB (Electronic Code Book).\n
+     *  \param[in]  key   AES128 key of size 16 bytes
+     *  \param[in\out] state   16 bytes of plain text and cipher text
+     *  \return  none
+     */
+    void aes_encrypt(uint8_t *state, uint8_t *key);
+    /**
+     *  \brief AES128 decryption.
+     *      Given AES128 key and  16 bytes cipher text, plain text of 16 bytes is computed.\n
+     *      The AES implementation is in mode ECB (Electronic Code Book).\n
+     *  \param[in]  key   AES128 key of size 16 bytes
+     *  \param[in\out] state   16 bytes of cipher text and plain text
+     *  \return  none
+     */
+    void aes_decrypt(uint8_t *state, uint8_t *key);
+    /**
+     *  \brief Read the AES128 key from fileID #12 in EEPROM.
+     *  \param[out]  key   AES128 key of size 16 bytes
+     *  \return  0 on success, error otherwise.
+     */
+    int32_t aes_read_key(uint8_t *key);
+    /**
+     *  \brief Write the AES128 key to fileID #12 in EEPROM.
+     *  \param[out]  key   AES128 key of size 16 bytes
+     *  \return  on success 0, error otherwise.
+     */
+    int32_t aes_write_key(uint8_t *key);
+private:
+    uint8_t _expanded_key[176];
+};
+#endif
+
+/** Socket layer
+ */
+class cc3000_socket {
+public:
+    /**
+     *  \brief Ctor
+     *  \param simplelink Reference to simple link object.
+     *  \param hci        Reference to hci object.
+     *  \param event      Reference to event object.
+     *  \return none
+     */
+    cc3000_socket(cc3000_simple_link &simplelink, cc3000_hci &hci, cc3000_event &event);
+    /**
+     *  \brief Dtor
+     *  \param
+     *  \return none
+     */
+    ~cc3000_socket();
+    /**
+     *  \brief create an endpoint for communication.
+     *      The socket function creates a socket that is bound to a specific transport service provider.\n
+     *      This function is called by the application layer to obtain a socket handle.\n
+     *
+     *  \param   domain    selects the protocol family which will be used for\n
+     *                     communication. On this version only AF_INET is supported\n
+     *  \param   type      specifies the communication semantics. On this version\n
+     *                     only SOCK_STREAM, SOCK_DGRAM, SOCK_RAW are supported\n
+     *  \param   protocol  specifies a particular protocol to be used with the\n
+     *                     socket IPPROTO_TCP, IPPROTO_UDP or IPPROTO_RAW are supported.\n
+     *  \return  On success, socket handle that is used for consequent socket operations\n
+     *           On error, -1 is returned.\n
+     */
+    int32_t socket(int32_t domain, int32_t type, int32_t protocol);
+    /**
+     *  \brief accept a connection on a socket.
+     *      This function is used with connection-based socket types\n
+     *      (SOCK_STREAM). It extracts the first connection request on the\n
+     *      queue of pending connections, creates a new connected socket, and\n
+     *      returns a new file descriptor referring to that socket.\n
+     *      The newly created socket is not in the listening state.\n
+     *      The original socket sd is unaffected by this call.\n
+     *      The argument sd is a socket that has been created with socket(),\n
+     *      bound to a local address with bind(), and is  listening for \n
+     *      connections after a listen(). The argument addr is a pointer \n
+     *      to a sockaddr structure. This structure is filled in with the \n
+     *      address of the peer socket, as known to the communications layer.\n
+     *      The exact format of the address returned addr is determined by the \n
+     *      socket's address family. The addrlen argument is a value-result\n
+     *      argument: it should initially contain the size of the structure\n
+     *      pointed to by addr, on return it will contain the actual\n
+     *      length (in bytes) of the address returned.\n
+     *
+     *  \param[in]   sd      socket descriptor (handle)\n
+     *  \param[out]  addr    the argument addr is a pointer to a sockaddr structure\n
+     *                       This structure is filled in with the address of the \n
+     *                       peer socket, as known to the communications layer.  \n
+     *                       determined. The exact format of the address returned \n
+     *                       addr is by the socket's address sockaddr. \n
+     *                       On this version only AF_INET is supported.\n
+     *                       This argument returns in network order.\n
+     *  \param[out] addrlen  the addrlen argument is a value-result argument: \n
+     *                       it should initially contain the size of the structure\n
+     *                       pointed to by addr.\n
+     *  \return  For socket in blocking mode:\n
+     *            - On success, socket handle. on failure negative\n
+     *           For socket in non-blocking mode:\n
+     *            - On connection establishment, socket handle\n
+     *            - On connection pending, SOC_IN_PROGRESS (-2)\n
+     *            - On failure, SOC_ERROR    (-1)\n
+     *  \sa     socket ; bind ; listen
+     */
+    int32_t accept(int32_t sd, sockaddr *addr, socklen_t *addrlen);
+    /**
+     *  \brief assign a name to a socket.
+     *      This function gives the socket the local address addr.\n
+     *      addr is addrlen bytes long. Traditionally, this is called when a \n
+     *      socket is created with socket, it exists in a name space (address \n
+     *      family) but has no name assigned.\n
+     *      It is necessary to assign a local address before a SOCK_STREAM\n
+     *      socket may receive connections.\n
+     *
+     *  \param[in]   sd      socket descriptor (handle)
+     *  \param[out]  addr    specifies the destination address. On this version\n
+     *                       only AF_INET is supported.\n
+     *  \param[out] addrlen  contains the size of the structure pointed to by addr.\n
+     *  \return      On success, zero is returned.\n
+     *               On error, -1 is returned.\n
+     *  \sa          socket ; accept ; listen
+     */
+    int32_t bind(int32_t sd, const sockaddr *addr, int32_t addrlen);
+    /**
+     *  \brief HostFlowControlConsumeBuff.
+     *      if SEND_NON_BLOCKING is not defined - block until a free buffer is available,\n
+     *      otherwise return the status of the available buffers.\n
+     *
+     *  \param  sd  socket descriptor
+     *  \return  0 in case there are buffers available, \n
+     *          -1 in case of bad socket\n
+     *          -2 if there are no free buffers present (only when SEND_NON_BLOCKING is enabled)\n
+     */
+    int32_t HostFlowControlConsumeBuff(int32_t sd);
+    /**
+     *  \brief The socket function closes a created socket.
+     *  \param   sd    socket handle.
+     *  \return  On success, zero is returned. On error, -1 is returned.
+     */
+    int32_t closesocket(int32_t sd);
+    /**
+     *  \brief listen for connections on a socket.
+     *      The willingness to accept incoming connections and a queue\n
+     *      limit for incoming connections are specified with listen(),\n
+     *      and then the connections are accepted with accept.\n
+     *      The listen() call applies only to sockets of type SOCK_STREAM\n
+     *      The backlog parameter defines the maximum length the queue of\n
+     *      pending connections may grow to. \n
+     *
+     *  \param[in]  sd       socket descriptor (handle)
+     *  \param[in]  backlog  specifies the listen queue depth. On this version\n
+     *                       backlog is not supported.\n
+     *  \return     On success, zero is returned.\n
+     *              On error, -1 is returned.\n
+     *  \sa         socket ; accept ; bind
+     *  \note       On this version, backlog is not supported
+     */
+    int32_t listen(int32_t sd, int32_t backlog);
+    /**
+     *  \brief initiate a connection on a socket.
+     *      Function connects the socket referred to by the socket descriptor\n
+     *      sd, to the address specified by addr. The addrlen argument \n
+     *      specifies the size of addr. The format of the address in addr is \n
+     *      determined by the address space of the socket. If it is of type \n
+     *      SOCK_DGRAM, this call specifies the peer with which the socket is \n
+     *      to be associated; this address is that to which datagrams are to be\n
+     *      sent, and the only address from which datagrams are to be received. \n
+     *      If the socket is of type SOCK_STREAM, this call attempts to make a \n
+     *      connection to another socket. The other socket is specified  by \n
+     *      address, which is an address in the communications space of the\n
+     *      socket. Note that the function implements only blocking behavior \n
+     *      thus the caller will be waiting either for the connection \n
+     *      establishment or for the connection establishment failure.\n
+     *
+     *  \param[in]   sd       socket descriptor (handle)
+     *  \param[in]   addr     specifies the destination addr. On this version\n
+     *                        only AF_INET is supported.\n
+     *  \param[out]  addrlen  contains the size of the structure pointed to by addr
+     *  \return      On success, zero is returned.\n
+                   On error, -1 is returned\n
+     *  \sa socket
+     */
+    int32_t connect(int32_t sd, const sockaddr *addr, int32_t addrlen);
+    /**
+     *  \brief Monitor socket activity.
+     *      Select allow a program to monitor multiple file descriptors,\n
+     *      waiting until one or more of the file descriptors become \n
+     *      "ready" for some class of I/O operation \n
+     *
+     *  \param[in]    nfds       the highest-numbered file descriptor in any of the\n
+     *                           three sets, plus 1.  \n
+     *  \param[out]   readsds    socket descriptors list for read monitoring\n
+     *  \param[out]   writesds   socket descriptors list for write monitoring\n
+     *  \param[out]   exceptsds  socket descriptors list for exception monitoring\n
+     *  \param[in]    timeout    is an upper bound on the amount of time elapsed\n
+     *                           before select() returns. Null means infinity \n
+     *                           timeout. The minimum timeout is 5 milliseconds,\n
+     *                          less than 5 milliseconds will be set\n
+     *                           automatically to 5 milliseconds.\n
+     *  \return    On success, select() returns the number of file descriptors\n
+     *             contained in the three returned descriptor sets (that is, the\n
+     *             total number of bits that are set in readfds, writefds,\n
+     *             exceptfds) which may be zero if the timeout expires before\n
+     *             anything interesting  happens.\n
+     *             On error, -1 is returned.\n
+     *                   *readsds - return the sockets on which Read request will\n
+     *                              return without delay with valid data.\n
+     *                   *writesds - return the sockets on which Write request \n
+     *                                 will return without delay.\n
+     *                   *exceptsds - return the sockets which closed recently.\n
+     *  \Note   If the timeout value set to less than 5ms it will automatically\n
+     *          change to 5ms to prevent overload of the system\n
+     *  \sa socket
+     */
+    int32_t select(int32_t nfds, fd_set *readsds, fd_set *writesds, fd_set *exceptsds, struct timeval *timeout);
+    /**
+     *  \brief get socket options.
+     *      This function manipulate the options associated with a socket.\n
+     *      Options may exist at multiple protocol levels; they are always\n
+     *      present at the uppermost socket level.\n
+     *      When manipulating socket options the level at which the option \n
+     *      resides and the name of the option must be specified.  \n
+     *      To manipulate options at the socket level, level is specified as \n
+     *      SOL_SOCKET. To manipulate options at any other level the protocol \n
+     *      number of the appropriate protocol controlling the option is \n
+     *      supplied. For example, to indicate that an option is to be \n
+     *      interpreted by the TCP protocol, level should be set to the \n
+     *      protocol number of TCP; \n
+     *      The parameters optval and optlen are used to access optval -\n
+     *      use for setsockopt(). For getsockopt() they identify a buffer\n
+     *      in which the value for the requested option(s) are to \n
+     *      be returned. For getsockopt(), optlen is a value-result \n
+     *      parameter, initially containing the size of the buffer \n
+     *      pointed to by option_value, and modified on return to \n
+     *      indicate the actual size of the value returned. If no option \n
+     *      value is to be supplied or returned, option_value may be NULL.\n
+     *
+     *  \param[in]   sd          socket handle
+     *  \param[in]   level       defines the protocol level for this option
+     *  \param[in]   optname     defines the option name to Interrogate
+     *  \param[out]  optval      specifies a value for the option
+     *  \param[out]  optlen      specifies the length of the option value
+     *  \return      On success, zero is returned. On error, -1 is returned
+     *
+     *  \Note   On this version the following two socket options are enabled:\n
+     *          The only protocol level supported in this version is SOL_SOCKET (level).\n
+     *               1. SOCKOPT_RECV_TIMEOUT (optname)\n
+     *                  SOCKOPT_RECV_TIMEOUT configures recv and recvfrom timeout in milliseconds.\n
+     *                  In that case optval should be pointer to unsigned long.\n
+     *               2. SOCKOPT_NONBLOCK (optname). sets the socket non-blocking mode on or off.\n
+     *                  In that case optval should be SOCK_ON or SOCK_OFF (optval).\n
+     *  \sa setsockopt
+     */
+    int32_t getsockopt (int32_t sd, int32_t level, int32_t optname, void *optval, socklen_t *optlen);
+    /**
+     *  \brief Read data from socket (simple_link_recv).
+     *      Return the length of the message on successful completion.\n
+     *      If a message is too long to fit in the supplied buffer, excess bytes may\n
+     *      be discarded depending on the type of socket the message is received from.\n
+     *
+     *  \param sd       socket handle
+     *  \param buf      read buffer
+     *  \param len      buffer length
+     *  \param flags    indicates blocking or non-blocking operation
+     *  \param from     pointer to an address structure indicating source address
+     *  \param fromlen  source address structure size
+     *  \return         Return the number of bytes received, or -1 if an error occurred
+     */
+    int32_t simple_link_recv(int32_t sd, void *buf, int32_t len, int32_t flags, sockaddr *from, socklen_t *fromlen, int32_t opcode);
+    /**
+     *  \brief Transmit a message to another socket (simple_link_send).
+     *  \param sd       socket handle
+     *  \param buf      write buffer
+     *  \param len      buffer length
+     *  \param flags    On this version, this parameter is not supported
+     *  \param to       pointer to an address structure indicating destination address
+     *  \param tolen    destination address structure size
+     *  \return         Return the number of bytes transmitted, or -1 if an error\n
+     *                  occurred, or -2 in case there are no free buffers available\n
+     *                  (only when SEND_NON_BLOCKING is enabled)\n
+     */
+    int32_t simple_link_send(int32_t sd, const void *buf, int32_t len, int32_t flags, const sockaddr *to, int32_t tolen, int32_t opcode);
+    /**
+     *  \brief Receive a message from a connection-mode socket.
+     *  \param[in]  sd     socket handle
+     *  \param[out] buf    Points to the buffer where the message should be stored
+     *  \param[in]  len    Specifies the length in bytes of the buffer pointed to \n
+     *                     by the buffer argument.\n
+     *  \param[in] flags   Specifies the type of message reception. \n
+     *                     On this version, this parameter is not supported.\n
+     *  \return         Return the number of bytes received, or -1 if an error occurred
+     *  \sa recvfrom
+     *  \Note On this version, only blocking mode is supported.
+     */
+    int32_t recv(int32_t sd, void *buf, int32_t len, int32_t flags);
+    /**
+     *  \brief read data from socket (recvfrom).
+     *      Receives a message from a connection-mode or connectionless-mode socket.\n
+     *      Note that raw sockets are not supported.\n
+     *
+     *  \param[in]  sd       socket handle
+     *  \param[out] buf      Points to the buffer where the message should be stored
+     *  \param[in]  len      Specifies the length in bytes of the buffer pointed to \n
+     *                       by the buffer argument.\n
+     *  \param[in] flags     Specifies the type of message reception.\n
+     *                       On this version, this parameter is not supported.\n
+     *  \param[in] from      pointer to an address structure indicating the source\n
+     *                       address: sockaddr. On this version only AF_INET is\n
+     *                       supported.\n
+     *  \param[in] fromlen   source address structure size
+     *  \return              Return the number of bytes received, or -1 if an error occurred
+     *  \sa recv
+     *  \Note On this version, only blocking mode is supported.
+     */
+    int32_t recvfrom(int32_t sd, void *buf, int32_t len, int32_t flags, sockaddr *from, socklen_t *fromlen);
+    /**
+     *  \brief Transmit a message to another socket (send).
+     *  \param sd       socket handle
+     *  \param buf      Points to a buffer containing the message to be sent
+     *  \param len      message size in bytes
+     *  \param flags    On this version, this parameter is not supported
+     *  \return         Return the number of bytes transmitted, or -1 if an\n
+     *                  error occurred\n
+     *  \Note           On this version, only blocking mode is supported.
+     *  \sa             sendto
+     */
+    int32_t send(int32_t sd, const void *buf, int32_t len, int32_t flags);
+    /**
+     *  \brief Transmit a message to another socket (sendto).
+     *  \param sd       socket handle
+     *  \param buf      Points to a buffer containing the message to be sent
+     *  \param len      message size in bytes
+     *  \param flags    On this version, this parameter is not supported
+     *  \param to       pointer to an address structure indicating the destination\n
+     *                  address: sockaddr. On this version only AF_INET is\n
+     *                  supported.\n
+     *  \param tolen    destination address structure size
+     *  \return         Return the number of bytes transmitted, or -1 if an error occurred
+     *  \Note           On this version, only blocking mode is supported.
+     *  \sa             send
+     */
+    int32_t sendto(int32_t sd, const void *buf, int32_t len, int32_t flags, const sockaddr *to, socklen_t tolen);
+    /**
+     *  \brief Set CC3000 in mDNS advertiser mode in order to advertise itself.
+     *  \param[in] mdns_enabled                 flag to enable/disable the mDNS feature
+     *  \param[in] device_service_name          Service name as part of the published\n
+     *                                          canonical domain name\n
+     *  \param[in] device_service_name_length   Length of the service name
+     *  \return   On success, zero is returned,\n
+     *            return SOC_ERROR if socket was not opened successfully, or if an error occurred.\n
+     */
+    int32_t mdns_advertiser(uint16_t mdns_enabled, uint8_t * device_service_name, uint16_t device_service_name_length);
+    /**
+     *  \brief
+     *  \param[in] s_addr in host format ( little endian )
+     *  \param[in] *buf     buffer to write too
+     *  \param[in] buflen   length of supplied buffer
+     *  \return    pointer to buf \n
+     */
+    char * inet_ntoa_r(uint32_t s_addr, char *buf, int buflen);
+#ifndef CC3000_TINY_DRIVER
+    /**
+     *  \brief Get host IP by name.\n
+     *      Obtain the IP Address of machine on network\n
+     *
+     *  \param[in]   hostname     host name
+     *  \param[in]   name_length  name length
+     *  \param[out]  out_ip_addr  This parameter is filled in with host IP address.\n
+     *                            In case that host name is not resolved, \n
+     *                            out_ip_addr is zero.\n
+     *  \return      On success, positive is returned.\n
+     *               On error, negative is returned by its name.\n
+     *  \note  On this version, only blocking mode is supported. Also note that\n
+     *         The function requires DNS server to be configured prior to its usage.\n
+     */
+    int32_t gethostbyname(uint8_t *hostname, uint16_t name_length, uint32_t *out_ip_addr);
+    /**
+     *  \brief set socket options.
+     *      This function manipulate the options associated with a socket.\n
+     *      Options may exist at multiple protocol levels; they are always\n
+     *      present at the uppermost socket level.\n
+     *      When manipulating socket options the level at which the option \n
+     *      resides and the name of the option must be specified.\n
+     *      To manipulate options at the socket level, level is specified as\n
+     *      SOL_SOCKET. To manipulate options at any other level the protocol \n
+     *      number of the appropriate protocol controlling the option is \n
+     *      supplied. For example, to indicate that an option is to be \n
+     *      interpreted by the TCP protocol, level should be set to the \n
+     *      protocol number of TCP; \n
+     *      The parameters optval and optlen are used to access optval - \n
+     *      use for setsockopt(). For getsockopt() they identify a buffer\n
+     *      in which the value for the requested option(s) are to \n
+     *      be returned. For getsockopt(), optlen is a value-result \n
+     *      parameter, initially containing the size of the buffer \n
+     *      pointed to by option_value, and modified on return to \n
+     *      indicate the actual size of the value returned. If no option \n
+     *      value is to be supplied or returned, option_value may be NULL.\n
+     *
+     *  \param[in]   sd          socket handle
+     *  \param[in]   level       defines the protocol level for this option
+     *  \param[in]   optname     defines the option name to Interrogate
+     *  \param[in]   optval      specifies a value for the option
+     *  \param[in]   optlen      specifies the length of the option value
+     *  \return      On success, zero is returned.\n
+     *               On error, -1 is returned\n
+     *
+     *  \Note   On this version the following two socket options are enabled:\n
+     *          The only protocol level supported in this version is SOL_SOCKET (level).\n
+     *               1. SOCKOPT_RECV_TIMEOUT (optname)\n
+     *                  SOCKOPT_RECV_TIMEOUT configures recv and recvfrom timeout in milliseconds.\n
+     *                  In that case optval should be pointer to unsigned long.\n
+     *               2. SOCKOPT_NONBLOCK (optname). sets the socket non-blocking mode on or off.\n
+     *                  In that case optval should be SOCK_ON or SOCK_OFF (optval).\n
+     *  \sa getsockopt
+     */
+    int32_t setsockopt(int32_t sd, int32_t level, int32_t optname, const void *optval, socklen_t optlen);
+#endif
+private:
+    cc3000_simple_link  &_simple_link;
+    cc3000_hci          &_hci;
+    cc3000_event        &_event;
+};
+
+/** SPI communication layer
+ */
+class cc3000_spi {
+public:
+    /**
+     *  \brief Ctor
+     *  \param irq         IRQ pin
+     *  \param cc3000_en   Enable pin
+     *  \param cc3000_cs   Chip select pin
+     *  \param cc3000_spi  SPI object
+     *  \param irq_port    Port for IRQ pin (needed for enable/disable interrupts)
+     *  \param event       Reference to the event object.
+     *  \param simple_link Reference to the simple link object.
+     *  \return none
+     */
+     cc3000_spi(PinName cc3000_irq, PinName cc3000_en, PinName cc3000_cs, SPI cc3000_spi, cc3000_event &event, cc3000_simple_link &simple_link);
+    /**
+     *  \brief Dtor
+     *  \param none
+     *  \return none
+     */
+     ~cc3000_spi();
+     /**
+      *  \brief Close SPI - disables IRQ and set received buffer to 0
+      *  \param none
+      *  \return none
+     */
+     void close();
+    /**
+     *  \brief Open the SPI interface
+     *  \param  none
+     *  \return none
+     */
+     void open();
+    /**
+     *  \brief First SPI write after powerup (delay needed between SPI header and body)
+     *  \param  buffer pointer to write buffer
+     *  \param  length buffer length
+     *  \return 0
+     */
+     uint32_t first_write(uint8_t *buffer, uint16_t length);
+    /**
+     *  \brief SPI Write function
+     *  \param  buffer pointer to write buffer
+     *  \param  length buffer length
+     *  \return 0
+     */
+     uint32_t write(uint8_t *buffer, uint16_t length);
+    /**
+     *  \brief Low level SPI write
+     *  \param  data pointer to data buffer
+     *  \param  size number of bytes
+     *  \return none
+     */
+     void write_synchronous(uint8_t *data, uint16_t size);
+    /**
+     *  \brief Low level SPI read
+     *  \param  data pointer to data buffer
+     *  \param  size number of bytes
+     *  \return none
+     */
+     void read_synchronous(uint8_t *data, uint16_t size);
+    /**
+     *  \brief Process the received SPI Header and in accordance with it - continue reading the packet
+     *  \param  None
+     *  \return 0
+     */
+     uint32_t read_data_cont();
+     /**
+     *  \brief Enable WLAN interrutp
+     *  \param  None
+     *  \return None
+     */
+    void wlan_irq_enable();
+     /**
+     *  \brief Disable WLAN interrutp
+     *  \param  None
+     *  \return None
+     */
+    void wlan_irq_disable();
+    /**
+     *  \brief Get WLAN interrupt status
+     *  \param   None
+     *  \return  0 : No interrupt occured
+     *           1 : Interrupt occured
+     */
+    uint32_t wlan_irq_read();
+    /**
+     *  \brief SPI interrupt Handler.
+     *      The external WLAN device asserts the IRQ line when data is ready.\n
+     *      The host CPU needs to acknowledges the IRQ by asserting CS.\n
+     *
+     *  \param  none
+     *  \return none
+     */
+    void WLAN_IRQHandler();
+    /**
+     *  \brief Enable/Disable the WLAN module
+     *  \param  value 1 : Enable
+     *                0 : Disable
+     *  \return None
+     */
+    void set_wlan_en(uint8_t value);
+private:
+    tSpiInfo            _spi_info;
+    InterruptIn         _wlan_irq;
+    DigitalOut          _wlan_en;
+    DigitalOut          _wlan_cs;
+    SPI                 _wlan_spi;
+    cc3000_event        &_event;
+    cc3000_simple_link  &_simple_link;
+    bool                _process_irq;
+};
+
+/** HCI layer
+ */
+class cc3000_hci {
+public:
+    /**
+     *  \brief Ctor
+     *  \param spi Reference to the spi object.
+     *  \return none
+     */
+    cc3000_hci(cc3000_spi &spi);
+    /**
+     *  \brief Dtor
+     *  \param none
+     *  \return none
+     */
+    ~cc3000_hci();
+    /**
+     *  \brief Initiate an HCI command.
+     *  \param op_code command operation code
+     *  \param buffer  pointer to the command's arguments buffer
+     *  \param length  length of the arguments
+     *  \return 0
+     */
+    uint16_t command_send(uint16_t op_code, uint8_t *buffer, uint8_t length);
+    /**
+     *  \brief Initiate an HCI data write operation
+     *  \param op_code     command operation code
+     *  \param args        pointer to the command's arguments buffer
+     *  \param arg_length  length of the arguments
+     *  \param data_length length od data
+     *  \param tail        pointer to the data buffer
+     *  \param tail_length buffer length
+     *  \return ESUCCESS
+     */
+    uint32_t data_send(uint8_t op_code, uint8_t *args, uint16_t arg_length,
+                        uint16_t data_length, const uint8_t *tail, uint16_t tail_length);
+    /**
+     *  \brief Prepare HCI header and initiate an HCI data write operation.
+     *  \param op_code     command operation code
+     *  \param buffer      pointer to the data buffer
+     *  \param arg_length  arguments length
+     *  \param data_length data length
+     *  \return none
+     */
+    void data_command_send(uint16_t op_code, uint8_t *buffer, uint8_t arg_length,
+                            uint16_t data_length);
+    /**
+     *  \brief Prepare HCI header and initiate an HCI patch write operation.
+     *  \param op_code     command operation code
+     *  \param buffer      pointer to the command's arguments buffer
+     *  \param patch       pointer to patch content buffer
+     *  \param data_length data length
+     *  \return none
+     */
+    void patch_send(uint8_t op_code, uint8_t *buffer, uint8_t *patch, uint16_t data_length);
+private:
+    cc3000_spi &_spi;
+};
+
+/** NVMEM layer
+ */
+class cc3000_nvmem {
+public:
+    /**
+     *  \brief Ctor
+     *  \param hci         Reference to the hci object.
+     *  \param event       Reference to the event object.
+     *  \param simple_link Reference to the simple link object.
+     *  \return none
+     */
+    cc3000_nvmem(cc3000_hci &hci, cc3000_event &event, cc3000_simple_link &simple_link);
+    /**
+     *  \brief Dtor
+     *  \param none
+     *  \return none
+     */
+    ~cc3000_nvmem();
+    /**
+     *  \brief Reads data from the file referred by the file_id parameter.
+     *      Reads data from file offset till length. Err if the file can't be used,
+     *      is invalid, or if the read is out of bounds.
+     *  \param file_id nvmem file id.
+     *  \param length  number of bytes to read.
+     *  \param offset  offset in file from where to read.
+     *  \param buff    output buffer pointer.
+     *  \return
+     *      Number of bytes read, otherwise error.
+     */
+    int32_t read(uint32_t file_id, uint32_t length, uint32_t offset, uint8_t *buff);
+    /**
+     *  \brief Write data to nvmem.
+     *  \param file_id      Nvmem file id
+     *  \param length       number of bytes to write
+     *  \param entry_offset offset in file to start write operation from
+     *  \param buff         data to write
+     *  \return
+     *      On success 0, error otherwise.
+     */
+    int32_t write(uint32_t file_id, uint32_t length, uint32_t entry_offset, uint8_t *buff);
+    /**
+     *  \brief Write MAC address to EEPROM.
+     *  \param mac Mac address to be set
+     *  \return
+     *      On success 0, error otherwise.
+     */
+    uint8_t set_mac_address(uint8_t *mac);
+    /**
+     *  \brief Read MAC address from EEPROM.
+     *  \param mac Mac address
+     *  \return
+     *      On success 0, error otherwise.
+     */
+    uint8_t get_mac_address(uint8_t *mac);
+    /**
+     *  \brief Program a patch to a specific file ID. The SP data is assumed to be organized in 2-dimensional.
+     *      Each line is SP_PORTION_SIZE bytes long.
+     *  \param file_id nvmem file id/
+     *  \param length  number of bytes to write
+     *  \param data    SP data to write
+     *  \return
+     *      On success 0, error otherwise.
+     */
+    uint8_t write_patch(uint32_t file_id, uint32_t length, const uint8_t *data);
+    /**
+     *  \brief Create new file entry and allocate space on the NVMEM. Applies only to user files.
+     *  \param file_id nvmem file Id
+     *  \param new_len entry ulLength
+     *  \return
+     */
+    int32_t create_entry(uint32_t file_id, uint32_t new_len);
+#ifndef CC3000_TINY_DRIVER
+    /**
+     *  \brief Read patch version. read package version (WiFi FW patch, river-supplicant-NS patch,
+     *      bootloader patch)
+     *  \param patch_ver First number indicates package ID and the second number indicates
+     *      package build number
+     *  \return
+     *      On success 0, error otherwise.
+     */
+    uint8_t read_sp_version(uint8_t* patch_ver);
+#endif
+private:
+    cc3000_hci          &_hci;
+    cc3000_event        &_event;
+    cc3000_simple_link  &_simple_link;
+};
+
+/** WLAN layer
+ */
+class cc3000_wlan {
+public:
+    /**
+     *  \brief Ctor
+     *  \param simple_link Reference to the simple link object.
+     *  \param event       Reference to the event object.
+     *  \param spi         Reference to the spi object.
+     *  \param hci         Reference to the hci object.
+     *  \return none
+     */
+    cc3000_wlan(cc3000_simple_link &simple_link, cc3000_event &event, cc3000_spi &spi, cc3000_hci &hci);
+    /**
+     *  \brief Dtor
+     *  \param none
+     *  \return none
+     */
+    ~cc3000_wlan();
+    /**
+     *  \brief Send SIMPLE LINK START to cc3000.
+     *  \param patches_available_host Flag to indicate if patches are available.
+     *  \return none
+     */
+    void simpleLink_init_start(uint16_t patches_available_host);
+    /**
+     *  \brief Start wlan device. Blocking call until init is completed.
+     *  \param patches_available_host Flag to indicate if patches are available.
+     *  \return none
+     */
+    void start(uint16_t patches_available_host);
+    /**
+     *  \brief Stop wlan device
+     *  \param none
+     *  \return none
+     */
+    void stop(void);
+#ifndef CC3000_TINY_DRIVER
+    /**
+     *  \brief Connect to AP.
+     *  \param sec_type    Security option.
+     *  \param ssid        up to 32 bytes, ASCII SSID
+     *  \param ssid_length length of SSID
+     *  \param b_ssid      6 bytes specified the AP bssid
+     *  \param key         up to 16 bytes specified the AP security key
+     *  \param key_len     key length
+     *  \return
+     *      On success, zero is returned. On error, negative is returned.
+     */
+    int32_t connect(uint32_t sec_type, const uint8_t *ssid, int32_t ssid_length, uint8_t *b_ssid, uint8_t *key, int32_t key_len);
+    /**
+     *  \brief Add profile. Up to 7 profiles are supported.
+     *  \param sec_type                      Security option.
+     *  \param ssid                          Up to 32 bytes, ASCII SSID
+     *  \param ssid_length                   Length of SSID
+     *  \param b_ssid                        6 bytes specified the AP bssid
+     *  \param priority                      Up to 16 bytes specified the AP security key
+     *  \param pairwise_cipher_or_tx_key_len Key length
+     *  \param group_cipher_tx_key_index     Key length for WEP security
+     *  \param key_mgmt                      KEY management
+     *  \param pf_or_key                     Security key
+     *  \param pass_phrase_length            Security key length for WPA\WPA2
+     *  \return
+     *      On success, zero is returned. On error, negative is returned.
+     */
+    int32_t add_profile(uint32_t sec_type, uint8_t* ssid, uint32_t ssid_length, uint8_t *b_ssid, uint32_t priority, uint32_t pairwise_cipher_or_tx_key_len, uint32_t group_cipher_tx_key_index,
+                          uint32_t key_mgmt, uint8_t* pf_or_key, uint32_t pass_phrase_length);
+    /**
+     *  \brief Gets entry from scan result table. The scan results are returned
+     *      one by one, and each entry represents a single AP found in the area.
+     *  \param scan_timeout Not supported yet
+     *  \param results      Scan result
+     *  \return
+     *      On success, zero is returned. On error, -1 is returned
+     */
+    int32_t ioctl_get_scan_results(uint32_t scan_timeout, uint8_t *results);
+    /**
+     *  \brief Start and stop scan procedure. Set scan parameters.
+     *  \param enable             Start/stop application scan
+     *  \param min_dwell_time     Minimum dwell time value to be used for each channel, in ms. (Default: 20)
+     *  \param max_dwell_time     Maximum dwell time value to be used for each channel, in ms. (Default: 30)
+     *  \param num_probe_requests Max probe request between dwell time. (Default:2)
+     *  \param channel_mask       Bitwise, up to 13 channels (0x1fff).
+     *  \param rssi_threshold     RSSI threshold. Saved: yes (Default: -80)
+     *  \param snr_threshold      NSR threshold. Saved: yes (Default: 0)
+     *  \param default_tx_power   probe Tx power. Saved: yes (Default: 205)
+     *  \param interval_list      Pointer to array with 16 entries (16 channels)
+     *  \return
+     *      On success, zero is returned. On error, -1 is returned.
+     */
+    int32_t ioctl_set_scan_params(uint32_t enable, uint32_t min_dwell_time, uint32_t max_dwell_time, uint32_t num_probe_requests,
+                                uint32_t channel_mask, int32_t rssi_threshold, uint32_t snr_threshold, uint32_t default_tx_power, uint32_t *interval_list);
+    /**
+     *  \brief Get wlan status: disconnected, scanning, connecting or connected
+     *  \param none
+     *  \return
+     *      WLAN_STATUS_DISCONNECTED, WLAN_STATUS_SCANING, STATUS_CONNECTING or WLAN_STATUS_CONNECTED
+     */
+    int32_t ioctl_statusget(void);
+#else
+    /**
+     *  \brief Connect to AP
+     *  \param ssid        Up to 32 bytes and is ASCII SSID of the AP
+     *  \param ssid_length Length of the SSID
+     *  \return
+     *      On success, zero is returned. On error, negative is returned.
+     */
+    int32_t connect(const uint8_t *ssid, int32_t ssid_length);
+    /**
+     *  \brief When auto start is enabled, the device connects to station from the profiles table.
+     *      If several profiles configured the device choose the highest priority profile.
+     *  \param sec_type                      WLAN_SEC_UNSEC,WLAN_SEC_WEP,WLAN_SEC_WPA,WLAN_SEC_WPA2
+     *  \param ssid                          SSID up to 32 bytes
+     *  \param ssid_length                   SSID length
+     *  \param b_ssid                        bssid 6 bytes
+     *  \param priority                      Profile priority. Lowest priority:0.
+     *  \param pairwise_cipher_or_tx_key_len Key length for WEP security
+     *  \param group_cipher_tx_key_index     Key index
+     *  \param key_mgmt                      KEY management
+     *  \param pf_or_key                     Security key
+     *  \param pass_phrase_length            Security key length for WPA\WPA2
+     *  \return
+     *      On success, zero is returned. On error, -1 is returned
+     */
+    int32_t add_profile(uint32_t sec_type, uint8_t *ssid, uint32_t ssid_length, uint8_t *b_ssid, uint32_t priority,
+                      uint32_t pairwise_cipher_or_tx_key_len, uint32_t group_cipher_tx_key_index, uint32_t key_mgmt,
+                      uint8_t* pf_or_key, uint32_t pass_phrase_length);
+#endif
+#ifndef CC3000_UNENCRYPTED_SMART_CONFIG
+    /**
+     *  \brief Process the acquired data and store it as a profile.
+     *  \param none
+     *  \return
+     *      On success, zero is returned. On error, -1 is returned.
+     */
+    int32_t smart_config_process(void);
+#endif
+    /**
+     *  \brief Disconnect connection from AP.
+     *  \param none
+     *  \return
+     *      0 if disconnected done, other CC3000 already disconnected.
+     */
+    int32_t disconnect();
+    /**
+     *  \brief When auto is enabled, the device tries to connect according the following policy:
+     *      1) If fast connect is enabled and last connection is valid, the device will try to
+     *      connect to it without the scanning procedure (fast). The last connection will be
+     *      marked as invalid, due to adding/removing profile.
+     *      2) If profile exists, the device will try to connect it (Up to seven profiles).
+     *      3) If fast and profiles are not found, and open mode is enabled, the device
+     *      will try to connect to any AP.
+     *      Note that the policy settings are stored in the CC3000 NVMEM.
+     *  \param should_connect_to_open_ap Enable(1), disable(0) connect to any available AP.
+     *  \param use_fast_connect          Enable(1), disable(0). if enabled, tries to
+     *                                   connect to the last connected AP.
+     *  \param use_profiles              Enable(1), disable(0) auto connect after reset.
+     *                                   and periodically reconnect if needed.
+     *  \return
+     *      On success, zero is returned. On error, -1 is returned
+     */
+    int32_t ioctl_set_connection_policy(uint32_t should_connect_to_open_ap, uint32_t use_fast_connect, uint32_t use_profiles);
+    /**
+     *  \brief Delete WLAN profile
+     *  \param index Number of profile to delete
+     *  \return
+     *      On success, zero is returned. On error, -1 is returned
+     */
+    int32_t ioctl_del_profile(uint32_t index);
+    /**
+     *  \brief Mask event according to bit mask. In case that event is
+     *      masked (1), the device will not send the masked event to host.
+     *  \param mask event mask
+     *  \return
+     *      On success, zero is returned. On error, -1 is returned
+     */
+    int32_t set_event_mask(uint32_t mask);
+    /**
+     *  \brief Start to acquire device profile. The device acquire its own
+     *      profile, if profile message is found.
+     *  \param encrypted_flag Indicates whether the information is encrypted
+     *  \return
+     *      On success, zero is returned. On error, -1 is returned.
+     */
+    int32_t smart_config_start(uint32_t encrypted_flag);
+    /**
+     *  \brief Stop the acquire profile procedure.
+     *  \param none
+     *  \return
+     *      On success, zero is returned. On error, -1 is returned
+     */
+    int32_t smart_config_stop(void);
+    /**
+     *  \brief Configure station ssid prefix.
+     *  \param new_prefix 3 bytes identify the SSID prefix for the Smart Config.
+     *  \return
+     *      On success, zero is returned. On error, -1 is returned.
+     */
+    int32_t smart_config_set_prefix(uint8_t *new_prefix);
+private:
+    cc3000_simple_link  &_simple_link;
+    cc3000_event        &_event;
+    cc3000_spi          &_spi;
+    cc3000_hci          &_hci;
+};
+
+/** The main object of cc3000 implementation
+ */
+class cc3000 {
+public:
+    /** status structure */
+    typedef struct {
+        uint8_t socket;
+        bool    dhcp;
+        bool    connected;
+        bool    smart_config_complete;
+        bool    stop_smart_config;
+        bool    dhcp_configured;
+        bool    ok_to_shut_down;
+        bool    enabled;
+    } tStatus;
+    /**
+     *  \brief Ctor.
+     *  \param cc3000_irq IRQ pin
+     *  \param cc3000_en  Enable pin
+     *  \param cc3000_cs  Chip select pin
+     *  \param cc3000_spi SPI interface
+     */
+    cc3000(PinName cc3000_irq, PinName cc3000_en, PinName cc3000_cs, SPI cc3000_spi);
+    /**
+     *  \brief Dtor.
+     */
+    ~cc3000();
+    /**
+     *  \brief Initiate cc3000. It starts the wlan communication.
+     *  \param patch Patch
+     */
+    void start(uint8_t patch);
+    /**
+     *  \brief Stops the wlan communication.
+     */
+    void stop();
+    /**
+     *  \brief Restarts the wlan communication.
+     */
+    void restart(uint8_t patch);
+    /**
+     *  \brief Callback which is called from the event class. This updates status of cc3000.
+     *  \param event_type Type of the event
+     *  \param data       Pointer to data
+     *  \param length     Length of data
+     *  \return none
+     */
+    void usync_callback(int32_t event_type, uint8_t *data, uint8_t length);
+    /**
+     *  \brief Start connection to SSID (open/secured) non-blocking
+     *  \param ssid          SSID name
+     *  \param key           Security key (if key = 0, open connection)
+     *  \param security_mode Security mode
+     *  \return true if connection was established, false otherwise.
+     */
+    bool connect_non_blocking(const uint8_t *ssid, const uint8_t *key, int32_t security_mode);
+    /**
+     *  \brief Connect to SSID (open/secured) with timeout (10s).
+     *  \param ssid          SSID name
+     *  \param key           Security key (if key = 0, open connection)
+     *  \param security_mode Security mode
+     *  \return true if connection was established, false otherwise.
+     */
+    bool connect_to_AP(const uint8_t *ssid, const uint8_t *key, int32_t security_mode);
+    /**
+     *  \brief Connect to SSID which is secured
+     *  \param ssid          SSID name
+     *  \param key           Security key
+     *  \param security_mode Security mode
+     *  \return true if connection was established, false otherwise.
+     */
+    bool connect_secure(const uint8_t *ssid, const uint8_t *key, int32_t security_mode);
+    /**
+     *  \brief Connect to SSID which is open (no security)
+     *  \param ssid          SSID name
+     *  \return true if connection was established, false otherwise.
+     */
+    bool connect_open(const uint8_t *ssid);
+    /**
+     *  \brief Status of the cc3000 module.
+     *  \return true if it's enabled, false otherwise.
+     */
+    bool is_enabled();
+    /**
+     *  \brief Status of the cc3000 connection.
+     *  \return true if it's connected, false otherwise.
+     */
+    bool is_connected();
+    /**
+     *  \brief Status of DHCP.
+     *  \param none
+     *  \return true if DCHP is configured, false otherwise.
+     */
+    bool is_dhcp_configured();
+    /**
+     *  \brief Status of smart confing completation.
+     *  \param none
+     *  \return smart config was set, false otherwise.
+     */
+    bool is_smart_confing_completed();
+    /**
+     *  \brief Return the cc3000's mac address.
+     *  \param address Retreived mac address.
+     *  \return
+     */
+    uint8_t get_mac_address(uint8_t address[6]);
+    /**
+     *  \brief Set the cc3000's mac address.
+     *  \param address Mac address to be set.
+     *  \return
+     */
+    uint8_t set_mac_address(uint8_t address[6]);
+    /**
+     *  \brief Get user file info.
+     *  \param  info_file Pointer where info will be stored.
+     *  \param  size      Available size.
+     *  \return none
+     */
+    void get_user_file_info(uint8_t *info_file, size_t size);
+    /**
+     *  \brief Set user filo info.
+     *  \param info_file Pointer to user's info.
+     *  \return none
+     */
+    void set_user_file_info(uint8_t *info_file, size_t size);
+    /**
+     *  \brief Start smart config.
+     *  \param smart_config_key Pointer to smart config key.
+     *  \return none
+     */
+    void start_smart_config(const uint8_t *smart_config_key);  /* TODO enable AES ? */
+#ifndef CC3000_TINY_DRIVER
+    /**
+     *  \brief Return ip configuration.
+     *  \param ip_config Pointer to ipconfig data.
+     *  \return true if it's connected and info was retrieved, false otherwise.
+     */
+    bool get_ip_config(tNetappIpconfigRetArgs *ip_config);
+#endif
+    /**
+     *  \brief Delete all stored profiles.
+     *  \param none
+     *  \return none
+     */
+    void delete_profiles(void);
+    /**
+     *  \brief Ping an ip address.
+     *  \param ip       Destination IP address
+     *  \param attempts Number of attempts
+     *  \param timeout  Time to wait for a response,in milliseconds.
+     *  \param size     Send buffer size which may be up to 1400 bytes
+     */
+    uint32_t ping(uint32_t ip, uint8_t attempts, uint16_t timeout, uint8_t size);
+    /**
+     *  \brief Returns cc3000 instance. Used in Socket interface.
+     *  \param none
+     *  \return Pointer to cc3000 object
+     */
+    static cc3000* get_instance() {
+        return _inst;
+    }
+#if (CC3000_ETH_COMPAT == 1)
+    /**
+     *  \brief Ctor for EthernetInterface
+     *  \param cc3000_irq   IRQ pin
+     *  \param cc3000_en    Enable pin
+     *  \param cc3000_cs    Chip select pin
+     *  \param cc3000_spi   SPI interface
+     *  \param ssid         SSID
+     *  \param phrase       Password
+     *  \param sec          Security of the AP
+     *  \param smart_config Smart config selection
+     */
+    cc3000(PinName cc3000_irq, PinName cc3000_en, PinName cc3000_cs, SPI cc3000_spi, const char *ssid, const char *phrase, Security sec, bool smart_config);
+    /**
+     *  \brief Disconnect wlan device.
+     *  \param none
+     *  \return 0 if successful, -1 otherwise.
+     */
+    int disconnect();
+    /**
+     *  \brief Initialize the interface with DHCP.
+     *  \param none
+     *  \return none
+     */
+    void init();
+    /**
+     *  \brief Initialize the interface with a static IP address.
+     *  \param ip      the IP address to use.
+     *  \param mask    the IP address mask
+     *  \param gateway the gateway to use
+     *  \return none
+     */
+    void init(const char *ip, const char *mask, const char *gateway);
+    /**
+     *  \brief Connect Bring the interface up.
+     *  \param timeout_ms timeout in ms
+     *  \return 0 if successful, -1 otherwise.
+     */
+    int connect(unsigned int timeout_ms = 20000);
+    /**
+     *  \brief Get the MAC address of your Ethernet interface.
+     *  \param none
+     *  \return
+     *      Pointer to a string containing the MAC address.
+     */
+    char* getMACAddress();
+     /**
+     *  \brief Get the IP address of your Ethernet interface.
+     *  \param none
+     *  \return
+     *      Pointer to a string containing the IP address.
+     */
+    char* getIPAddress();
+     /**
+     *  \brief Get the Gateway address of your Ethernet interface
+     *  \param none
+     *  \return
+     *      Pointer to a string containing the Gateway address
+     */
+    char* getGateway();
+     /**
+     *  \brief Get the Network mask of your Ethernet interface
+     *  \param none
+     *  \return
+     *      Pointer to a string containing the Network mask
+     */
+    char* getNetworkMask();
+#endif
+public:
+    cc3000_simple_link  _simple_link;
+    cc3000_event        _event;
+    cc3000_socket       _socket;
+    cc3000_spi          _spi;
+    cc3000_hci          _hci;
+    cc3000_nvmem        _nvmem;
+    cc3000_netapp       _netapp;
+    cc3000_wlan         _wlan;
+#ifndef CC3000_UNENCRYPTED_SMART_CONFIG
+    cc3000_security     _security;
+#endif
+protected:
+    static cc3000       *_inst;
+private:
+    tStatus                  _status;
+    netapp_pingreport_args_t _ping_report;
+    bool                     _closed_sockets[MAX_SOCKETS];
+#if (CC3000_ETH_COMPAT == 1)
+    uint8_t                  _phrase[30];
+    uint8_t                  _ssid[30];
+    Security                 _sec;
+    bool                     _smart_config;
+#endif
+};
+
+/**
+ * Copy 32 bit to stream while converting to little endian format.
+ * @param  p       pointer to the new stream
+ * @param  u32     pointer to the 32 bit
+ * @return         pointer to the new stream
+ */
+uint8_t *UINT32_TO_STREAM_f (uint8_t *p, uint32_t u32);
+
+/**
+ * Copy 16 bit to stream while converting to little endian format.
+ * @param  p       pointer to the new stream
+ * @param  u32     pointer to the 16 bit
+ * @return         pointer to the new stream
+ */
+uint8_t *UINT16_TO_STREAM_f (uint8_t *p, uint16_t u16);
+
+/**
+ * Copy received stream to 16 bit in little endian format.
+ * @param  p          pointer to the stream
+ * @param  offset     offset in the stream
+ * @return            pointer to the new 16 bit
+ */
+uint16_t STREAM_TO_UINT16_f(uint8_t* p, uint16_t offset);
+
+/**
+ * Copy received stream to 32 bit in little endian format.
+ * @param  p          pointer to the stream
+ * @param  offset     offset in the stream
+ * @return            pointer to the new 32 bit
+ */
+uint32_t STREAM_TO_UINT32_f(uint8_t* p, uint16_t offset);
+
+} /* end of mbed_cc3000 namespace */
+
+
+#endif
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/WifiRobot/cc3000/cc3000_common.h	Tue Dec 09 05:06:37 2014 +0000
@@ -0,0 +1,198 @@
+/*****************************************************************************
+*
+*  C++ interface/implementation created by Martin Kojtal (0xc0170). Thanks to
+*  Jim Carver and Frank Vannieuwkerke for their inital cc3000 mbed port and
+*  provided help.
+*
+*  This version of "host driver" uses CC3000 Host Driver Implementation. Thus
+*  read the following copyright:
+*
+*  Copyright (C) 2011 Texas Instruments Incorporated - http://www.ti.com/
+*
+*  Redistribution and use in source and binary forms, with or without
+*  modification, are permitted provided that the following conditions
+*  are met:
+*
+*    Redistributions of source code must retain the above copyright
+*    notice, this list of conditions and the following disclaimer.
+*
+*    Redistributions in binary form must reproduce the above copyright
+*    notice, this list of conditions and the following disclaimer in the
+*    documentation and/or other materials provided with the
+*    distribution.
+*
+*    Neither the name of Texas Instruments Incorporated nor the names of
+*    its contributors may be used to endorse or promote products derived
+*    from this software without specific prior written permission.
+*
+*  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+*  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+*  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
+*  A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
+*  OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
+*  SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
+*  LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
+*  DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
+*  THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+*  (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
+*  OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+*
+*****************************************************************************/
+#ifndef CC3000_COMMON_H
+#define CC3000_COMMON_H
+
+#include <errno.h>
+
+//#define CC3000_TINY_DRIVER                // Driver for small memory model CPUs
+
+#define ESUCCESS        0
+#define EFAIL          -1
+#define EERROR          EFAIL
+
+#define CC3000_UNENCRYPTED_SMART_CONFIG   // No encryption
+
+#define ERROR_SOCKET_INACTIVE   -57
+
+#define HCI_CC_PAYLOAD_LEN      5
+
+#define WLAN_ENABLE            (1)
+#define WLAN_DISABLE           (0)
+
+#define MAC_ADDR_LEN           (6)
+
+
+/*Defines for minimal and maximal RX buffer size. This size includes the spi
+  header and hci header.
+  maximal buffer size: MTU + HCI header + SPI header + sendto() args size
+  minimum buffer size: HCI header + SPI header + max args size
+
+  This buffer is used for receiving events and data.
+  The packet can not be longer than MTU size and CC3000 does not support
+  fragmentation. Note that the same buffer is used for reception of the data
+  and events from CC3000. That is why the minimum is defined.
+  The calculation for the actual size of buffer for reception is:
+  Given the maximal data size MAX_DATA that is expected to be received by
+  application, the required buffer Using recv() or recvfrom():
+
+    max(CC3000_MINIMAL_RX_SIZE, MAX_DATA + HEADERS_SIZE_DATA + fromlen + ucArgsize + 1)
+
+  Using gethostbyname() with minimal buffer size will limit the host name returned to 99 bytes.
+  The 1 is used for the overrun detection
+*/
+
+#define CC3000_MINIMAL_RX_SIZE      (118 + 1)
+#define CC3000_MAXIMAL_RX_SIZE      (511 + 1)
+
+/*Defines for minimal and maximal TX buffer size.
+  This buffer is used for sending events and data.
+  The packet can not be longer than MTU size and CC3000 does not support
+  fragmentation. Note that the same buffer is used for transmission of the data
+  and commands. That is why the minimum is defined.
+  The calculation for the actual size of buffer for transmission is:
+  Given the maximal data size MAX_DATA, the required buffer is:
+  Using Sendto():
+
+   max(CC3000_MINIMAL_TX_SIZE, MAX_DATA + SPI_HEADER_SIZE
+   + SOCKET_SENDTO_PARAMS_LEN + SIMPLE_LINK_HCI_DATA_HEADER_SIZE + 1)
+
+  Using Send():
+
+   max(CC3000_MINIMAL_TX_SIZE, MAX_DATA + SPI_HEADER_SIZE
+   + HCI_CMND_SEND_ARG_LENGTH + SIMPLE_LINK_HCI_DATA_HEADER_SIZE + 1)
+
+  The 1 is used for the overrun detection */
+
+#define CC3000_MINIMAL_TX_SIZE      (118 + 1)
+#define CC3000_MAXIMAL_TX_SIZE      (1519 + 1)
+
+//TX and RX buffer size - allow to receive and transmit maximum data at lengh 8.
+#ifdef CC3000_TINY_DRIVER
+#define TINY_CC3000_MAXIMAL_RX_SIZE 44
+#define TINY_CC3000_MAXIMAL_TX_SIZE 59
+#endif
+
+/*In order to determine your preferred buffer size,
+  change CC3000_MAXIMAL_RX_SIZE and CC3000_MAXIMAL_TX_SIZE to a value between
+  the minimal and maximal specified above.
+  Note that the buffers are allocated by SPI.
+*/
+
+#ifndef CC3000_TINY_DRIVER
+
+    #define CC3000_RX_BUFFER_SIZE   (CC3000_MAXIMAL_RX_SIZE)
+    #define CC3000_TX_BUFFER_SIZE   (CC3000_MAXIMAL_TX_SIZE)
+    #define SP_PORTION_SIZE         512
+
+//TINY DRIVER: We use smaller rx and tx buffers in order to minimize RAM consumption
+#else
+    #define CC3000_RX_BUFFER_SIZE   (TINY_CC3000_MAXIMAL_RX_SIZE)
+    #define CC3000_TX_BUFFER_SIZE   (TINY_CC3000_MAXIMAL_TX_SIZE)
+    #define SP_PORTION_SIZE         32
+#endif
+
+
+//Copy 8 bit to stream while converting to little endian format.
+#define UINT8_TO_STREAM(_p, _val)    {*(_p)++ = (_val);}
+//Copy 16 bit to stream while converting to little endian format.
+#define UINT16_TO_STREAM(_p, _u16)    (UINT16_TO_STREAM_f(_p, _u16))
+//Copy 32 bit to stream while converting to little endian format.
+#define UINT32_TO_STREAM(_p, _u32)    (UINT32_TO_STREAM_f(_p, _u32))
+//Copy a specified value length bits (l) to stream while converting to little endian format.
+#define ARRAY_TO_STREAM(p, a, l)     {uint32_t _i; for (_i = 0; _i < l; _i++) *(p)++ = ((uint8_t *) a)[_i];}
+//Copy received stream to 8 bit in little endian format.
+#define STREAM_TO_UINT8(_p, _offset, _u8)    {_u8 = (uint8_t)(*(_p + _offset));}
+//Copy received stream to 16 bit in little endian format.
+#define STREAM_TO_UINT16(_p, _offset, _u16)    {_u16 = STREAM_TO_UINT16_f(_p, _offset);}
+//Copy received stream to 32 bit in little endian format.
+#define STREAM_TO_UINT32(_p, _offset, _u32)    {_u32 = STREAM_TO_UINT32_f(_p, _offset);}
+#define STREAM_TO_STREAM(p, a, l)     {uint32_t _i; for (_i = 0; _i < l; _i++) *(a)++= ((uint8_t *) p)[_i];}
+
+typedef struct _sockaddr_t
+{
+    uint16_t  family;
+    uint8_t   data[14];
+} sockaddr;
+
+struct timeval
+{
+    int32_t tv_sec;       /* seconds */
+    int32_t tv_usec;      /* microseconds */
+};
+
+#define SMART_CONFIG_PROFILE_SIZE        67        // 67 = 32 (max ssid) + 32 (max key) + 1 (SSID length) + 1 (security type) + 1 (key length)
+
+/* patches type */
+#define PATCHES_HOST_TYPE_WLAN_DRIVER   0x01
+#define PATCHES_HOST_TYPE_WLAN_FW       0x02
+#define PATCHES_HOST_TYPE_BOOTLOADER    0x03
+
+#define SL_SET_SCAN_PARAMS_INTERVAL_LIST_SIZE    (16)
+#define SL_SIMPLE_CONFIG_PREFIX_LENGTH           (3)
+#define ETH_ALEN                                 (6)
+#define MAXIMAL_SSID_LENGTH                      (32)
+
+#define SL_PATCHES_REQUEST_DEFAULT               (0)
+#define SL_PATCHES_REQUEST_FORCE_HOST            (1)
+#define SL_PATCHES_REQUEST_FORCE_NONE            (2)
+
+
+#define      WLAN_SEC_UNSEC  (0)
+#define      WLAN_SEC_WEP    (1)
+#define      WLAN_SEC_WPA    (2)
+#define      WLAN_SEC_WPA2   (3)
+
+
+#define WLAN_SL_INIT_START_PARAMS_LEN           (1)
+#define WLAN_PATCH_PARAMS_LENGTH                (8)
+#define WLAN_SET_CONNECTION_POLICY_PARAMS_LEN   (12)
+#define WLAN_DEL_PROFILE_PARAMS_LEN             (4)
+#define WLAN_SET_MASK_PARAMS_LEN                (4)
+#define WLAN_SET_SCAN_PARAMS_LEN                (100)
+#define WLAN_GET_SCAN_RESULTS_PARAMS_LEN        (4)
+#define WLAN_ADD_PROFILE_NOSEC_PARAM_LEN        (24)
+#define WLAN_ADD_PROFILE_WEP_PARAM_LEN          (36)
+#define WLAN_ADD_PROFILE_WPA_PARAM_LEN          (44)
+#define WLAN_CONNECT_PARAM_LEN                  (29)
+#define WLAN_SMART_CONFIG_START_PARAMS_LEN      (4)
+
+#endif
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/WifiRobot/cc3000/cc3000_event.cpp	Tue Dec 09 05:06:37 2014 +0000
@@ -0,0 +1,680 @@
+/*****************************************************************************
+*
+*  C++ interface/implementation created by Martin Kojtal (0xc0170). Thanks to
+*  Jim Carver and Frank Vannieuwkerke for their inital cc3000 mbed port and
+*  provided help.
+*
+*  This version of "host driver" uses CC3000 Host Driver Implementation. Thus
+*  read the following copyright:
+*
+*  Copyright (C) 2011 Texas Instruments Incorporated - http://www.ti.com/
+*
+*  Redistribution and use in source and binary forms, with or without
+*  modification, are permitted provided that the following conditions
+*  are met:
+*
+*    Redistributions of source code must retain the above copyright
+*    notice, this list of conditions and the following disclaimer.
+*
+*    Redistributions in binary form must reproduce the above copyright
+*    notice, this list of conditions and the following disclaimer in the
+*    documentation and/or other materials provided with the
+*    distribution.
+*
+*    Neither the name of Texas Instruments Incorporated nor the names of
+*    its contributors may be used to endorse or promote products derived
+*    from this software without specific prior written permission.
+*
+*  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+*  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+*  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
+*  A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
+*  OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
+*  SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
+*  LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
+*  DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
+*  THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+*  (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
+*  OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+*
+*****************************************************************************/
+#include "cc3000.h"
+#include "cc3000_event.h"
+#include "cc3000_netapp.h"
+
+namespace mbed_cc3000 {
+
+#if (CC3000_DEBUG_HCI_RX == 1)
+const char *HCI_EVENT_STR[] =
+{
+    "Socket",
+    "Bind",
+    "Send",
+    "Recv",
+    "Accept",
+    "Listen",
+    "Connect",
+    "BSD Select",
+    "Set Socket Options",
+    "Get Socket Options",
+    "Close Socket",
+    "Unknown",
+    "Recv From",
+    "Write",
+    "Send To",
+    "Get Hostname",
+    "mDNS Advertise"
+};
+
+const char *HCI_NETAPP_STR[] =
+{
+    "DHCP",
+    "Ping Sent",
+    "Ping Report",
+    "Ping Stop",
+    "IP Config",
+    "ARP Flush",
+    "Unknown",
+    "Set Debug level",
+    "Set Timers"
+};
+
+// from 0-7
+const char *HCI_MISC_STR[] =
+{
+    "BASE - Error?",
+    "Connecting",
+    "Disconnect",
+    "Scan Param",
+    "Connect Policy",
+    "Add Profile",
+    "Del Profile",
+    "Get Scan Res",
+    "Event Mask",
+    "Status Req",
+    "Config Start",
+    "Config Stop",
+    "Config Set Prefix",
+    "Config Patch",
+};
+#endif
+
+cc3000_event::cc3000_event(cc3000_simple_link &simplelink, cc3000_hci &hci, cc3000_spi &spi, cc3000 &cc3000)
+    : socket_active_status(SOCKET_STATUS_INIT_VAL), _simple_link(simplelink), _hci(hci), _spi(spi), _cc3000(cc3000) {
+
+}
+
+cc3000_event::~cc3000_event() {
+
+}
+
+/* TODO removed buffer, set it in init */
+void cc3000_event::received_handler(uint8_t *buffer) {
+    _simple_link.set_data_received_flag(1);
+    _simple_link.set_received_data(buffer);
+
+    hci_unsolicited_event_handler();
+}
+
+void cc3000_event::hci_unsol_handle_patch_request(uint8_t *event_hdr) {
+    uint8_t *params = (uint8_t *)(event_hdr) + HCI_EVENT_HEADER_SIZE;
+    uint32_t length = 0;
+    uint8_t *patch;
+
+    switch (*params)
+    {
+        case HCI_EVENT_PATCHES_DRV_REQ:
+        {
+            tDriverPatches func_pointer = (tDriverPatches)_simple_link.get_func_pointer(DRIVER_PATCHES);
+            if (func_pointer)
+            {
+                patch = func_pointer(&length);
+                if (patch)
+                {
+                    _hci.patch_send(HCI_EVENT_PATCHES_DRV_REQ, _simple_link.get_transmit_buffer(), patch, length);
+                    return;
+                }
+            }
+
+            // Send 0 length Patches response event
+            _hci.patch_send(HCI_EVENT_PATCHES_DRV_REQ, _simple_link.get_transmit_buffer(), 0, 0);
+            break;
+        }
+        case HCI_EVENT_PATCHES_FW_REQ:
+        {
+            tFWPatches func_pointer = (tFWPatches)_simple_link.get_func_pointer(FW_PATCHES);
+            if (func_pointer)
+            {
+                patch = func_pointer(&length);
+                // Build and send a patch
+                if (patch)
+                {
+                    _hci.patch_send(HCI_EVENT_PATCHES_FW_REQ, _simple_link.get_transmit_buffer(), patch, length);
+                    return;
+                }
+            }
+            // Send 0 length Patches response event
+            _hci.patch_send(HCI_EVENT_PATCHES_FW_REQ, _simple_link.get_transmit_buffer(), 0, 0);
+            break;
+        }
+        case HCI_EVENT_PATCHES_BOOTLOAD_REQ:
+        {
+            tBootLoaderPatches func_pointer = (tBootLoaderPatches)_simple_link.get_func_pointer(BOOTLOADER_PATCHES);
+            if (func_pointer)
+            {
+                patch = func_pointer(&length);
+                if (patch)
+                {
+                    _hci.patch_send(HCI_EVENT_PATCHES_BOOTLOAD_REQ, _simple_link.get_transmit_buffer(), patch, length);
+                    return;
+                }
+            }
+            // Send 0 length Patches response event
+            _hci.patch_send(HCI_EVENT_PATCHES_BOOTLOAD_REQ, _simple_link.get_transmit_buffer(), 0, 0);
+            break;
+        }
+    }
+}
+
+static void hci_event_debug_print(uint16_t hciEventNo)
+{
+#if (CC3000_DEBUG_HCI_RX == 1)
+    if ((hciEventNo > HCI_CMND_SOCKET_BASE) && ( hciEventNo <= HCI_CMND_MDNS_ADVERTISE))
+    {
+        DBG_HCI("Event Received : 0x%04X - %s", hciEventNo, HCI_EVENT_STR[hciEventNo-HCI_CMND_SOCKET]);
+    }
+    else if ((hciEventNo > HCI_CMND_NETAPP_BASE) && ( hciEventNo <= HCI_NETAPP_SET_TIMERS))
+    {
+        DBG_HCI("Event Received : 0x%04X - %s", hciEventNo, HCI_NETAPP_STR[hciEventNo-HCI_NETAPP_DHCP]);
+    }
+    else if (hciEventNo < HCI_CMND_WLAN_CONFIGURE_PATCH+1)
+    {
+        DBG_HCI("Event Received : 0x%04X - %s", hciEventNo, HCI_MISC_STR[hciEventNo]);
+    }
+    else
+    {
+        DBG_HCI("Event Received : 0x%04X", hciEventNo);
+    }
+#endif
+}
+
+uint8_t *cc3000_event::hci_event_handler(void *ret_param, uint8_t *from, uint8_t *fromlen) {
+    uint8_t *received_data, argument_size;
+    uint16_t length;
+    uint8_t *pucReceivedParams;
+    uint16_t received_op_code = 0;
+    uint32_t return_value;
+    uint8_t * RecvParams;
+    uint8_t *RetParams;
+
+    while (1)
+    {
+
+        if (_simple_link.get_data_received_flag() != 0)
+        {
+            received_data = _simple_link.get_received_data();
+            if (*received_data == HCI_TYPE_EVNT)
+            {
+                // Event Received
+                STREAM_TO_UINT16((uint8_t *)received_data, HCI_EVENT_OPCODE_OFFSET,received_op_code);
+                pucReceivedParams = received_data + HCI_EVENT_HEADER_SIZE;
+                RecvParams = pucReceivedParams;
+                RetParams = (uint8_t *)ret_param;
+
+                // unsolicited event received - finish handling
+                if (hci_unsol_event_handler((uint8_t *)received_data) == 0)
+                {
+                    STREAM_TO_UINT8(received_data, HCI_DATA_LENGTH_OFFSET, length);
+                    hci_event_debug_print( received_op_code );
+                    switch(received_op_code)
+                    {   
+                        
+                    case HCI_CMND_READ_BUFFER_SIZE:
+                        {
+                            uint16_t temp = _simple_link.get_number_free_buffers();
+                            STREAM_TO_UINT8((uint8_t *)pucReceivedParams, 0, temp);
+                            _simple_link.set_number_free_buffers(temp);
+
+                            temp = _simple_link.get_buffer_length();
+                            STREAM_TO_UINT16((uint8_t *)pucReceivedParams, 1, temp);
+                            _simple_link.set_buffer_length(temp);
+                        }
+                        break;
+
+                    case HCI_CMND_WLAN_CONFIGURE_PATCH:
+                    case HCI_NETAPP_DHCP:
+                    case HCI_NETAPP_PING_SEND:
+                    case HCI_NETAPP_PING_STOP:
+                    case HCI_NETAPP_ARP_FLUSH:
+                    case HCI_NETAPP_SET_DEBUG_LEVEL:
+                    case HCI_NETAPP_SET_TIMERS:
+                    case HCI_EVNT_NVMEM_READ:
+                    case HCI_EVNT_NVMEM_CREATE_ENTRY:
+                    case HCI_CMND_NVMEM_WRITE_PATCH:
+                    case HCI_NETAPP_PING_REPORT:
+                    case HCI_EVNT_MDNS_ADVERTISE:
+
+                        STREAM_TO_UINT8(received_data, HCI_EVENT_STATUS_OFFSET, *(uint8_t *)ret_param);
+                        break;
+
+                    case HCI_CMND_SETSOCKOPT:
+                    case HCI_CMND_WLAN_CONNECT:
+                    case HCI_CMND_WLAN_IOCTL_STATUSGET:
+                    case HCI_EVNT_WLAN_IOCTL_ADD_PROFILE:
+                    case HCI_CMND_WLAN_IOCTL_DEL_PROFILE:
+                    case HCI_CMND_WLAN_IOCTL_SET_CONNECTION_POLICY:
+                    case HCI_CMND_WLAN_IOCTL_SET_SCANPARAM:
+                    case HCI_CMND_WLAN_IOCTL_SIMPLE_CONFIG_START:
+                    case HCI_CMND_WLAN_IOCTL_SIMPLE_CONFIG_STOP:
+                    case HCI_CMND_WLAN_IOCTL_SIMPLE_CONFIG_SET_PREFIX:
+                    case HCI_CMND_EVENT_MASK:
+                    case HCI_EVNT_WLAN_DISCONNECT:
+                    case HCI_EVNT_SOCKET:
+                    case HCI_EVNT_BIND:
+                    case HCI_CMND_LISTEN:
+                    case HCI_EVNT_CLOSE_SOCKET:
+                    case HCI_EVNT_CONNECT:
+                    case HCI_EVNT_NVMEM_WRITE:
+
+                        STREAM_TO_UINT32((uint8_t *)pucReceivedParams,0, *(uint32_t *)ret_param);
+                        break;
+
+                    case HCI_EVNT_READ_SP_VERSION:
+
+                        STREAM_TO_UINT8(received_data, HCI_EVENT_STATUS_OFFSET, *(uint8_t *)ret_param);
+                        ret_param = ((uint8_t *)ret_param) + 1;
+                        STREAM_TO_UINT32((uint8_t *)pucReceivedParams, 0, return_value);
+                        UINT32_TO_STREAM((uint8_t *)ret_param, return_value);
+                        break;
+
+                    case HCI_EVNT_BSD_GETHOSTBYNAME:
+
+                        STREAM_TO_UINT32((uint8_t *)pucReceivedParams,GET_HOST_BY_NAME_RETVAL_OFFSET,*(uint32_t *)ret_param);
+                        ret_param = ((uint8_t *)ret_param) + 4;
+                        STREAM_TO_UINT32((uint8_t *)pucReceivedParams,GET_HOST_BY_NAME_ADDR_OFFSET,*(uint32_t *)ret_param);
+                        break;
+
+                    case HCI_EVNT_ACCEPT:
+                        {
+                            STREAM_TO_UINT32((uint8_t *)pucReceivedParams,ACCEPT_SD_OFFSET,*(uint32_t *)ret_param);
+                            ret_param = ((uint8_t *)ret_param) + 4;
+                            STREAM_TO_UINT32((uint8_t *)pucReceivedParams,ACCEPT_RETURN_STATUS_OFFSET,*(uint32_t *)ret_param);
+                            ret_param = ((uint8_t *)ret_param) + 4;
+
+                            //This argument returns in network order
+                            memcpy((uint8_t *)ret_param, pucReceivedParams + ACCEPT_ADDRESS__OFFSET, sizeof(sockaddr));
+                            break;
+                        }
+
+                    case HCI_EVNT_RECV:
+                    case HCI_EVNT_RECVFROM:
+                        {
+                            STREAM_TO_UINT32((uint8_t *)pucReceivedParams,SL_RECEIVE_SD_OFFSET ,*(uint32_t *)ret_param);
+                            ret_param = ((uint8_t *)ret_param) + 4;
+                            STREAM_TO_UINT32((uint8_t *)pucReceivedParams,SL_RECEIVE_NUM_BYTES_OFFSET,*(uint32_t *)ret_param);
+                            ret_param = ((uint8_t *)ret_param) + 4;
+                            STREAM_TO_UINT32((uint8_t *)pucReceivedParams,SL_RECEIVE__FLAGS__OFFSET,*(uint32_t *)ret_param);
+
+                            if(((tBsdReadReturnParams *)ret_param)->iNumberOfBytes == ERROR_SOCKET_INACTIVE)
+                            {
+                                set_socket_active_status(((tBsdReadReturnParams *)ret_param)->iSocketDescriptor,SOCKET_STATUS_INACTIVE);
+                            }
+                            break;
+                        }
+
+                    case HCI_EVNT_SEND:
+                    case HCI_EVNT_SENDTO:
+                        {
+                            STREAM_TO_UINT32((uint8_t *)pucReceivedParams,SL_RECEIVE_SD_OFFSET ,*(uint32_t *)ret_param);
+                            ret_param = ((uint8_t *)ret_param) + 4;
+                            STREAM_TO_UINT32((uint8_t *)pucReceivedParams,SL_RECEIVE_NUM_BYTES_OFFSET,*(uint32_t *)ret_param);
+                            ret_param = ((uint8_t *)ret_param) + 4;
+
+                            break;
+                        }
+
+                    case HCI_EVNT_SELECT:
+                        {
+                            STREAM_TO_UINT32((uint8_t *)pucReceivedParams,SELECT_STATUS_OFFSET,*(uint32_t *)ret_param);
+                            ret_param = ((uint8_t *)ret_param) + 4;
+                            STREAM_TO_UINT32((uint8_t *)pucReceivedParams,SELECT_READFD_OFFSET,*(uint32_t *)ret_param);
+                            ret_param = ((uint8_t *)ret_param) + 4;
+                            STREAM_TO_UINT32((uint8_t *)pucReceivedParams,SELECT_WRITEFD_OFFSET,*(uint32_t *)ret_param);
+                            ret_param = ((uint8_t *)ret_param) + 4;
+                            STREAM_TO_UINT32((uint8_t *)pucReceivedParams,SELECT_EXFD_OFFSET,*(uint32_t *)ret_param);
+                            break;
+                        }
+
+                    case HCI_CMND_GETSOCKOPT:
+
+                        STREAM_TO_UINT8(received_data, HCI_EVENT_STATUS_OFFSET,((tBsdGetSockOptReturnParams *)ret_param)->iStatus);
+                        //This argument returns in network order
+                        memcpy((uint8_t *)ret_param, pucReceivedParams, 4);
+                        break;
+                    
+                    case HCI_CMND_WLAN_IOCTL_GET_SCAN_RESULTS:
+                        {
+                            /*
+                        char snake[20];
+                        for (int i = 12; i < 30; ++i) {
+                            snake[i-12] = (char) *(pucReceivedParams+i);
+                            
+                            }
+                        snake[19] = '\0';
+                        printf("%s\n", snake);
+                        
+                        printf("handling get scan results\n");
+                        */
+                        uint8_t received_params_copy[53];
+                        memcpy(received_params_copy, pucReceivedParams, 53);
+                        //printf("copied memory\n");
+                        
+                        
+                        STREAM_TO_UINT32((uint8_t *)received_params_copy,GET_SCAN_RESULTS_TABlE_COUNT_OFFSET,*(uint32_t *)ret_param);
+                        ret_param = ((uint8_t *)ret_param) + 4;
+                        STREAM_TO_UINT32((uint8_t *)received_params_copy,GET_SCAN_RESULTS_SCANRESULT_STATUS_OFFSET,*(uint32_t *)ret_param);
+                        ret_param = ((uint8_t *)ret_param) + 4;
+                        STREAM_TO_UINT16((uint8_t *)received_params_copy,GET_SCAN_RESULTS_ISVALID_TO_SSIDLEN_OFFSET,*(uint16_t *)ret_param);
+                        ret_param = ((uint8_t *)ret_param) + 2;
+                        STREAM_TO_UINT16((uint8_t *)received_params_copy,GET_SCAN_RESULTS_FRAME_TIME_OFFSET,*(uint16_t *)ret_param);
+                        ret_param = ((uint8_t *)ret_param) + 2;
+                        
+                        /*
+                        
+                        STREAM_TO_UINT32((uint8_t *)pucReceivedParams,GET_SCAN_RESULTS_TABlE_COUNT_OFFSET,*(uint32_t *)ret_param);
+                        ret_param = ((uint8_t *)ret_param) + 4;
+                        printf("handling get scan results 2");
+                        STREAM_TO_UINT32((uint8_t *)pucReceivedParams,GET_SCAN_RESULTS_SCANRESULT_STATUS_OFFSET,*(uint32_t *)ret_param);
+                        ret_param = ((uint8_t *)ret_param) + 4;
+                        STREAM_TO_UINT16((uint8_t *)pucReceivedParams,GET_SCAN_RESULTS_ISVALID_TO_SSIDLEN_OFFSET,*(uint32_t *)ret_param);
+                        ret_param = ((uint8_t *)ret_param) + 2;
+                        STREAM_TO_UINT16((uint8_t *)pucReceivedParams,GET_SCAN_RESULTS_FRAME_TIME_OFFSET,*(uint32_t *)ret_param);
+                        ret_param = ((uint8_t *)ret_param) + 2;
+                        */
+                        memcpy((uint8_t *)ret_param, (uint8_t *)(pucReceivedParams + GET_SCAN_RESULTS_FRAME_TIME_OFFSET + 2), GET_SCAN_RESULTS_SSID_MAC_LENGTH);
+                        
+                        break;
+                        }
+                        
+                        
+
+                    case HCI_CMND_SIMPLE_LINK_START:
+                        break;
+
+                    case HCI_NETAPP_IPCONFIG:
+
+                        //Read IP address
+                        STREAM_TO_STREAM(RecvParams,RetParams,NETAPP_IPCONFIG_IP_LENGTH);
+                        RecvParams += 4;
+
+                        //Read subnet
+                        STREAM_TO_STREAM(RecvParams,RetParams,NETAPP_IPCONFIG_IP_LENGTH);
+                        RecvParams += 4;
+
+                        //Read default GW
+                        STREAM_TO_STREAM(RecvParams,RetParams,NETAPP_IPCONFIG_IP_LENGTH);
+                        RecvParams += 4;
+
+                        //Read DHCP server
+                        STREAM_TO_STREAM(RecvParams,RetParams,NETAPP_IPCONFIG_IP_LENGTH);
+                        RecvParams += 4;
+
+                        //Read DNS server
+                        STREAM_TO_STREAM(RecvParams,RetParams,NETAPP_IPCONFIG_IP_LENGTH);
+                        RecvParams += 4;
+
+                        //Read Mac address
+                        STREAM_TO_STREAM(RecvParams,RetParams,NETAPP_IPCONFIG_MAC_LENGTH);
+                        RecvParams += 6;
+
+                        //Read SSID
+                        STREAM_TO_STREAM(RecvParams,RetParams,NETAPP_IPCONFIG_SSID_LENGTH);
+                        break;
+
+                    default :
+                        DBG_HCI("UNKNOWN Event Received : 0x%04X ", received_op_code);
+                        break;
+                    }
+
+                }
+                if (received_op_code == _simple_link.get_op_code())
+                {
+                    _simple_link.set_op_code(0);
+                }
+            }
+            else
+            {
+                pucReceivedParams = received_data;
+                STREAM_TO_UINT8((uint8_t *)received_data, HCI_PACKET_ARGSIZE_OFFSET, argument_size);
+
+                STREAM_TO_UINT16((uint8_t *)received_data, HCI_PACKET_LENGTH_OFFSET, length);
+
+                // Data received: note that the only case where from and from length
+                // are not null is in recv from, so fill the args accordingly
+                if (from)
+                {
+                    STREAM_TO_UINT32((uint8_t *)(received_data + HCI_DATA_HEADER_SIZE), BSD_RECV_FROM_FROMLEN_OFFSET, *(uint32_t *)fromlen);
+                    memcpy(from, (received_data + HCI_DATA_HEADER_SIZE + BSD_RECV_FROM_FROM_OFFSET) ,*fromlen);
+                }
+
+                memcpy(ret_param, pucReceivedParams + HCI_DATA_HEADER_SIZE + argument_size, length - argument_size);
+
+                _simple_link.set_pending_data(0);
+            }
+
+            _simple_link.set_data_received_flag(0);
+            _spi.wlan_irq_enable();
+
+            // Since we are going to TX - we need to handle this event after the ResumeSPi since we need interrupts
+            if ((*received_data == HCI_TYPE_EVNT) && (received_op_code == HCI_EVNT_PATCHES_REQ))
+            {
+                hci_unsol_handle_patch_request((uint8_t *)received_data);
+            }
+            if ((_simple_link.get_op_code() == 0) && (_simple_link.get_pending_data() == 0))
+            {
+                return NULL;
+            }
+        }
+    }
+}
+
+int32_t cc3000_event::hci_unsol_event_handler(uint8_t *event_hdr) {
+    uint8_t *data = NULL;
+    int32_t event_type;
+    uint32_t number_of_released_packets;
+    uint32_t number_of_sent_packets;
+
+    STREAM_TO_UINT16(event_hdr, HCI_EVENT_OPCODE_OFFSET,event_type);
+
+    if (event_type & HCI_EVNT_UNSOL_BASE) {
+        switch(event_type) {
+            case HCI_EVNT_DATA_UNSOL_FREE_BUFF:
+            {
+                hci_event_unsol_flowcontrol_handler(event_hdr);
+
+                number_of_released_packets = _simple_link.get_released_packets();
+                number_of_sent_packets = _simple_link.get_sent_packets();
+
+                if (number_of_released_packets == number_of_sent_packets)
+                {
+                    if (_simple_link.get_tx_complete_signal())
+                    {
+                        //tWlanCB func_pointer = (tWlanCB)_simple_link.get_func_pointer(WLAN_CB);
+                        _cc3000.usync_callback(HCI_EVENT_CC3000_CAN_SHUT_DOWN, NULL, 0);
+                    }
+                }
+                return 1;
+            }
+        }
+    }
+
+    if (event_type & HCI_EVNT_WLAN_UNSOL_BASE) {
+        switch(event_type) {
+            case HCI_EVNT_WLAN_KEEPALIVE:
+            case HCI_EVNT_WLAN_UNSOL_CONNECT:
+            case HCI_EVNT_WLAN_UNSOL_DISCONNECT:
+            case HCI_EVNT_WLAN_UNSOL_INIT:
+            case HCI_EVNT_WLAN_ASYNC_SIMPLE_CONFIG_DONE:
+                 _cc3000.usync_callback(event_type, 0, 0);
+                break;
+            case HCI_EVNT_WLAN_UNSOL_DHCP:
+            {
+                uint8_t params[NETAPP_IPCONFIG_MAC_OFFSET + 1]; // extra byte is for the status
+                uint8_t *recParams = params;
+                data = (uint8_t *)(event_hdr) + HCI_EVENT_HEADER_SIZE;
+
+                //Read IP address
+                STREAM_TO_STREAM(data,recParams,NETAPP_IPCONFIG_IP_LENGTH);
+                data += 4;
+                //Read subnet
+                STREAM_TO_STREAM(data,recParams,NETAPP_IPCONFIG_IP_LENGTH);
+                data += 4;
+                //Read default GW
+                STREAM_TO_STREAM(data,recParams,NETAPP_IPCONFIG_IP_LENGTH);
+                data += 4;
+                //Read DHCP server
+                STREAM_TO_STREAM(data,recParams,NETAPP_IPCONFIG_IP_LENGTH);
+                data += 4;
+                //Read DNS server
+                STREAM_TO_STREAM(data,recParams,NETAPP_IPCONFIG_IP_LENGTH);
+                // read the status
+                STREAM_TO_UINT8(event_hdr, HCI_EVENT_STATUS_OFFSET, *recParams);
+
+                _cc3000.usync_callback(event_type, (uint8_t  *)params, sizeof(params));
+
+                break;
+            }
+            case HCI_EVNT_WLAN_ASYNC_PING_REPORT:
+            {
+                netapp_pingreport_args_t params;
+                data = (uint8_t *)(event_hdr) + HCI_EVENT_HEADER_SIZE;
+                STREAM_TO_UINT32(data, NETAPP_PING_PACKETS_SENT_OFFSET, params.packets_sent);
+                STREAM_TO_UINT32(data, NETAPP_PING_PACKETS_RCVD_OFFSET, params.packets_received);
+                STREAM_TO_UINT32(data, NETAPP_PING_MIN_RTT_OFFSET, params.min_round_time);
+                STREAM_TO_UINT32(data, NETAPP_PING_MAX_RTT_OFFSET, params.max_round_time);
+                STREAM_TO_UINT32(data, NETAPP_PING_AVG_RTT_OFFSET, params.avg_round_time);
+
+                _cc3000.usync_callback(event_type, (uint8_t  *)¶ms, sizeof(params));
+                break;
+            }
+            case HCI_EVNT_BSD_TCP_CLOSE_WAIT:
+            {
+                _cc3000.usync_callback(event_type, NULL, 0);
+                break;
+            }
+
+            //'default' case which means "event not supported"
+            default:
+                return (0);
+        }
+        return(1);
+    }
+
+    if ((event_type == HCI_EVNT_SEND) || (event_type == HCI_EVNT_SENDTO) || (event_type == HCI_EVNT_WRITE)) {
+        uint8_t *pArg;
+        int32_t status;
+        pArg = M_BSD_RESP_PARAMS_OFFSET(event_hdr);
+        STREAM_TO_UINT32(pArg, BSD_RSP_PARAMS_STATUS_OFFSET,status);
+        if (ERROR_SOCKET_INACTIVE == status) {
+            // The only synchronous event that can come from SL device in form of
+            // command complete is "Command Complete" on data sent, in case SL device
+            // was unable to transmit
+            int32_t transmit_error  = _simple_link.get_transmit_error();
+            STREAM_TO_UINT8(event_hdr, HCI_EVENT_STATUS_OFFSET, transmit_error);
+            _simple_link.set_transmit_error(transmit_error);
+            update_socket_active_status(M_BSD_RESP_PARAMS_OFFSET(event_hdr));
+            return (1);
+        }
+        else {
+            return (0);
+        }
+    }
+    return(0);
+}
+
+int32_t cc3000_event::hci_unsolicited_event_handler(void) {
+    uint32_t res = 0;
+    uint8_t *received_data;
+
+    if (_simple_link.get_data_received_flag() != 0) {
+        received_data = (_simple_link.get_received_data());
+
+        if (*received_data == HCI_TYPE_EVNT) {
+            // unsolicited event received - finish handling
+            if (hci_unsol_event_handler((uint8_t *)received_data) == 1) {
+                // An unsolicited event was received:
+                // release the buffer and clean the event received
+                _simple_link.set_data_received_flag(0);
+
+                res = 1;
+                _spi.wlan_irq_enable();
+            }
+        }
+    }
+    return res;
+}
+
+void cc3000_event::set_socket_active_status(int32_t sd, int32_t status) {
+    if (M_IS_VALID_SD(sd) && M_IS_VALID_STATUS(status)) {
+        socket_active_status &= ~(1 << sd);      /* clean socket's mask */
+        socket_active_status |= (status << sd); /* set new socket's mask */
+    }
+}
+
+int32_t cc3000_event::hci_event_unsol_flowcontrol_handler(uint8_t *event) {
+    int32_t temp, value;
+    uint16_t i;
+    uint16_t pusNumberOfHandles=0;
+    uint8_t *pReadPayload;
+
+    STREAM_TO_UINT16((uint8_t *)event,HCI_EVENT_HEADER_SIZE,pusNumberOfHandles);
+    pReadPayload = ((uint8_t *)event + HCI_EVENT_HEADER_SIZE + sizeof(pusNumberOfHandles));
+    temp = 0;
+
+    for(i = 0; i < pusNumberOfHandles; i++) {
+        STREAM_TO_UINT16(pReadPayload, FLOW_CONTROL_EVENT_FREE_BUFFS_OFFSET, value);
+        temp += value;
+        pReadPayload += FLOW_CONTROL_EVENT_SIZE;
+    }
+
+    _simple_link.set_number_free_buffers(_simple_link.get_number_free_buffers() + temp);
+    _simple_link.set_number_of_released_packets(_simple_link.get_released_packets() + temp);
+
+    return(ESUCCESS);
+}
+
+int32_t cc3000_event::get_socket_active_status(int32_t sd) {
+    if (M_IS_VALID_SD(sd)) {
+        return (socket_active_status & (1 << sd)) ? SOCKET_STATUS_INACTIVE : SOCKET_STATUS_ACTIVE;
+    } else {
+        return SOCKET_STATUS_INACTIVE;
+    }
+}
+
+void cc3000_event::update_socket_active_status(uint8_t *resp_params) {
+    int32_t status, sd;
+
+    STREAM_TO_UINT32(resp_params, BSD_RSP_PARAMS_SOCKET_OFFSET,sd);
+    STREAM_TO_UINT32(resp_params, BSD_RSP_PARAMS_STATUS_OFFSET,status);
+
+    if (ERROR_SOCKET_INACTIVE == status) {
+        set_socket_active_status(sd, SOCKET_STATUS_INACTIVE);
+    }
+}
+
+void cc3000_event::simplelink_wait_event(uint16_t op_code, void *ret_param) {
+    // In the blocking implementation the control to caller will be returned only
+    // after the end of current transaction
+    _simple_link.set_op_code(op_code);
+    hci_event_handler(ret_param, 0, 0);
+}
+
+void cc3000_event::simplelink_wait_data(uint8_t *pBuf, uint8_t *from, uint8_t *fromlen) {
+    // In the blocking implementation the control to caller will be returned only
+    // after the end of current transaction, i.e. only after data will be received
+    _simple_link.set_pending_data(1);
+    hci_event_handler(pBuf, from, fromlen);
+}
+
+
+} // end of cc3000
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/WifiRobot/cc3000/cc3000_event.h	Tue Dec 09 05:06:37 2014 +0000
@@ -0,0 +1,143 @@
+/*****************************************************************************
+*
+*  C++ interface/implementation created by Martin Kojtal (0xc0170). Thanks to
+*  Jim Carver and Frank Vannieuwkerke for their inital cc3000 mbed port and
+*  provided help.
+*
+*  This version of "host driver" uses CC3000 Host Driver Implementation. Thus
+*  read the following copyright:
+*
+*  Copyright (C) 2011 Texas Instruments Incorporated - http://www.ti.com/
+*
+*  Redistribution and use in source and binary forms, with or without
+*  modification, are permitted provided that the following conditions
+*  are met:
+*
+*    Redistributions of source code must retain the above copyright
+*    notice, this list of conditions and the following disclaimer.
+*
+*    Redistributions in binary form must reproduce the above copyright
+*    notice, this list of conditions and the following disclaimer in the
+*    documentation and/or other materials provided with the
+*    distribution.
+*
+*    Neither the name of Texas Instruments Incorporated nor the names of
+*    its contributors may be used to endorse or promote products derived
+*    from this software without specific prior written permission.
+*
+*  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+*  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+*  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
+*  A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
+*  OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
+*  SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
+*  LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
+*  DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
+*  THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+*  (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
+*  OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+*
+*****************************************************************************/
+#ifndef CC3000_EVENT_H
+#define CC3000_EVENT_H
+
+typedef struct _bsd_read_return_t
+{
+    int32_t             iSocketDescriptor;
+    int32_t             iNumberOfBytes;
+    uint32_t    uiFlags;
+} tBsdReadReturnParams;
+
+typedef struct _bsd_getsockopt_return_t
+{
+    uint8_t ucOptValue[4];
+    uint8_t          iStatus;
+} tBsdGetSockOptReturnParams;
+
+typedef struct _bsd_accept_return_t
+{
+    int32_t             iSocketDescriptor;
+    int32_t             iStatus;
+    sockaddr         tSocketAddress;
+
+} tBsdReturnParams;
+
+typedef struct _bsd_select_return_t
+{
+    int32_t            iStatus;
+    uint32_t           uiRdfd;
+    uint32_t           uiWrfd;
+    uint32_t           uiExfd;
+} tBsdSelectRecvParams;
+
+typedef struct _bsd_gethostbyname_return_t
+{
+    int32_t  retVal;
+    int32_t  outputAddress;
+} tBsdGethostbynameParams;
+
+#define FLOW_CONTROL_EVENT_HANDLE_OFFSET        (0)
+#define FLOW_CONTROL_EVENT_BLOCK_MODE_OFFSET    (1)
+#define FLOW_CONTROL_EVENT_FREE_BUFFS_OFFSET    (2)
+#define FLOW_CONTROL_EVENT_SIZE                 (4)
+
+#define BSD_RSP_PARAMS_SOCKET_OFFSET            (0)
+#define BSD_RSP_PARAMS_STATUS_OFFSET            (4)
+
+#define GET_HOST_BY_NAME_RETVAL_OFFSET          (0)
+#define GET_HOST_BY_NAME_ADDR_OFFSET            (4)
+
+#define ACCEPT_SD_OFFSET                        (0)
+#define ACCEPT_RETURN_STATUS_OFFSET             (4)
+#define ACCEPT_ADDRESS__OFFSET                  (8)
+
+#define SL_RECEIVE_SD_OFFSET                    (0)
+#define SL_RECEIVE_NUM_BYTES_OFFSET             (4)
+#define SL_RECEIVE__FLAGS__OFFSET               (8)
+
+
+#define SELECT_STATUS_OFFSET                    (0)
+#define SELECT_READFD_OFFSET                    (4)
+#define SELECT_WRITEFD_OFFSET                   (8)
+#define SELECT_EXFD_OFFSET                      (12)
+
+
+#define NETAPP_IPCONFIG_IP_OFFSET               (0)
+#define NETAPP_IPCONFIG_SUBNET_OFFSET           (4)
+#define NETAPP_IPCONFIG_GW_OFFSET               (8)
+#define NETAPP_IPCONFIG_DHCP_OFFSET             (12)
+#define NETAPP_IPCONFIG_DNS_OFFSET              (16)
+#define NETAPP_IPCONFIG_MAC_OFFSET              (20)
+#define NETAPP_IPCONFIG_SSID_OFFSET             (26)
+
+#define NETAPP_IPCONFIG_IP_LENGTH               (4)
+#define NETAPP_IPCONFIG_MAC_LENGTH              (6)
+#define NETAPP_IPCONFIG_SSID_LENGTH             (32)
+
+
+#define NETAPP_PING_PACKETS_SENT_OFFSET         (0)
+#define NETAPP_PING_PACKETS_RCVD_OFFSET         (4)
+#define NETAPP_PING_MIN_RTT_OFFSET              (8)
+#define NETAPP_PING_MAX_RTT_OFFSET              (12)
+#define NETAPP_PING_AVG_RTT_OFFSET              (16)
+
+#define GET_SCAN_RESULTS_TABlE_COUNT_OFFSET              (0)
+#define GET_SCAN_RESULTS_SCANRESULT_STATUS_OFFSET        (4)
+#define GET_SCAN_RESULTS_ISVALID_TO_SSIDLEN_OFFSET       (8)
+#define GET_SCAN_RESULTS_FRAME_TIME_OFFSET               (10)
+#define GET_SCAN_RESULTS_SSID_MAC_LENGTH                 (38)
+
+#define M_BSD_RESP_PARAMS_OFFSET(hci_event_hdr)((uint8_t *)(hci_event_hdr) + HCI_EVENT_HEADER_SIZE)
+
+#define SOCKET_STATUS_ACTIVE       0
+#define SOCKET_STATUS_INACTIVE     1
+/* Init socket_active_status = 'all ones': init all sockets with SOCKET_STATUS_INACTIVE.
+   Will be changed by 'set_socket_active_status' upon 'connect' and 'accept' calls */
+#define SOCKET_STATUS_INIT_VAL  0xFFFF
+#define M_IS_VALID_SD(sd) ((0 <= (sd)) && ((sd) <= 7))
+#define M_IS_VALID_STATUS(status) (((status) == SOCKET_STATUS_ACTIVE)||((status) == SOCKET_STATUS_INACTIVE))
+
+#define BSD_RECV_FROM_FROMLEN_OFFSET    (4)
+#define BSD_RECV_FROM_FROM_OFFSET       (16)
+
+#endif
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/WifiRobot/cc3000/cc3000_hci.cpp	Tue Dec 09 05:06:37 2014 +0000
@@ -0,0 +1,143 @@
+/*****************************************************************************
+*
+*  C++ interface/implementation created by Martin Kojtal (0xc0170). Thanks to
+*  Jim Carver and Frank Vannieuwkerke for their inital cc3000 mbed port and
+*  provided help.
+*
+*  This version of "host driver" uses CC3000 Host Driver Implementation. Thus
+*  read the following copyright:
+*
+*  Copyright (C) 2011 Texas Instruments Incorporated - http://www.ti.com/
+*
+*  Redistribution and use in source and binary forms, with or without
+*  modification, are permitted provided that the following conditions
+*  are met:
+*
+*    Redistributions of source code must retain the above copyright
+*    notice, this list of conditions and the following disclaimer.
+*
+*    Redistributions in binary form must reproduce the above copyright
+*    notice, this list of conditions and the following disclaimer in the
+*    documentation and/or other materials provided with the
+*    distribution.
+*
+*    Neither the name of Texas Instruments Incorporated nor the names of
+*    its contributors may be used to endorse or promote products derived
+*    from this software without specific prior written permission.
+*
+*  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+*  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+*  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
+*  A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
+*  OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
+*  SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
+*  LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
+*  DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
+*  THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+*  (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
+*  OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+*
+*****************************************************************************/
+#include "cc3000.h"
+
+namespace mbed_cc3000 {
+
+cc3000_hci::cc3000_hci(cc3000_spi &spi) : _spi(spi) {
+
+}
+
+cc3000_hci::~cc3000_hci() {
+
+}
+
+uint16_t  cc3000_hci::command_send(uint16_t op_code, uint8_t *buffer, uint8_t length) {
+    uint8_t *stream;
+
+    DBG_HCI_CMD("Command Sent : 0x%04X", op_code);
+
+    stream = (buffer + SPI_HEADER_SIZE);
+
+    UINT8_TO_STREAM(stream, HCI_TYPE_CMND);
+    stream = UINT16_TO_STREAM(stream, op_code);
+    UINT8_TO_STREAM(stream, length);
+    //Update the opcode of the event we will be waiting for
+    _spi.write(buffer, length + SIMPLE_LINK_HCI_CMND_HEADER_SIZE);
+    return(0);
+}
+
+uint32_t  cc3000_hci::data_send(uint8_t op_code, uint8_t *args, uint16_t arg_length,
+                    uint16_t data_length, const uint8_t *tail, uint16_t tail_length) {
+    uint8_t *stream;
+
+    stream = ((args) + SPI_HEADER_SIZE);
+
+    UINT8_TO_STREAM(stream, HCI_TYPE_DATA);
+    UINT8_TO_STREAM(stream, op_code);
+    UINT8_TO_STREAM(stream, arg_length);
+    stream = UINT16_TO_STREAM(stream, arg_length + data_length + tail_length);
+
+    // Send the packet
+    _spi.write(args, SIMPLE_LINK_HCI_DATA_HEADER_SIZE + arg_length + data_length + tail_length);
+
+    return 0;
+}
+
+void  cc3000_hci::data_command_send(uint16_t op_code, uint8_t *buffer, uint8_t arg_length, uint16_t data_length) {
+    uint8_t *stream = (buffer + SPI_HEADER_SIZE);
+
+    UINT8_TO_STREAM(stream, HCI_TYPE_DATA);
+    UINT8_TO_STREAM(stream, op_code);
+    UINT8_TO_STREAM(stream, arg_length);
+    stream = UINT16_TO_STREAM(stream, arg_length + data_length);
+
+    // Send the command
+    _spi.write(buffer, arg_length + data_length + SIMPLE_LINK_HCI_DATA_CMND_HEADER_SIZE);
+
+    return;
+}
+
+void  cc3000_hci::patch_send(uint8_t op_code, uint8_t *buffer, uint8_t *patch, uint16_t data_length) {
+    uint16_t usTransLength;
+    uint8_t *stream = (buffer + SPI_HEADER_SIZE);
+    UINT8_TO_STREAM(stream, HCI_TYPE_PATCH);
+    UINT8_TO_STREAM(stream, op_code);
+    stream = UINT16_TO_STREAM(stream, data_length + SIMPLE_LINK_HCI_PATCH_HEADER_SIZE);
+    if (data_length <= SL_PATCH_PORTION_SIZE) {
+        UINT16_TO_STREAM(stream, data_length);
+        stream = UINT16_TO_STREAM(stream, data_length);
+        memcpy((buffer + SPI_HEADER_SIZE) + HCI_PATCH_HEADER_SIZE, patch, data_length);
+        // Update the opcode of the event we will be waiting for
+        _spi.write(buffer, data_length + HCI_PATCH_HEADER_SIZE);
+    } else {
+
+        usTransLength = (data_length/SL_PATCH_PORTION_SIZE);
+        UINT16_TO_STREAM(stream, data_length + SIMPLE_LINK_HCI_PATCH_HEADER_SIZE + usTransLength*SIMPLE_LINK_HCI_PATCH_HEADER_SIZE);
+        stream = UINT16_TO_STREAM(stream, SL_PATCH_PORTION_SIZE);
+        memcpy(buffer + SPI_HEADER_SIZE + HCI_PATCH_HEADER_SIZE, patch, SL_PATCH_PORTION_SIZE);
+        data_length -= SL_PATCH_PORTION_SIZE;
+        patch += SL_PATCH_PORTION_SIZE;
+
+        // Update the opcode of the event we will be waiting for
+        _spi.write(buffer, SL_PATCH_PORTION_SIZE + HCI_PATCH_HEADER_SIZE);
+
+        stream = (buffer + SPI_HEADER_SIZE);
+        while (data_length) {
+            if (data_length <= SL_PATCH_PORTION_SIZE) {
+                usTransLength = data_length;
+                data_length = 0;
+            } else {
+                usTransLength = SL_PATCH_PORTION_SIZE;
+                data_length -= usTransLength;
+            }
+
+            *(uint16_t *)stream = usTransLength;
+            memcpy(stream + SIMPLE_LINK_HCI_PATCH_HEADER_SIZE, patch, usTransLength);
+            patch += usTransLength;
+
+            // Update the opcode of the event we will be waiting for
+            _spi.write((unsigned char *)stream, usTransLength + sizeof(usTransLength));
+        }
+    }
+}
+
+} // mbed_cc3000 namespace
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/WifiRobot/cc3000/cc3000_netapp.cpp	Tue Dec 09 05:06:37 2014 +0000
@@ -0,0 +1,199 @@
+/*****************************************************************************
+*
+*  C++ interface/implementation created by Martin Kojtal (0xc0170). Thanks to
+*  Jim Carver and Frank Vannieuwkerke for their inital cc3000 mbed port and
+*  provided help.
+*
+*  This version of "host driver" uses CC3000 Host Driver Implementation. Thus
+*  read the following copyright:
+*
+*  Copyright (C) 2011 Texas Instruments Incorporated - http://www.ti.com/
+*
+*  Redistribution and use in source and binary forms, with or without
+*  modification, are permitted provided that the following conditions
+*  are met:
+*
+*    Redistributions of source code must retain the above copyright
+*    notice, this list of conditions and the following disclaimer.
+*
+*    Redistributions in binary form must reproduce the above copyright
+*    notice, this list of conditions and the following disclaimer in the
+*    documentation and/or other materials provided with the
+*    distribution.
+*
+*    Neither the name of Texas Instruments Incorporated nor the names of
+*    its contributors may be used to endorse or promote products derived
+*    from this software without specific prior written permission.
+*
+*  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+*  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+*  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
+*  A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
+*  OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
+*  SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
+*  LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
+*  DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
+*  THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+*  (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
+*  OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+*
+*****************************************************************************/
+#include "cc3000.h"
+#include "cc3000_netapp.h"
+
+namespace mbed_cc3000 {
+
+cc3000_netapp::cc3000_netapp(cc3000_simple_link &simple_link, cc3000_nvmem &nvmem, cc3000_hci &hci , cc3000_event &event) :
+    _simple_link(simple_link), _nvmem(nvmem), _hci(hci), _event(event) {
+
+}
+
+cc3000_netapp::~cc3000_netapp() {
+
+}
+
+int32_t cc3000_netapp::config_mac_adrress(uint8_t * mac) {
+    return  _nvmem.set_mac_address(mac);
+}
+
+int32_t cc3000_netapp::dhcp(uint32_t *ip, uint32_t *subnet_mask,uint32_t *default_gateway, uint32_t *dns_server) {
+    int8_t scRet;
+    uint8_t *ptr;
+    uint8_t *args;
+
+    scRet = EFAIL;
+    ptr = _simple_link.get_transmit_buffer();
+    args = (ptr + HEADERS_SIZE_CMD);
+
+    // Fill in temporary command buffer
+    ARRAY_TO_STREAM(args,ip,4);
+    ARRAY_TO_STREAM(args,subnet_mask,4);
+    ARRAY_TO_STREAM(args,default_gateway,4);
+    args = UINT32_TO_STREAM(args, 0);
+    ARRAY_TO_STREAM(args,dns_server,4);
+
+    // Initiate a HCI command
+    _hci.command_send(HCI_NETAPP_DHCP, ptr, NETAPP_DHCP_PARAMS_LEN);
+
+    // Wait for command complete event
+    _event.simplelink_wait_event(HCI_NETAPP_DHCP, &scRet);
+
+    return scRet;
+}
+
+#ifndef CC3000_TINY_DRIVER
+void cc3000_netapp::ipconfig( tNetappIpconfigRetArgs * ipconfig ) {
+    uint8_t *ptr;
+
+    ptr = _simple_link.get_transmit_buffer();
+
+    // Initiate a HCI command
+    _hci.command_send(HCI_NETAPP_IPCONFIG, ptr, 0);
+
+    // Wait for command complete event
+    _event.simplelink_wait_event(HCI_NETAPP_IPCONFIG, ipconfig );
+}
+
+
+int32_t cc3000_netapp::timeout_values(uint32_t *dhcp, uint32_t *arp,uint32_t *keep_alive, uint32_t *inactivity) {
+    int8_t scRet;
+    uint8_t *ptr;
+    uint8_t *args;
+
+    scRet = EFAIL;
+    ptr = _simple_link.get_transmit_buffer();
+    args = (ptr + HEADERS_SIZE_CMD);
+
+    // Set minimal values of timers
+    MIN_TIMER_SET(*dhcp)
+    MIN_TIMER_SET(*arp)
+    MIN_TIMER_SET(*keep_alive)
+    MIN_TIMER_SET(*inactivity)
+
+    // Fill in temporary command buffer
+    args = UINT32_TO_STREAM(args, *dhcp);
+    args = UINT32_TO_STREAM(args, *arp);
+    args = UINT32_TO_STREAM(args, *keep_alive);
+    args = UINT32_TO_STREAM(args, *inactivity);
+
+    // Initiate a HCI command
+    _hci.command_send(HCI_NETAPP_SET_TIMERS, ptr, NETAPP_SET_TIMER_PARAMS_LEN);
+
+    // Wait for command complete event
+    _event.simplelink_wait_event(HCI_NETAPP_SET_TIMERS, &scRet);
+
+    return scRet;
+}
+
+int32_t cc3000_netapp::ping_send(uint32_t *ip, uint32_t ping_attempts, uint32_t ping_size, uint32_t ping_timeout) {
+    int8_t scRet;
+    uint8_t *ptr, *args;
+
+    scRet = EFAIL;
+    ptr = _simple_link.get_transmit_buffer();
+    args = (ptr + HEADERS_SIZE_CMD);
+
+    // Fill in temporary command buffer
+    args = UINT32_TO_STREAM(args, *ip);
+    args = UINT32_TO_STREAM(args, ping_attempts);
+    args = UINT32_TO_STREAM(args, ping_size);
+    args = UINT32_TO_STREAM(args, ping_timeout);
+
+    // Initiate a HCI command
+    _hci.command_send(HCI_NETAPP_PING_SEND, ptr, NETAPP_PING_SEND_PARAMS_LEN);
+
+    // Wait for command complete event
+    _event.simplelink_wait_event(HCI_NETAPP_PING_SEND, &scRet);
+
+    return scRet;
+}
+
+void cc3000_netapp::ping_report() {
+    uint8_t *ptr;
+    int8_t scRet;
+    ptr = _simple_link.get_transmit_buffer();
+
+
+    scRet = EFAIL;
+
+    // Initiate a HCI command
+    _hci.command_send(HCI_NETAPP_PING_REPORT, ptr, 0);
+
+    // Wait for command complete event
+    _event.simplelink_wait_event(HCI_NETAPP_PING_REPORT, &scRet);
+}
+
+int32_t cc3000_netapp::ping_stop() {
+    int8_t scRet;
+    uint8_t *ptr;
+
+    scRet = EFAIL;
+    ptr = _simple_link.get_transmit_buffer();
+
+    // Initiate a HCI command
+    _hci.command_send(HCI_NETAPP_PING_STOP, ptr, 0);
+
+    // Wait for command complete event
+    _event.simplelink_wait_event(HCI_NETAPP_PING_STOP, &scRet);
+
+    return scRet;
+}
+
+int32_t cc3000_netapp::arp_flush() {
+    int8_t scRet;
+    uint8_t *ptr;
+
+    scRet = EFAIL;
+    ptr = _simple_link.get_transmit_buffer();
+
+    // Initiate a HCI command
+    _hci.command_send(HCI_NETAPP_ARP_FLUSH, ptr, 0);
+
+    // Wait for command complete event
+    _event.simplelink_wait_event(HCI_NETAPP_ARP_FLUSH, &scRet);
+
+    return scRet;
+}
+#endif
+
+} // mbed_cc3000
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/WifiRobot/cc3000/cc3000_netapp.h	Tue Dec 09 05:06:37 2014 +0000
@@ -0,0 +1,88 @@
+/*****************************************************************************
+*
+*  C++ interface/implementation created by Martin Kojtal (0xc0170). Thanks to
+*  Jim Carver and Frank Vannieuwkerke for their inital cc3000 mbed port and
+*  provided help.
+*
+*  This version of "host driver" uses CC3000 Host Driver Implementation. Thus
+*  read the following copyright:
+*
+*  Copyright (C) 2011 Texas Instruments Incorporated - http://www.ti.com/
+*
+*  Redistribution and use in source and binary forms, with or without
+*  modification, are permitted provided that the following conditions
+*  are met:
+*
+*    Redistributions of source code must retain the above copyright
+*    notice, this list of conditions and the following disclaimer.
+*
+*    Redistributions in binary form must reproduce the above copyright
+*    notice, this list of conditions and the following disclaimer in the
+*    documentation and/or other materials provided with the
+*    distribution.
+*
+*    Neither the name of Texas Instruments Incorporated nor the names of
+*    its contributors may be used to endorse or promote products derived
+*    from this software without specific prior written permission.
+*
+*  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+*  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+*  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
+*  A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
+*  OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
+*  SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
+*  LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
+*  DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
+*  THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+*  (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
+*  OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+*
+*****************************************************************************/
+#ifndef CC3000_NETAPP_H
+#define CC3000_NETAPP_H
+
+#define MIN_TIMER_VAL_SECONDS      20
+#define MIN_TIMER_SET(t)    if ((0 != t) && (t < MIN_TIMER_VAL_SECONDS)) \
+                            { \
+                                t = MIN_TIMER_VAL_SECONDS; \
+                            }
+
+
+#define NETAPP_DHCP_PARAMS_LEN                 (20)
+#define NETAPP_SET_TIMER_PARAMS_LEN            (20)
+#define NETAPP_SET_DEBUG_LEVEL_PARAMS_LEN      (4)
+#define NETAPP_PING_SEND_PARAMS_LEN            (16)
+
+
+typedef struct _netapp_dhcp_ret_args_t
+{
+    uint8_t aucIP[4];
+    uint8_t aucSubnetMask[4];
+    uint8_t aucDefaultGateway[4];
+    uint8_t aucDHCPServer[4];
+    uint8_t aucDNSServer[4];
+}tNetappDhcpParams;
+
+typedef struct _netapp_ipconfig_ret_args_t
+{
+    uint8_t aucIP[4];
+    uint8_t aucSubnetMask[4];
+    uint8_t aucDefaultGateway[4];
+    uint8_t aucDHCPServer[4];
+    uint8_t aucDNSServer[4];
+    uint8_t uaMacAddr[6];
+    uint8_t uaSSID[32];
+}tNetappIpconfigRetArgs;
+
+
+/*Ping send report parameters*/
+typedef struct _netapp_pingreport_args
+{
+    uint32_t packets_sent;
+    uint32_t packets_received;
+    uint32_t min_round_time;
+    uint32_t max_round_time;
+    uint32_t avg_round_time;
+} netapp_pingreport_args_t;
+
+#endif
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/WifiRobot/cc3000/cc3000_nvmem.cpp	Tue Dec 09 05:06:37 2014 +0000
@@ -0,0 +1,182 @@
+/*****************************************************************************
+*
+*  C++ interface/implementation created by Martin Kojtal (0xc0170). Thanks to
+*  Jim Carver and Frank Vannieuwkerke for their inital cc3000 mbed port and
+*  provided help.
+*
+*  This version of "host driver" uses CC3000 Host Driver Implementation. Thus
+*  read the following copyright:
+*
+*  Copyright (C) 2011 Texas Instruments Incorporated - http://www.ti.com/
+*
+*  Redistribution and use in source and binary forms, with or without
+*  modification, are permitted provided that the following conditions
+*  are met:
+*
+*    Redistributions of source code must retain the above copyright
+*    notice, this list of conditions and the following disclaimer.
+*
+*    Redistributions in binary form must reproduce the above copyright
+*    notice, this list of conditions and the following disclaimer in the
+*    documentation and/or other materials provided with the
+*    distribution.
+*
+*    Neither the name of Texas Instruments Incorporated nor the names of
+*    its contributors may be used to endorse or promote products derived
+*    from this software without specific prior written permission.
+*
+*  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+*  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+*  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
+*  A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
+*  OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
+*  SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
+*  LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
+*  DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
+*  THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+*  (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
+*  OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+*
+*****************************************************************************/
+#include "cc3000.h"
+#include "cc3000_nvmem.h"
+#include "cc3000_common.h"
+
+namespace mbed_cc3000 {
+
+cc3000_nvmem::cc3000_nvmem(cc3000_hci &hci, cc3000_event &event, cc3000_simple_link &simple_link)
+        : _hci(hci), _event(event), _simple_link(simple_link) {
+
+}
+
+cc3000_nvmem::~cc3000_nvmem() {
+
+}
+
+int32_t  cc3000_nvmem::read(uint32_t file_id, uint32_t length, uint32_t offset, uint8_t *buff) {
+    uint8_t ucStatus = 0xFF;
+    uint8_t *ptr;
+    uint8_t *args;
+
+    ptr = _simple_link.get_transmit_buffer();
+    args = (ptr + HEADERS_SIZE_CMD);
+    // Fill in HCI packet structure
+    args = UINT32_TO_STREAM(args, file_id);
+    args = UINT32_TO_STREAM(args, length);
+    args = UINT32_TO_STREAM(args, offset);
+
+    // Initiate HCI command
+    _hci.command_send(HCI_CMND_NVMEM_READ, ptr, NVMEM_READ_PARAMS_LEN);
+    _event.simplelink_wait_event(HCI_CMND_NVMEM_READ, &ucStatus);
+
+    // If data is present, read it even when an error is returned.
+    // Note: It is the users responsibility to ignore the data when an error is returned.
+    // Wait for the data in a synchronous way.
+    //  We assume the buffer is large enough to also store nvmem parameters.
+    _event.simplelink_wait_data(buff, 0, 0);
+
+    return(ucStatus);
+}
+
+int32_t  cc3000_nvmem::write(uint32_t file_id, uint32_t length, uint32_t entry_offset, uint8_t *buff) {
+    int32_t iRes;
+    uint8_t *ptr;
+    uint8_t *args;
+
+    iRes = EFAIL;
+
+    ptr = _simple_link.get_transmit_buffer();
+    args = (ptr + SPI_HEADER_SIZE + HCI_DATA_CMD_HEADER_SIZE);
+
+    // Fill in HCI packet structure
+    args = UINT32_TO_STREAM(args, file_id);
+    args = UINT32_TO_STREAM(args, 12);
+    args = UINT32_TO_STREAM(args, length);
+    args = UINT32_TO_STREAM(args, entry_offset);
+
+    memcpy((ptr + SPI_HEADER_SIZE + HCI_DATA_CMD_HEADER_SIZE +
+                    NVMEM_WRITE_PARAMS_LEN),buff,length);
+
+    // Initiate a HCI command on the data channel
+    _hci.data_command_send(HCI_CMND_NVMEM_WRITE, ptr, NVMEM_WRITE_PARAMS_LEN, length);
+
+    _event.simplelink_wait_event(HCI_EVNT_NVMEM_WRITE, &iRes);
+
+    return(iRes);
+}
+
+uint8_t  cc3000_nvmem::set_mac_address(uint8_t *mac) {
+    return  write(NVMEM_MAC_FILEID, MAC_ADDR_LEN, 0, mac);
+}
+
+uint8_t  cc3000_nvmem::get_mac_address(uint8_t *mac) {
+    return  read(NVMEM_MAC_FILEID, MAC_ADDR_LEN, 0, mac);
+}
+
+uint8_t  cc3000_nvmem::write_patch(uint32_t file_id, uint32_t length, const uint8_t *data) {
+    uint8_t     status = 0;
+    uint16_t    offset = 0;
+    uint8_t*      spDataPtr = (uint8_t*)data;
+
+    while ((status == 0) && (length >= SP_PORTION_SIZE)) {
+        status = write(file_id, SP_PORTION_SIZE, offset, spDataPtr);
+        offset += SP_PORTION_SIZE;
+        length -= SP_PORTION_SIZE;
+        spDataPtr += SP_PORTION_SIZE;
+    }
+
+    if (status !=0) {
+        // NVMEM error occurred
+        return status;
+    }
+
+    if (length != 0) {
+        // If length MOD 512 is nonzero, write the remaining bytes.
+        status = write(file_id, length, offset, spDataPtr);
+    }
+
+    return status;
+}
+
+int32_t  cc3000_nvmem::create_entry(uint32_t file_id, uint32_t new_len) {
+    uint8_t *ptr;
+    uint8_t *args;
+    uint16_t retval;
+
+    ptr = _simple_link.get_transmit_buffer();
+    args = (ptr + HEADERS_SIZE_CMD);
+
+    // Fill in HCI packet structure
+    args = UINT32_TO_STREAM(args, file_id);
+    args = UINT32_TO_STREAM(args, new_len);
+
+    // Initiate a HCI command
+    _hci.command_send(HCI_CMND_NVMEM_CREATE_ENTRY,ptr, NVMEM_CREATE_PARAMS_LEN);
+
+    _event.simplelink_wait_event(HCI_CMND_NVMEM_CREATE_ENTRY, &retval);
+
+    return(retval);
+}
+
+#ifndef CC3000_TINY_DRIVER
+uint8_t cc3000_nvmem::read_sp_version(uint8_t* patch_ver) {
+    uint8_t *ptr;
+    // 1st byte is the status and the rest is the SP version
+    uint8_t retBuf[5];
+
+    ptr = _simple_link.get_transmit_buffer();
+
+   // Initiate a HCI command, no args are required
+    _hci.command_send(HCI_CMND_READ_SP_VERSION, ptr, 0);
+    _event.simplelink_wait_event(HCI_CMND_READ_SP_VERSION, retBuf);
+
+    // package ID
+    *patch_ver = retBuf[3];
+    // package build number
+    *(patch_ver+1) = retBuf[4];
+
+    return(retBuf[0]);
+}
+#endif
+
+} // mbed_cc3000 namespace
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/WifiRobot/cc3000/cc3000_nvmem.h Tue Dec 09 05:06:37 2014 +0000 @@ -0,0 +1,100 @@ +/***************************************************************************** +* +* C++ interface/implementation created by Martin Kojtal (0xc0170). Thanks to +* Jim Carver and Frank Vannieuwkerke for their inital cc3000 mbed port and +* provided help. +* +* This version of "host driver" uses CC3000 Host Driver Implementation. Thus +* read the following copyright: +* +* Copyright (C) 2011 Texas Instruments Incorporated - http://www.ti.com/ +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* +* Redistributions in binary form must reproduce the above copyright +* notice, this list of conditions and the following disclaimer in the +* documentation and/or other materials provided with the +* distribution. +* +* Neither the name of Texas Instruments Incorporated nor the names of +* its contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR +* A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +* OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +* SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT +* LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, +* DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY +* THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +* +*****************************************************************************/ +#ifndef CC3000_NVMEM_H +#define CC3000_NVMEM_H + +#define NVMEM_READ_PARAMS_LEN (12) +#define NVMEM_CREATE_PARAMS_LEN (8) +#define NVMEM_WRITE_PARAMS_LEN (16) + + +/**************************************************************************** +** +** Definitions for File IDs +** +****************************************************************************/ +/* --------------------------------------------------------- EEPROM FAT table --------------------------------------------------------- + + File ID Offset File Size Used Size Parameter + # ID address (bytes) (bytes) + -------------------------------------------------------------------------------------------------------------------------------------- + 0 NVMEM_NVS_FILEID 0x50 0x1A0 0x1A RF Calibration results table(generated automatically by TX Bip) + 1 NVMEM_NVS_SHADOW_FILEID 0x1F0 0x1A0 0x1A NVS Shadow + 2 NVMEM_WLAN_CONFIG_FILEID 0x390 0x1000 0x64 WLAN configuration + 3 NVMEM_WLAN_CONFIG_SHADOW_FILEID 0x1390 0x1000 0x64 WLAN configuration shadow + 4 NVMEM_WLAN_DRIVER_SP_FILEID 0x2390 0x2000 variable WLAN Driver ROM Patches + 5 NVMEM_WLAN_FW_SP_FILEID 0x4390 0x2000 variable WLAN FW Patches + 6 NVMEM_MAC_FILEID 0x6390 0x10 0x10 6 bytes of MAC address + 7 NVMEM_FRONTEND_VARS_FILEID 0x63A0 0x10 0x10 Frontend Vars + 8 NVMEM_IP_CONFIG_FILEID 0x63B0 0x40 0x40 IP configuration + 9 NVMEM_IP_CONFIG_SHADOW_FILEID 0x63F0 0x40 0x40 IP configuration shadow +10 NVMEM_BOOTLOADER_SP_FILEID 0x6430 0x400 variable Bootloader Patches +11 NVMEM_RM_FILEID 0x6830 0x200 0x7F Radio parameters +12 NVMEM_AES128_KEY_FILEID 0x6A30 0x10 0x10 AES128 key file +13 NVMEM_SHARED_MEM_FILEID 0x6A40 0x50 0x44 Host-CC3000 shared memory file +14 NVMEM_USER_FILE_1_FILEID 0x6A90 variable variable 1st user file +15 NVMEM_USER_FILE_2_FILEID variable variable variable 2nd user file +*/ +/* NVMEM file ID - system files*/ +#define NVMEM_NVS_FILEID (0) +#define NVMEM_NVS_SHADOW_FILEID (1) +#define NVMEM_WLAN_CONFIG_FILEID (2) +#define NVMEM_WLAN_CONFIG_SHADOW_FILEID (3) +#define NVMEM_WLAN_DRIVER_SP_FILEID (4) +#define NVMEM_WLAN_FW_SP_FILEID (5) +#define NVMEM_MAC_FILEID (6) +#define NVMEM_FRONTEND_VARS_FILEID (7) +#define NVMEM_IP_CONFIG_FILEID (8) +#define NVMEM_IP_CONFIG_SHADOW_FILEID (9) +#define NVMEM_BOOTLOADER_SP_FILEID (10) +#define NVMEM_RM_FILEID (11) + +/* NVMEM file ID - user files*/ +#define NVMEM_AES128_KEY_FILEID (12) +#define NVMEM_SHARED_MEM_FILEID (13) +#define NVMEM_USER_FILE_1_FILEID (14) +#define NVMEM_USER_FILE_2_FILEID (15) + +/* max entry in order to invalid nvmem */ +#define NVMEM_MAX_ENTRY (16) + + +#endif
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/WifiRobot/cc3000/cc3000_security.cpp	Tue Dec 09 05:06:37 2014 +0000
@@ -0,0 +1,381 @@
+/*****************************************************************************
+*
+*  C++ interface/implementation created by Martin Kojtal (0xc0170). Thanks to
+*  Jim Carver and Frank Vannieuwkerke for their inital cc3000 mbed port and
+*  provided help.
+*
+*  This version of "host driver" uses CC3000 Host Driver Implementation. Thus
+*  read the following copyright:
+*
+*  Copyright (C) 2011 Texas Instruments Incorporated - http://www.ti.com/
+*
+*  Redistribution and use in source and binary forms, with or without
+*  modification, are permitted provided that the following conditions
+*  are met:
+*
+*    Redistributions of source code must retain the above copyright
+*    notice, this list of conditions and the following disclaimer.
+*
+*    Redistributions in binary form must reproduce the above copyright
+*    notice, this list of conditions and the following disclaimer in the
+*    documentation and/or other materials provided with the
+*    distribution.
+*
+*    Neither the name of Texas Instruments Incorporated nor the names of
+*    its contributors may be used to endorse or promote products derived
+*    from this software without specific prior written permission.
+*
+*  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+*  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+*  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
+*  A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
+*  OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
+*  SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
+*  LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
+*  DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
+*  THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+*  (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
+*  OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+*
+*****************************************************************************/
+#include "cc3000.h"
+
+namespace mbed_cc3000 {
+
+#ifndef CC3000_UNENCRYPTED_SMART_CONFIG
+
+// forward sbox
+static const uint8_t sbox[256] =   {
+//0     1    2      3     4    5     6     7      8    9     A      B    C     D     E     F
+0x63, 0x7c, 0x77, 0x7b, 0xf2, 0x6b, 0x6f, 0xc5, 0x30, 0x01, 0x67, 0x2b, 0xfe, 0xd7, 0xab, 0x76, //0
+0xca, 0x82, 0xc9, 0x7d, 0xfa, 0x59, 0x47, 0xf0, 0xad, 0xd4, 0xa2, 0xaf, 0x9c, 0xa4, 0x72, 0xc0, //1
+0xb7, 0xfd, 0x93, 0x26, 0x36, 0x3f, 0xf7, 0xcc, 0x34, 0xa5, 0xe5, 0xf1, 0x71, 0xd8, 0x31, 0x15, //2
+0x04, 0xc7, 0x23, 0xc3, 0x18, 0x96, 0x05, 0x9a, 0x07, 0x12, 0x80, 0xe2, 0xeb, 0x27, 0xb2, 0x75, //3
+0x09, 0x83, 0x2c, 0x1a, 0x1b, 0x6e, 0x5a, 0xa0, 0x52, 0x3b, 0xd6, 0xb3, 0x29, 0xe3, 0x2f, 0x84, //4
+0x53, 0xd1, 0x00, 0xed, 0x20, 0xfc, 0xb1, 0x5b, 0x6a, 0xcb, 0xbe, 0x39, 0x4a, 0x4c, 0x58, 0xcf, //5
+0xd0, 0xef, 0xaa, 0xfb, 0x43, 0x4d, 0x33, 0x85, 0x45, 0xf9, 0x02, 0x7f, 0x50, 0x3c, 0x9f, 0xa8, //6
+0x51, 0xa3, 0x40, 0x8f, 0x92, 0x9d, 0x38, 0xf5, 0xbc, 0xb6, 0xda, 0x21, 0x10, 0xff, 0xf3, 0xd2, //7
+0xcd, 0x0c, 0x13, 0xec, 0x5f, 0x97, 0x44, 0x17, 0xc4, 0xa7, 0x7e, 0x3d, 0x64, 0x5d, 0x19, 0x73, //8
+0x60, 0x81, 0x4f, 0xdc, 0x22, 0x2a, 0x90, 0x88, 0x46, 0xee, 0xb8, 0x14, 0xde, 0x5e, 0x0b, 0xdb, //9
+0xe0, 0x32, 0x3a, 0x0a, 0x49, 0x06, 0x24, 0x5c, 0xc2, 0xd3, 0xac, 0x62, 0x91, 0x95, 0xe4, 0x79, //A
+0xe7, 0xc8, 0x37, 0x6d, 0x8d, 0xd5, 0x4e, 0xa9, 0x6c, 0x56, 0xf4, 0xea, 0x65, 0x7a, 0xae, 0x08, //B
+0xba, 0x78, 0x25, 0x2e, 0x1c, 0xa6, 0xb4, 0xc6, 0xe8, 0xdd, 0x74, 0x1f, 0x4b, 0xbd, 0x8b, 0x8a, //C
+0x70, 0x3e, 0xb5, 0x66, 0x48, 0x03, 0xf6, 0x0e, 0x61, 0x35, 0x57, 0xb9, 0x86, 0xc1, 0x1d, 0x9e, //D
+0xe1, 0xf8, 0x98, 0x11, 0x69, 0xd9, 0x8e, 0x94, 0x9b, 0x1e, 0x87, 0xe9, 0xce, 0x55, 0x28, 0xdf, //E
+0x8c, 0xa1, 0x89, 0x0d, 0xbf, 0xe6, 0x42, 0x68, 0x41, 0x99, 0x2d, 0x0f, 0xb0, 0x54, 0xbb, 0x16 }; //F
+// inverse sbox
+static const uint8_t rsbox[256] =
+{ 0x52, 0x09, 0x6a, 0xd5, 0x30, 0x36, 0xa5, 0x38, 0xbf, 0x40, 0xa3, 0x9e, 0x81, 0xf3, 0xd7, 0xfb
+, 0x7c, 0xe3, 0x39, 0x82, 0x9b, 0x2f, 0xff, 0x87, 0x34, 0x8e, 0x43, 0x44, 0xc4, 0xde, 0xe9, 0xcb
+, 0x54, 0x7b, 0x94, 0x32, 0xa6, 0xc2, 0x23, 0x3d, 0xee, 0x4c, 0x95, 0x0b, 0x42, 0xfa, 0xc3, 0x4e
+, 0x08, 0x2e, 0xa1, 0x66, 0x28, 0xd9, 0x24, 0xb2, 0x76, 0x5b, 0xa2, 0x49, 0x6d, 0x8b, 0xd1, 0x25
+, 0x72, 0xf8, 0xf6, 0x64, 0x86, 0x68, 0x98, 0x16, 0xd4, 0xa4, 0x5c, 0xcc, 0x5d, 0x65, 0xb6, 0x92
+, 0x6c, 0x70, 0x48, 0x50, 0xfd, 0xed, 0xb9, 0xda, 0x5e, 0x15, 0x46, 0x57, 0xa7, 0x8d, 0x9d, 0x84
+, 0x90, 0xd8, 0xab, 0x00, 0x8c, 0xbc, 0xd3, 0x0a, 0xf7, 0xe4, 0x58, 0x05, 0xb8, 0xb3, 0x45, 0x06
+, 0xd0, 0x2c, 0x1e, 0x8f, 0xca, 0x3f, 0x0f, 0x02, 0xc1, 0xaf, 0xbd, 0x03, 0x01, 0x13, 0x8a, 0x6b
+, 0x3a, 0x91, 0x11, 0x41, 0x4f, 0x67, 0xdc, 0xea, 0x97, 0xf2, 0xcf, 0xce, 0xf0, 0xb4, 0xe6, 0x73
+, 0x96, 0xac, 0x74, 0x22, 0xe7, 0xad, 0x35, 0x85, 0xe2, 0xf9, 0x37, 0xe8, 0x1c, 0x75, 0xdf, 0x6e
+, 0x47, 0xf1, 0x1a, 0x71, 0x1d, 0x29, 0xc5, 0x89, 0x6f, 0xb7, 0x62, 0x0e, 0xaa, 0x18, 0xbe, 0x1b
+, 0xfc, 0x56, 0x3e, 0x4b, 0xc6, 0xd2, 0x79, 0x20, 0x9a, 0xdb, 0xc0, 0xfe, 0x78, 0xcd, 0x5a, 0xf4
+, 0x1f, 0xdd, 0xa8, 0x33, 0x88, 0x07, 0xc7, 0x31, 0xb1, 0x12, 0x10, 0x59, 0x27, 0x80, 0xec, 0x5f
+, 0x60, 0x51, 0x7f, 0xa9, 0x19, 0xb5, 0x4a, 0x0d, 0x2d, 0xe5, 0x7a, 0x9f, 0x93, 0xc9, 0x9c, 0xef
+, 0xa0, 0xe0, 0x3b, 0x4d, 0xae, 0x2a, 0xf5, 0xb0, 0xc8, 0xeb, 0xbb, 0x3c, 0x83, 0x53, 0x99, 0x61
+, 0x17, 0x2b, 0x04, 0x7e, 0xba, 0x77, 0xd6, 0x26, 0xe1, 0x69, 0x14, 0x63, 0x55, 0x21, 0x0c, 0x7d };
+// round constant
+static const uint8_t Rcon[11] = {0x8d, 0x01, 0x02, 0x04, 0x08, 0x10, 0x20, 0x40, 0x80, 0x1b, 0x36};
+
+void cc3000_security::expandKey(uint8_t *expanded_key, uint8_t *key) {
+  uint16_t ii, buf1;
+  for (ii=0;ii<16;ii++)
+    expanded_key[ii] = key[ii];
+  for (ii=1;ii<11;ii++)
+  {
+    buf1 = expanded_key[ii*16 - 4];
+    expanded_key[ii*16 + 0] = sbox[expanded_key[ii*16 - 3]]^expanded_key[(ii-1)*16 + 0]^Rcon[ii];
+    expanded_key[ii*16 + 1] = sbox[expanded_key[ii*16 - 2]]^expanded_key[(ii-1)*16 + 1];
+    expanded_key[ii*16 + 2] = sbox[expanded_key[ii*16 - 1]]^expanded_key[(ii-1)*16 + 2];
+    expanded_key[ii*16 + 3] = sbox[buf1                  ]^expanded_key[(ii-1)*16 + 3];
+    expanded_key[ii*16 + 4] = expanded_key[(ii-1)*16 + 4]^expanded_key[ii*16 + 0];
+    expanded_key[ii*16 + 5] = expanded_key[(ii-1)*16 + 5]^expanded_key[ii*16 + 1];
+    expanded_key[ii*16 + 6] = expanded_key[(ii-1)*16 + 6]^expanded_key[ii*16 + 2];
+    expanded_key[ii*16 + 7] = expanded_key[(ii-1)*16 + 7]^expanded_key[ii*16 + 3];
+    expanded_key[ii*16 + 8] = expanded_key[(ii-1)*16 + 8]^expanded_key[ii*16 + 4];
+    expanded_key[ii*16 + 9] = expanded_key[(ii-1)*16 + 9]^expanded_key[ii*16 + 5];
+    expanded_key[ii*16 +10] = expanded_key[(ii-1)*16 +10]^expanded_key[ii*16 + 6];
+    expanded_key[ii*16 +11] = expanded_key[(ii-1)*16 +11]^expanded_key[ii*16 + 7];
+    expanded_key[ii*16 +12] = expanded_key[(ii-1)*16 +12]^expanded_key[ii*16 + 8];
+    expanded_key[ii*16 +13] = expanded_key[(ii-1)*16 +13]^expanded_key[ii*16 + 9];
+    expanded_key[ii*16 +14] = expanded_key[(ii-1)*16 +14]^expanded_key[ii*16 +10];
+    expanded_key[ii*16 +15] = expanded_key[(ii-1)*16 +15]^expanded_key[ii*16 +11];
+  }
+}
+
+uint8_t cc3000_security::galois_mul2(uint8_t value) {
+    if (value >> 7) {
+        value = value << 1;
+        return (value ^ 0x1b);
+    } else {
+        return (value << 1);
+    }
+}
+
+void cc3000_security::aes_encr(uint8_t *state, uint8_t *expanded_key) {
+  uint8_t buf1, buf2, buf3, round;
+
+  for (round = 0; round < 9; round ++)
+  {
+    // addroundkey, sbox and shiftrows
+    // row 0
+    state[ 0]  = sbox[(state[ 0] ^ expanded_key[(round*16)     ])];
+    state[ 4]  = sbox[(state[ 4] ^ expanded_key[(round*16) +  4])];
+    state[ 8]  = sbox[(state[ 8] ^ expanded_key[(round*16) +  8])];
+    state[12]  = sbox[(state[12] ^ expanded_key[(round*16) + 12])];
+    // row 1
+    buf1 = state[1] ^ expanded_key[(round*16) + 1];
+    state[ 1]  = sbox[(state[ 5] ^ expanded_key[(round*16) +  5])];
+    state[ 5]  = sbox[(state[ 9] ^ expanded_key[(round*16) +  9])];
+    state[ 9]  = sbox[(state[13] ^ expanded_key[(round*16) + 13])];
+    state[13]  = sbox[buf1];
+    // row 2
+    buf1 = state[2] ^ expanded_key[(round*16) + 2];
+    buf2 = state[6] ^ expanded_key[(round*16) + 6];
+    state[ 2]  = sbox[(state[10] ^ expanded_key[(round*16) + 10])];
+    state[ 6]  = sbox[(state[14] ^ expanded_key[(round*16) + 14])];
+    state[10]  = sbox[buf1];
+    state[14]  = sbox[buf2];
+    // row 3
+    buf1 = state[15] ^ expanded_key[(round*16) + 15];
+    state[15]  = sbox[(state[11] ^ expanded_key[(round*16) + 11])];
+    state[11]  = sbox[(state[ 7] ^ expanded_key[(round*16) +  7])];
+    state[ 7]  = sbox[(state[ 3] ^ expanded_key[(round*16) +  3])];
+    state[ 3]  = sbox[buf1];
+
+    // mixcolums //////////
+    // col1
+    buf1 = state[0] ^ state[1] ^ state[2] ^ state[3];
+    buf2 = state[0];
+    buf3 = state[0]^state[1]; buf3=galois_mul2(buf3); state[0] = state[0] ^ buf3 ^ buf1;
+    buf3 = state[1]^state[2]; buf3=galois_mul2(buf3); state[1] = state[1] ^ buf3 ^ buf1;
+    buf3 = state[2]^state[3]; buf3=galois_mul2(buf3); state[2] = state[2] ^ buf3 ^ buf1;
+    buf3 = state[3]^buf2;     buf3=galois_mul2(buf3); state[3] = state[3] ^ buf3 ^ buf1;
+    // col2
+    buf1 = state[4] ^ state[5] ^ state[6] ^ state[7];
+    buf2 = state[4];
+    buf3 = state[4]^state[5]; buf3=galois_mul2(buf3); state[4] = state[4] ^ buf3 ^ buf1;
+    buf3 = state[5]^state[6]; buf3=galois_mul2(buf3); state[5] = state[5] ^ buf3 ^ buf1;
+    buf3 = state[6]^state[7]; buf3=galois_mul2(buf3); state[6] = state[6] ^ buf3 ^ buf1;
+    buf3 = state[7]^buf2;     buf3=galois_mul2(buf3); state[7] = state[7] ^ buf3 ^ buf1;
+    // col3
+    buf1 = state[8] ^ state[9] ^ state[10] ^ state[11];
+    buf2 = state[8];
+    buf3 = state[8]^state[9];   buf3=galois_mul2(buf3); state[8] = state[8] ^ buf3 ^ buf1;
+    buf3 = state[9]^state[10];  buf3=galois_mul2(buf3); state[9] = state[9] ^ buf3 ^ buf1;
+    buf3 = state[10]^state[11]; buf3=galois_mul2(buf3); state[10] = state[10] ^ buf3 ^ buf1;
+    buf3 = state[11]^buf2;      buf3=galois_mul2(buf3); state[11] = state[11] ^ buf3 ^ buf1;
+    // col4
+    buf1 = state[12] ^ state[13] ^ state[14] ^ state[15];
+    buf2 = state[12];
+    buf3 = state[12]^state[13]; buf3=galois_mul2(buf3); state[12] = state[12] ^ buf3 ^ buf1;
+    buf3 = state[13]^state[14]; buf3=galois_mul2(buf3); state[13] = state[13] ^ buf3 ^ buf1;
+    buf3 = state[14]^state[15]; buf3=galois_mul2(buf3); state[14] = state[14] ^ buf3 ^ buf1;
+    buf3 = state[15]^buf2;      buf3=galois_mul2(buf3); state[15] = state[15] ^ buf3 ^ buf1;
+
+  }
+  // 10th round without mixcols
+  state[ 0]  = sbox[(state[ 0] ^ expanded_key[(round*16)     ])];
+  state[ 4]  = sbox[(state[ 4] ^ expanded_key[(round*16) +  4])];
+  state[ 8]  = sbox[(state[ 8] ^ expanded_key[(round*16) +  8])];
+  state[12]  = sbox[(state[12] ^ expanded_key[(round*16) + 12])];
+  // row 1
+  buf1 = state[1] ^ expanded_key[(round*16) + 1];
+  state[ 1]  = sbox[(state[ 5] ^ expanded_key[(round*16) +  5])];
+  state[ 5]  = sbox[(state[ 9] ^ expanded_key[(round*16) +  9])];
+  state[ 9]  = sbox[(state[13] ^ expanded_key[(round*16) + 13])];
+  state[13]  = sbox[buf1];
+  // row 2
+  buf1 = state[2] ^ expanded_key[(round*16) + 2];
+  buf2 = state[6] ^ expanded_key[(round*16) + 6];
+  state[ 2]  = sbox[(state[10] ^ expanded_key[(round*16) + 10])];
+  state[ 6]  = sbox[(state[14] ^ expanded_key[(round*16) + 14])];
+  state[10]  = sbox[buf1];
+  state[14]  = sbox[buf2];
+  // row 3
+  buf1 = state[15] ^ expanded_key[(round*16) + 15];
+  state[15]  = sbox[(state[11] ^ expanded_key[(round*16) + 11])];
+  state[11]  = sbox[(state[ 7] ^ expanded_key[(round*16) +  7])];
+  state[ 7]  = sbox[(state[ 3] ^ expanded_key[(round*16) +  3])];
+  state[ 3]  = sbox[buf1];
+  // last addroundkey
+  state[ 0]^=expanded_key[160];
+  state[ 1]^=expanded_key[161];
+  state[ 2]^=expanded_key[162];
+  state[ 3]^=expanded_key[163];
+  state[ 4]^=expanded_key[164];
+  state[ 5]^=expanded_key[165];
+  state[ 6]^=expanded_key[166];
+  state[ 7]^=expanded_key[167];
+  state[ 8]^=expanded_key[168];
+  state[ 9]^=expanded_key[169];
+  state[10]^=expanded_key[170];
+  state[11]^=expanded_key[171];
+  state[12]^=expanded_key[172];
+  state[13]^=expanded_key[173];
+  state[14]^=expanded_key[174];
+  state[15]^=expanded_key[175];
+}
+
+void cc3000_security::aes_decr(uint8_t *state, uint8_t *expanded_key) {
+  uint8_t buf1, buf2, buf3;
+  int8_t round;
+  round = 9;
+
+  // initial addroundkey
+  state[ 0]^=expanded_key[160];
+  state[ 1]^=expanded_key[161];
+  state[ 2]^=expanded_key[162];
+  state[ 3]^=expanded_key[163];
+  state[ 4]^=expanded_key[164];
+  state[ 5]^=expanded_key[165];
+  state[ 6]^=expanded_key[166];
+  state[ 7]^=expanded_key[167];
+  state[ 8]^=expanded_key[168];
+  state[ 9]^=expanded_key[169];
+  state[10]^=expanded_key[170];
+  state[11]^=expanded_key[171];
+  state[12]^=expanded_key[172];
+  state[13]^=expanded_key[173];
+  state[14]^=expanded_key[174];
+  state[15]^=expanded_key[175];
+
+  // 10th round without mixcols
+  state[ 0]  = rsbox[state[ 0]] ^ expanded_key[(round*16)     ];
+  state[ 4]  = rsbox[state[ 4]] ^ expanded_key[(round*16) +  4];
+  state[ 8]  = rsbox[state[ 8]] ^ expanded_key[(round*16) +  8];
+  state[12]  = rsbox[state[12]] ^ expanded_key[(round*16) + 12];
+  // row 1
+  buf1 =       rsbox[state[13]] ^ expanded_key[(round*16) +  1];
+  state[13]  = rsbox[state[ 9]] ^ expanded_key[(round*16) + 13];
+  state[ 9]  = rsbox[state[ 5]] ^ expanded_key[(round*16) +  9];
+  state[ 5]  = rsbox[state[ 1]] ^ expanded_key[(round*16) +  5];
+  state[ 1]  = buf1;
+  // row 2
+  buf1 =       rsbox[state[ 2]] ^ expanded_key[(round*16) + 10];
+  buf2 =       rsbox[state[ 6]] ^ expanded_key[(round*16) + 14];
+  state[ 2]  = rsbox[state[10]] ^ expanded_key[(round*16) +  2];
+  state[ 6]  = rsbox[state[14]] ^ expanded_key[(round*16) +  6];
+  state[10]  = buf1;
+  state[14]  = buf2;
+  // row 3
+  buf1 =       rsbox[state[ 3]] ^ expanded_key[(round*16) + 15];
+  state[ 3]  = rsbox[state[ 7]] ^ expanded_key[(round*16) +  3];
+  state[ 7]  = rsbox[state[11]] ^ expanded_key[(round*16) +  7];
+  state[11]  = rsbox[state[15]] ^ expanded_key[(round*16) + 11];
+  state[15]  = buf1;
+
+  for (round = 8; round >= 0; round--)
+  {
+    // barreto
+    //col1
+    buf1 = galois_mul2(galois_mul2(state[0]^state[2]));
+    buf2 = galois_mul2(galois_mul2(state[1]^state[3]));
+    state[0] ^= buf1;     state[1] ^= buf2;    state[2] ^= buf1;    state[3] ^= buf2;
+    //col2
+    buf1 = galois_mul2(galois_mul2(state[4]^state[6]));
+    buf2 = galois_mul2(galois_mul2(state[5]^state[7]));
+    state[4] ^= buf1;    state[5] ^= buf2;    state[6] ^= buf1;    state[7] ^= buf2;
+    //col3
+    buf1 = galois_mul2(galois_mul2(state[8]^state[10]));
+    buf2 = galois_mul2(galois_mul2(state[9]^state[11]));
+    state[8] ^= buf1;    state[9] ^= buf2;    state[10] ^= buf1;    state[11] ^= buf2;
+    //col4
+    buf1 = galois_mul2(galois_mul2(state[12]^state[14]));
+    buf2 = galois_mul2(galois_mul2(state[13]^state[15]));
+    state[12] ^= buf1;    state[13] ^= buf2;    state[14] ^= buf1;    state[15] ^= buf2;
+    // mixcolums //////////
+    // col1
+    buf1 = state[0] ^ state[1] ^ state[2] ^ state[3];
+    buf2 = state[0];
+    buf3 = state[0]^state[1]; buf3=galois_mul2(buf3); state[0] = state[0] ^ buf3 ^ buf1;
+    buf3 = state[1]^state[2]; buf3=galois_mul2(buf3); state[1] = state[1] ^ buf3 ^ buf1;
+    buf3 = state[2]^state[3]; buf3=galois_mul2(buf3); state[2] = state[2] ^ buf3 ^ buf1;
+    buf3 = state[3]^buf2;     buf3=galois_mul2(buf3); state[3] = state[3] ^ buf3 ^ buf1;
+    // col2
+    buf1 = state[4] ^ state[5] ^ state[6] ^ state[7];
+    buf2 = state[4];
+    buf3 = state[4]^state[5]; buf3=galois_mul2(buf3); state[4] = state[4] ^ buf3 ^ buf1;
+    buf3 = state[5]^state[6]; buf3=galois_mul2(buf3); state[5] = state[5] ^ buf3 ^ buf1;
+    buf3 = state[6]^state[7]; buf3=galois_mul2(buf3); state[6] = state[6] ^ buf3 ^ buf1;
+    buf3 = state[7]^buf2;     buf3=galois_mul2(buf3); state[7] = state[7] ^ buf3 ^ buf1;
+    // col3
+    buf1 = state[8] ^ state[9] ^ state[10] ^ state[11];
+    buf2 = state[8];
+    buf3 = state[8]^state[9];   buf3=galois_mul2(buf3); state[8] = state[8] ^ buf3 ^ buf1;
+    buf3 = state[9]^state[10];  buf3=galois_mul2(buf3); state[9] = state[9] ^ buf3 ^ buf1;
+    buf3 = state[10]^state[11]; buf3=galois_mul2(buf3); state[10] = state[10] ^ buf3 ^ buf1;
+    buf3 = state[11]^buf2;      buf3=galois_mul2(buf3); state[11] = state[11] ^ buf3 ^ buf1;
+    // col4
+    buf1 = state[12] ^ state[13] ^ state[14] ^ state[15];
+    buf2 = state[12];
+    buf3 = state[12]^state[13]; buf3=galois_mul2(buf3); state[12] = state[12] ^ buf3 ^ buf1;
+    buf3 = state[13]^state[14]; buf3=galois_mul2(buf3); state[13] = state[13] ^ buf3 ^ buf1;
+    buf3 = state[14]^state[15]; buf3=galois_mul2(buf3); state[14] = state[14] ^ buf3 ^ buf1;
+    buf3 = state[15]^buf2;      buf3=galois_mul2(buf3); state[15] = state[15] ^ buf3 ^ buf1;
+
+    // addroundkey, rsbox and shiftrows
+    // row 0
+    state[ 0]  = rsbox[state[ 0]] ^ expanded_key[(round*16)     ];
+    state[ 4]  = rsbox[state[ 4]] ^ expanded_key[(round*16) +  4];
+    state[ 8]  = rsbox[state[ 8]] ^ expanded_key[(round*16) +  8];
+    state[12]  = rsbox[state[12]] ^ expanded_key[(round*16) + 12];
+    // row 1
+    buf1 =       rsbox[state[13]] ^ expanded_key[(round*16) +  1];
+    state[13]  = rsbox[state[ 9]] ^ expanded_key[(round*16) + 13];
+    state[ 9]  = rsbox[state[ 5]] ^ expanded_key[(round*16) +  9];
+    state[ 5]  = rsbox[state[ 1]] ^ expanded_key[(round*16) +  5];
+    state[ 1]  = buf1;
+    // row 2
+    buf1 =       rsbox[state[ 2]] ^ expanded_key[(round*16) + 10];
+    buf2 =       rsbox[state[ 6]] ^ expanded_key[(round*16) + 14];
+    state[ 2]  = rsbox[state[10]] ^ expanded_key[(round*16) +  2];
+    state[ 6]  = rsbox[state[14]] ^ expanded_key[(round*16) +  6];
+    state[10]  = buf1;
+    state[14]  = buf2;
+    // row 3
+    buf1 =       rsbox[state[ 3]] ^ expanded_key[(round*16) + 15];
+    state[ 3]  = rsbox[state[ 7]] ^ expanded_key[(round*16) +  3];
+    state[ 7]  = rsbox[state[11]] ^ expanded_key[(round*16) +  7];
+    state[11]  = rsbox[state[15]] ^ expanded_key[(round*16) + 11];
+    state[15]  = buf1;
+  }
+}
+
+void cc3000_security::aes_encrypt(uint8_t *state, uint8_t *key) {
+    // expand the key into 176 bytes
+    expandKey(_expanded_key, key);
+    aes_encr(state, _expanded_key);
+}
+
+void cc3000_security::aes_decrypt(uint8_t *state, uint8_t *key) {
+    expandKey(_expanded_key, key);       // expand the key into 176 bytes
+    aes_decr(state, _expanded_key);
+}
+
+int32_t cc3000_security::aes_read_key(uint8_t *key) {
+    int32_t returnValue;
+
+    returnValue = nvmem_read(NVMEM_AES128_KEY_FILEID, AES128_KEY_SIZE, 0, key);
+
+    return returnValue;
+}
+
+int32_t cc3000_security::aes_write_key(uint8_t *key) {
+    int32_t    returnValue;
+
+    returnValue = nvmem_write(NVMEM_AES128_KEY_FILEID, AES128_KEY_SIZE, 0, key);
+
+    return returnValue;
+}
+#endif
+
+} // mbed_cc3000 namespace
+
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/WifiRobot/cc3000/cc3000_simplelink.cpp	Tue Dec 09 05:06:37 2014 +0000
@@ -0,0 +1,170 @@
+/*****************************************************************************
+*
+*  C++ interface/implementation created by Martin Kojtal (0xc0170). Thanks to
+*  Jim Carver and Frank Vannieuwkerke for their inital cc3000 mbed port and
+*  provided help.
+*
+*  This version of "host driver" uses CC3000 Host Driver Implementation. Thus
+*  read the following copyright:
+*
+*  Copyright (C) 2011 Texas Instruments Incorporated - http://www.ti.com/
+*
+*  Redistribution and use in source and binary forms, with or without
+*  modification, are permitted provided that the following conditions
+*  are met:
+*
+*    Redistributions of source code must retain the above copyright
+*    notice, this list of conditions and the following disclaimer.
+*
+*    Redistributions in binary form must reproduce the above copyright
+*    notice, this list of conditions and the following disclaimer in the
+*    documentation and/or other materials provided with the
+*    distribution.
+*
+*    Neither the name of Texas Instruments Incorporated nor the names of
+*    its contributors may be used to endorse or promote products derived
+*    from this software without specific prior written permission.
+*
+*  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+*  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+*  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
+*  A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
+*  OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
+*  SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
+*  LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
+*  DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
+*  THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+*  (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
+*  OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+*
+*****************************************************************************/
+#include "cc3000.h"
+#include "cc3000_common.h"
+
+namespace mbed_cc3000 {
+
+cc3000_simple_link::cc3000_simple_link() {
+    _rx_buffer[CC3000_RX_BUFFER_SIZE - 1] = CC3000_BUFFER_MAGIC_NUMBER;
+    _tx_buffer[CC3000_TX_BUFFER_SIZE - 1] = CC3000_BUFFER_MAGIC_NUMBER;
+}
+
+cc3000_simple_link::~cc3000_simple_link() {
+}
+
+uint8_t cc3000_simple_link::get_data_received_flag() {
+    return _data_received_flag;
+}
+
+void *cc3000_simple_link::get_func_pointer(FunctionNumber function){
+    void *result;
+    /* casting to void *, will be casted back once used */
+    switch(function) {
+        case FW_PATCHES:
+            result = (void *)_fFWPatches;
+            break;
+        case DRIVER_PATCHES:
+            result = (void *)_fDriverPatches;
+            break;
+        case BOOTLOADER_PATCHES:
+            result = (void *)_fBootLoaderPatches;
+            break;
+        default:
+            result = 0;
+         }
+         return result;
+}
+
+uint8_t* cc3000_simple_link::get_transmit_buffer() {
+    return _tx_buffer;
+}
+
+uint8_t* cc3000_simple_link::get_received_buffer() {
+    return _rx_buffer;
+}
+
+void cc3000_simple_link::set_op_code(uint16_t code) {
+    _rx_event_opcode = code;
+}
+
+void cc3000_simple_link::set_pending_data(uint16_t value) {
+    _rx_data_pending = value;
+}
+
+uint16_t cc3000_simple_link::get_pending_data() {
+    return _rx_data_pending;
+}
+
+void cc3000_simple_link::set_number_free_buffers(uint16_t value) {
+    _free_buffers = value;
+}
+
+void cc3000_simple_link::set_number_of_released_packets(uint16_t value) {
+    _released_packets = value;
+}
+
+
+void cc3000_simple_link::set_tx_complete_signal(bool value) {
+    _tx_complete_signal = value;
+}
+
+bool cc3000_simple_link::get_tx_complete_signal() {
+    return _tx_complete_signal;
+}
+
+void cc3000_simple_link::set_data_received_flag(uint8_t value) {
+    _data_received_flag = value;
+}
+
+uint16_t cc3000_simple_link::get_number_free_buffers() {
+    return _free_buffers;
+}
+
+uint16_t cc3000_simple_link::get_buffer_length() {
+    return _buffer_length;
+}
+
+void cc3000_simple_link::set_buffer_length(uint16_t value) {
+    _buffer_length = value;
+}
+
+uint16_t cc3000_simple_link::get_op_code() {
+    return _rx_event_opcode;
+}
+
+uint16_t cc3000_simple_link::get_released_packets() {
+    return _released_packets;
+}
+
+uint16_t cc3000_simple_link::get_sent_packets() {
+    return _sent_packets;
+}
+
+void cc3000_simple_link::set_sent_packets(uint16_t value) {
+    _sent_packets = value;
+}
+
+void cc3000_simple_link::set_transmit_error(int32_t value){
+    _transmit_data_error = value;
+}
+
+int32_t cc3000_simple_link::get_transmit_error(){
+    return _transmit_data_error;
+}
+
+void cc3000_simple_link::set_buffer_size(uint16_t value) {
+    _buffer_size = value;
+}
+
+uint16_t cc3000_simple_link::get_buffer_size(void) {
+    return _buffer_size;
+}
+
+uint8_t *cc3000_simple_link::get_received_data(void) {
+    return _received_data;
+}
+
+void cc3000_simple_link::set_received_data(uint8_t *pointer) {
+    _received_data = pointer;
+}
+
+} // mbed_cc3000 namespace
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/WifiRobot/cc3000/cc3000_simplelink.h Tue Dec 09 05:06:37 2014 +0000 @@ -0,0 +1,48 @@ +/***************************************************************************** +* +* C++ interface/implementation created by Martin Kojtal (0xc0170). Thanks to +* Jim Carver and Frank Vannieuwkerke for their inital cc3000 mbed port and +* provided help. +* +* This version of "host driver" uses CC3000 Host Driver Implementation. Thus +* read the following copyright: +* +* Copyright (C) 2011 Texas Instruments Incorporated - http://www.ti.com/ +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* +* Redistributions in binary form must reproduce the above copyright +* notice, this list of conditions and the following disclaimer in the +* documentation and/or other materials provided with the +* distribution. +* +* Neither the name of Texas Instruments Incorporated nor the names of +* its contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR +* A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +* OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +* SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT +* LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, +* DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY +* THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +* +*****************************************************************************/ +#ifndef CC3000_SIMPLELINK_H +#define CC3000_SIMPLELINK_H + +typedef uint8_t *(*tFWPatches)(uint32_t *usLength); +typedef uint8_t *(*tDriverPatches)(uint32_t *usLength); +typedef uint8_t *(*tBootLoaderPatches)(uint32_t *usLength); + +#endif
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/WifiRobot/cc3000/cc3000_socket.cpp	Tue Dec 09 05:06:37 2014 +0000
@@ -0,0 +1,604 @@
+/*****************************************************************************
+*
+*  C++ interface/implementation created by Martin Kojtal (0xc0170). Thanks to
+*  Jim Carver and Frank Vannieuwkerke for their inital cc3000 mbed port and
+*  provided help.
+*
+*  This version of "host driver" uses CC3000 Host Driver Implementation. Thus
+*  read the following copyright:
+*
+*  Copyright (C) 2011 Texas Instruments Incorporated - http://www.ti.com/
+*
+*  Redistribution and use in source and binary forms, with or without
+*  modification, are permitted provided that the following conditions
+*  are met:
+*
+*    Redistributions of source code must retain the above copyright
+*    notice, this list of conditions and the following disclaimer.
+*
+*    Redistributions in binary form must reproduce the above copyright
+*    notice, this list of conditions and the following disclaimer in the
+*    documentation and/or other materials provided with the
+*    distribution.
+*
+*    Neither the name of Texas Instruments Incorporated nor the names of
+*    its contributors may be used to endorse or promote products derived
+*    from this software without specific prior written permission.
+*
+*  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+*  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+*  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
+*  A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
+*  OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
+*  SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
+*  LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
+*  DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
+*  THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+*  (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
+*  OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+*
+*****************************************************************************/
+#include "cc3000.h"
+#include "cc3000_socket.h"
+#include "cc3000_event.h" //TODO - remove this
+#include "cc3000_common.h"
+
+namespace mbed_cc3000 {
+
+cc3000_socket::cc3000_socket(cc3000_simple_link &simplelink, cc3000_hci &hci, cc3000_event &event)
+    : _simple_link(simplelink), _hci(hci), _event(event) {
+
+}
+
+cc3000_socket::~cc3000_socket() {
+
+}
+
+int32_t cc3000_socket::HostFlowControlConsumeBuff(int32_t sd) {
+#ifndef SEND_NON_BLOCKING
+    /* wait in busy loop */
+    do {
+        // When the last transmission failed, return the last failure reason.
+        // Note that the buffer will not be allocated in this case
+        if (_simple_link.get_transmit_error() != 0) {
+            errno = _simple_link.get_transmit_error();
+            _simple_link.set_transmit_error(0);
+            return errno;
+        }
+
+        if(SOCKET_STATUS_ACTIVE != _event.get_socket_active_status(sd))
+            return -1;
+    } while (0 == _simple_link.get_number_free_buffers());
+
+    uint16_t free_buffer = _simple_link.get_number_free_buffers();
+    free_buffer--;
+    _simple_link.set_number_free_buffers(free_buffer);
+
+    return 0;
+#else
+
+    // When the last transmission failed, return the last failure reason.
+    // Note that the buffer will not be allocated in this case
+    if (_simple_link.get_transmit_error() != 0) {
+        errno = _simple_link.get_transmit_error();
+        _simple_link.set_transmit_error(0);
+        return errno;
+    }
+    if (SOCKET_STATUS_ACTIVE != _event.get_socket_active_status(sd))
+        return -1;
+
+    // If there are no available buffers, return -2. It is recommended to use
+    // select or receive to see if there is any buffer occupied with received data
+    // If so, call receive() to release the buffer.
+    if (0 == _simple_link.get_number_free_buffers()) {
+        return -2;
+    } else {
+        uint16_t free_buffer = _simple_link.get_number_free_buffers();
+        free_buffer--;
+        _simple_link.set_number_free_buffers(free_buffer);
+        return 0;
+    }
+#endif
+}
+
+int32_t cc3000_socket::socket(int32_t domain, int32_t type, int32_t protocol) {
+    int32_t ret;
+    uint8_t *ptr, *args;
+
+    ret = EFAIL;
+    ptr = _simple_link.get_transmit_buffer();
+    args = (ptr + HEADERS_SIZE_CMD);
+
+    // Fill in HCI packet structure
+    args = UINT32_TO_STREAM(args, domain);
+    args = UINT32_TO_STREAM(args, type);
+    args = UINT32_TO_STREAM(args, protocol);
+
+    // Initiate a HCI command
+    _hci.command_send(HCI_CMND_SOCKET, ptr, SOCKET_OPEN_PARAMS_LEN);
+
+    // Since we are in blocking state - wait for event complete
+    _event.simplelink_wait_event(HCI_CMND_SOCKET, &ret);
+
+    // Process the event
+    errno = ret;
+
+    _event.set_socket_active_status(ret, SOCKET_STATUS_ACTIVE);
+
+    return ret;
+}
+
+int32_t cc3000_socket::closesocket(int32_t sd) {
+    int32_t ret;
+    uint8_t *ptr, *args;
+
+    while (_simple_link.get_number_free_buffers() != SOCKET_MAX_FREE_BUFFERS);
+    ret = EFAIL;
+    ptr = _simple_link.get_transmit_buffer();
+    args = (ptr + HEADERS_SIZE_CMD);
+
+    // Fill in HCI packet structure
+    args = UINT32_TO_STREAM(args, sd);
+
+    // Initiate a HCI command
+    _hci.command_send(HCI_CMND_CLOSE_SOCKET, ptr, SOCKET_CLOSE_PARAMS_LEN);
+
+    // Since we are in blocking state - wait for event complete
+    _event.simplelink_wait_event(HCI_CMND_CLOSE_SOCKET, &ret);
+    errno = ret;
+
+    // since 'close' call may result in either OK (and then it closed) or error, mark this socket as invalid
+    _event.set_socket_active_status(sd, SOCKET_STATUS_INACTIVE);
+
+    return ret;
+}
+
+int32_t cc3000_socket::accept(int32_t sd, sockaddr *addr, socklen_t *addrlen) {
+    int32_t ret;
+    uint8_t *ptr, *args;
+    tBsdReturnParams tAcceptReturnArguments;
+
+    ret = EFAIL;
+    ptr = _simple_link.get_transmit_buffer();
+    args = (ptr + HEADERS_SIZE_CMD);
+
+    // Fill in temporary command buffer
+    args = UINT32_TO_STREAM(args, sd);
+
+    // Initiate a HCI command
+    _hci.command_send(HCI_CMND_ACCEPT, ptr, SOCKET_ACCEPT_PARAMS_LEN);
+
+    // Since we are in blocking state - wait for event complete
+    _event.simplelink_wait_event(HCI_CMND_ACCEPT, &tAcceptReturnArguments);
+
+
+    // need specify return parameters!!!
+    memcpy(addr, &tAcceptReturnArguments.tSocketAddress, ASIC_ADDR_LEN);
+    *addrlen = ASIC_ADDR_LEN;
+    errno = tAcceptReturnArguments.iStatus;
+    ret = errno;
+
+    // if succeeded, iStatus = new socket descriptor. otherwise - error number
+    if(M_IS_VALID_SD(ret)) {
+        _event.set_socket_active_status(ret, SOCKET_STATUS_ACTIVE);
+    } else {
+        _event.set_socket_active_status(sd, SOCKET_STATUS_INACTIVE);
+    }
+
+    return ret;
+}
+
+int32_t cc3000_socket::bind(int32_t sd, const sockaddr *addr, int32_t addrlen) {
+    int32_t ret;
+    uint8_t *ptr, *args;
+
+    ret = EFAIL;
+    ptr = _simple_link.get_transmit_buffer();
+    args = (ptr + HEADERS_SIZE_CMD);
+
+    addrlen = ASIC_ADDR_LEN;
+
+    // Fill in temporary command buffer
+    args = UINT32_TO_STREAM(args, sd);
+    args = UINT32_TO_STREAM(args, 0x00000008);
+    args = UINT32_TO_STREAM(args, addrlen);
+    ARRAY_TO_STREAM(args, ((uint8_t *)addr), addrlen);
+
+    // Initiate a HCI command
+    _hci.command_send(HCI_CMND_BIND, ptr, SOCKET_BIND_PARAMS_LEN);
+
+    // Since we are in blocking state - wait for event complete
+    _event.simplelink_wait_event(HCI_CMND_BIND, &ret);
+
+    errno = ret;
+
+    return ret;
+}
+
+int32_t cc3000_socket::listen(int32_t sd, int32_t backlog) {
+    int32_t ret;
+    uint8_t *ptr, *args;
+
+    ret = EFAIL;
+    ptr = _simple_link.get_transmit_buffer();
+    args = (ptr + HEADERS_SIZE_CMD);
+
+    // Fill in temporary command buffer
+    args = UINT32_TO_STREAM(args, sd);
+    args = UINT32_TO_STREAM(args, backlog);
+
+    // Initiate a HCI command
+    _hci.command_send(HCI_CMND_LISTEN, ptr, SOCKET_LISTEN_PARAMS_LEN);
+
+    // Since we are in blocking state - wait for event complete
+    _event.simplelink_wait_event(HCI_CMND_LISTEN, &ret);
+    errno = ret;
+
+    return(ret);
+}
+
+int32_t cc3000_socket::connect(int32_t sd, const sockaddr *addr, int32_t addrlen) {
+    int32_t ret;
+    uint8_t *ptr, *args;
+
+    ret = EFAIL;
+    ptr = _simple_link.get_transmit_buffer();
+    args = (ptr + SIMPLE_LINK_HCI_CMND_TRANSPORT_HEADER_SIZE);
+    addrlen = 8;
+
+    // Fill in temporary command buffer
+    args = UINT32_TO_STREAM(args, sd);
+    args = UINT32_TO_STREAM(args, 0x00000008);
+    args = UINT32_TO_STREAM(args, addrlen);
+    ARRAY_TO_STREAM(args, ((uint8_t *)addr), addrlen);
+
+    // Initiate a HCI command
+    _hci.command_send(HCI_CMND_CONNECT, ptr, SOCKET_CONNECT_PARAMS_LEN);
+
+    // Since we are in blocking state - wait for event complete
+    _event.simplelink_wait_event(HCI_CMND_CONNECT, &ret);
+
+    errno = ret;
+
+    return((int32_t)ret);
+}
+
+int32_t cc3000_socket::select(int32_t nfds, fd_set *readsds, fd_set *writesds, fd_set *exceptsds, struct timeval *timeout) {
+    uint8_t *ptr, *args;
+    tBsdSelectRecvParams tParams;
+    uint32_t is_blocking;
+
+    if (timeout == NULL) {
+        is_blocking = 1; /* blocking , infinity timeout */
+    } else {
+        is_blocking = 0; /* no blocking, timeout */
+    }
+
+    // Fill in HCI packet structure
+    ptr = _simple_link.get_transmit_buffer();
+    args = (ptr + HEADERS_SIZE_CMD);
+
+    // Fill in temporary command buffer
+    args = UINT32_TO_STREAM(args, nfds);
+    args = UINT32_TO_STREAM(args, 0x00000014);
+    args = UINT32_TO_STREAM(args, 0x00000014);
+    args = UINT32_TO_STREAM(args, 0x00000014);
+    args = UINT32_TO_STREAM(args, 0x00000014);
+    args = UINT32_TO_STREAM(args, is_blocking);
+    args = UINT32_TO_STREAM(args, ((readsds) ? *(uint32_t*)readsds : 0));
+    args = UINT32_TO_STREAM(args, ((writesds) ? *(uint32_t*)writesds : 0));
+    args = UINT32_TO_STREAM(args, ((exceptsds) ? *(uint32_t*)exceptsds : 0));
+
+    if (timeout) {
+        if ( 0 == timeout->tv_sec && timeout->tv_usec < SELECT_TIMEOUT_MIN_MICRO_SECONDS) {
+            timeout->tv_usec = SELECT_TIMEOUT_MIN_MICRO_SECONDS;
+        }
+        args = UINT32_TO_STREAM(args, timeout->tv_sec);
+        args = UINT32_TO_STREAM(args, timeout->tv_usec);
+    }
+
+    // Initiate a HCI command
+    _hci.command_send(HCI_CMND_BSD_SELECT, ptr, SOCKET_SELECT_PARAMS_LEN);
+
+    // Since we are in blocking state - wait for event complete
+    _event.simplelink_wait_event(HCI_EVNT_SELECT, &tParams);
+
+    // Update actually read FD
+    if (tParams.iStatus >= 0) {
+        if (readsds) {
+            memcpy(readsds, &tParams.uiRdfd, sizeof(tParams.uiRdfd));
+        }
+
+        if (writesds) {
+            memcpy(writesds, &tParams.uiWrfd, sizeof(tParams.uiWrfd));
+        }
+
+        if (exceptsds) {
+            memcpy(exceptsds, &tParams.uiExfd, sizeof(tParams.uiExfd));
+        }
+
+        return(tParams.iStatus);
+
+    } else {
+        errno = tParams.iStatus;
+        return -1;
+    }
+}
+
+int32_t cc3000_socket::getsockopt (int32_t sd, int32_t level, int32_t optname, void *optval, socklen_t *optlen) {
+    uint8_t *ptr, *args;
+    tBsdGetSockOptReturnParams  tRetParams;
+
+    ptr = _simple_link.get_transmit_buffer();
+    args = (ptr + HEADERS_SIZE_CMD);
+
+    // Fill in temporary command buffer
+    args = UINT32_TO_STREAM(args, sd);
+    args = UINT32_TO_STREAM(args, level);
+    args = UINT32_TO_STREAM(args, optname);
+
+    // Initiate a HCI command
+    _hci.command_send(HCI_CMND_GETSOCKOPT, ptr, SOCKET_GET_SOCK_OPT_PARAMS_LEN);
+
+    // Since we are in blocking state - wait for event complete
+    _event.simplelink_wait_event(HCI_CMND_GETSOCKOPT, &tRetParams);
+
+    if (((int8_t)tRetParams.iStatus) >= 0) {
+        *optlen = 4;
+        memcpy(optval, tRetParams.ucOptValue, 4);
+        return (0);
+    } else {
+        errno = tRetParams.iStatus;
+        return errno;
+    }
+}
+
+int32_t cc3000_socket::simple_link_recv(int32_t sd, void *buf, int32_t len, int32_t flags, sockaddr *from, socklen_t *fromlen, int32_t opcode) {
+    uint8_t *ptr, *args;
+    tBsdReadReturnParams tSocketReadEvent;
+
+    ptr = _simple_link.get_transmit_buffer();
+    args = (ptr + HEADERS_SIZE_CMD);
+
+    // Fill in HCI packet structure
+    args = UINT32_TO_STREAM(args, sd);
+    args = UINT32_TO_STREAM(args, len);
+    args = UINT32_TO_STREAM(args, flags);
+
+    // Generate the read command, and wait for the
+    _hci.command_send(opcode,  ptr, SOCKET_RECV_FROM_PARAMS_LEN);
+
+    // Since we are in blocking state - wait for event complete
+    _event.simplelink_wait_event(opcode, &tSocketReadEvent);
+
+    // In case the number of bytes is more then zero - read data
+    if (tSocketReadEvent.iNumberOfBytes > 0) {
+        // Wait for the data in a synchronous way. Here we assume that the bug is
+        // big enough to store also parameters of receive from too....
+        _event.simplelink_wait_data((uint8_t *)buf, (uint8_t *)from, (uint8_t *)fromlen);
+    }
+
+    errno = tSocketReadEvent.iNumberOfBytes;
+
+    return(tSocketReadEvent.iNumberOfBytes);
+}
+
+int32_t cc3000_socket::recv(int32_t sd, void *buf, int32_t len, int32_t flags) {
+    return(simple_link_recv(sd, buf, len, flags, NULL, NULL, HCI_CMND_RECV));
+}
+
+int32_t cc3000_socket::recvfrom(int32_t sd, void *buf, int32_t len, int32_t flags, sockaddr *from, socklen_t *fromlen) {
+    return(simple_link_recv(sd, buf, len, flags, from, fromlen, HCI_CMND_RECVFROM));
+}
+
+int32_t cc3000_socket::simple_link_send(int32_t sd, const void *buf, int32_t len, int32_t flags, const sockaddr *to, int32_t tolen, int32_t opcode) {
+    uint8_t uArgSize = 0x00,  addrlen = 0x00;
+    uint8_t *ptr, *pDataPtr = NULL, *args;
+    uint32_t addr_offset = 0x00;
+    int32_t res;
+    tBsdReadReturnParams tSocketSendEvent;
+
+    // Check the bsd_arguments
+    if (0 != (res = HostFlowControlConsumeBuff(sd))) {
+        return res;
+    }
+
+    //Update the number of sent packets
+    uint16_t sent_packets = _simple_link.get_sent_packets();
+    sent_packets++;
+    _simple_link.set_sent_packets(sent_packets);
+
+    // Allocate a buffer and construct a packet and send it over spi
+    ptr = _simple_link.get_transmit_buffer();
+    args = (ptr + HEADERS_SIZE_DATA);
+
+    // Update the offset of data and parameters according to the command
+    switch(opcode)
+    {
+        case HCI_CMND_SENDTO:
+        {
+            addr_offset = len + sizeof(len) + sizeof(len);
+            addrlen = 8;
+            uArgSize = SOCKET_SENDTO_PARAMS_LEN;
+            pDataPtr = ptr + HEADERS_SIZE_DATA + SOCKET_SENDTO_PARAMS_LEN;
+            break;
+        }
+
+        case HCI_CMND_SEND:
+        {
+            tolen = 0;
+            to = NULL;
+            uArgSize = HCI_CMND_SEND_ARG_LENGTH;
+            pDataPtr = ptr + HEADERS_SIZE_DATA + HCI_CMND_SEND_ARG_LENGTH;
+            break;
+        }
+
+        default:
+        {
+            break;
+        }
+    }
+
+    // Fill in temporary command buffer
+    args = UINT32_TO_STREAM(args, sd);
+    args = UINT32_TO_STREAM(args, uArgSize - sizeof(sd));
+    args = UINT32_TO_STREAM(args, len);
+    args = UINT32_TO_STREAM(args, flags);
+
+    if (opcode == HCI_CMND_SENDTO) {
+        args = UINT32_TO_STREAM(args, addr_offset);
+        args = UINT32_TO_STREAM(args, addrlen);
+    }
+
+    // Copy the data received from user into the TX Buffer
+    ARRAY_TO_STREAM(pDataPtr, ((uint8_t *)buf), len);
+
+    // In case we are using SendTo, copy the to parameters
+    if (opcode == HCI_CMND_SENDTO) {
+        ARRAY_TO_STREAM(pDataPtr, ((uint8_t *)to), tolen);
+    }
+
+    // Initiate a HCI command
+    _hci.data_send(opcode, ptr, uArgSize, len,(uint8_t*)to, tolen);
+    if (opcode == HCI_CMND_SENDTO)
+       _event.simplelink_wait_event(HCI_EVNT_SENDTO, &tSocketSendEvent);
+    else
+       _event.simplelink_wait_event(HCI_EVNT_SEND, &tSocketSendEvent);
+
+    return (len);
+}
+
+int32_t cc3000_socket::send(int32_t sd, const void *buf, int32_t len, int32_t flags) {
+    return(simple_link_send(sd, buf, len, flags, NULL, 0, HCI_CMND_SEND));
+}
+
+int32_t cc3000_socket::sendto(int32_t sd, const void *buf, int32_t len, int32_t flags, const sockaddr *to, socklen_t tolen) {
+    return(simple_link_send(sd, buf, len, flags, to, tolen, HCI_CMND_SENDTO));
+}
+
+int32_t cc3000_socket::mdns_advertiser(uint16_t mdns_enabled, uint8_t *device_service_name, uint16_t device_service_name_length) {
+    int32_t ret;
+     uint8_t *pTxBuffer, *pArgs;
+
+    if (device_service_name_length > MDNS_DEVICE_SERVICE_MAX_LENGTH) {
+        return EFAIL;
+    }
+
+    pTxBuffer = _simple_link.get_transmit_buffer();
+    pArgs = (pTxBuffer + SIMPLE_LINK_HCI_CMND_TRANSPORT_HEADER_SIZE);
+
+    // Fill in HCI packet structure
+    pArgs = UINT32_TO_STREAM(pArgs, mdns_enabled);
+    pArgs = UINT32_TO_STREAM(pArgs, 8);
+    pArgs = UINT32_TO_STREAM(pArgs, device_service_name_length);
+    ARRAY_TO_STREAM(pArgs, device_service_name, device_service_name_length);
+
+    // Initiate a HCI command
+    _hci.command_send(HCI_CMND_MDNS_ADVERTISE, pTxBuffer, SOCKET_MDNS_ADVERTISE_PARAMS_LEN + device_service_name_length);
+
+    // Since we are in blocking state - wait for event complete
+    _event.simplelink_wait_event(HCI_EVNT_MDNS_ADVERTISE, &ret);
+
+    return ret;
+}
+
+
+#ifndef CC3000_TINY_DRIVER
+int32_t cc3000_socket::gethostbyname(uint8_t *hostname, uint16_t name_length, uint32_t *out_ip_addr) {
+    tBsdGethostbynameParams ret;
+    uint8_t *ptr, *args;
+
+    errno = EFAIL;
+
+    if (name_length > HOSTNAME_MAX_LENGTH) {
+        return errno;
+    }
+
+    ptr = _simple_link.get_transmit_buffer();
+    args = (ptr + SIMPLE_LINK_HCI_CMND_TRANSPORT_HEADER_SIZE);
+
+    // Fill in HCI packet structure
+    args = UINT32_TO_STREAM(args, 8);
+    args = UINT32_TO_STREAM(args, name_length);
+    ARRAY_TO_STREAM(args, hostname, name_length);
+
+    // Initiate a HCI command
+    _hci.command_send(HCI_CMND_GETHOSTNAME, ptr, SOCKET_GET_HOST_BY_NAME_PARAMS_LEN + name_length - 1);
+
+    // Since we are in blocking state - wait for event complete
+    _event.simplelink_wait_event(HCI_EVNT_BSD_GETHOSTBYNAME, &ret);
+
+    errno = ret.retVal;
+
+    (*((int32_t*)out_ip_addr)) = ret.outputAddress;
+
+    return (errno);
+}
+
+int32_t cc3000_socket::setsockopt(int32_t sd, int32_t level, int32_t optname, const void *optval, socklen_t optlen) {
+    int32_t ret;
+    uint8_t *ptr, *args;
+
+    ptr = _simple_link.get_transmit_buffer();
+    args = (ptr + HEADERS_SIZE_CMD);
+
+    // Fill in temporary command buffer
+    args = UINT32_TO_STREAM(args, sd);
+    args = UINT32_TO_STREAM(args, level);
+    args = UINT32_TO_STREAM(args, optname);
+    args = UINT32_TO_STREAM(args, 0x00000008);
+    args = UINT32_TO_STREAM(args, optlen);
+    ARRAY_TO_STREAM(args, ((uint8_t *)optval), optlen);
+
+    // Initiate a HCI command
+    _hci.command_send(HCI_CMND_SETSOCKOPT, ptr, SOCKET_SET_SOCK_OPT_PARAMS_LEN  + optlen);
+
+    // Since we are in blocking state - wait for event complete
+    _event.simplelink_wait_event(HCI_CMND_SETSOCKOPT, &ret);
+
+    if (ret >= 0) {
+        return (0);
+    } else {
+        errno = ret;
+        return ret;
+    }
+}
+
+#endif
+
+char* cc3000_socket::inet_ntoa_r(uint32_t s_addr, char *buf, int buflen)
+{
+    char inv[3];
+    char *rp;
+    uint8_t *ap;
+    uint8_t rem;
+    uint8_t n;
+    uint8_t i;
+    int len = 0;
+
+    rp = buf;
+    ap = (uint8_t *)&s_addr;
+    for (n = 0; n < 4; n++) {
+        i = 0;
+        do {
+            rem = *ap % (uint8_t)10;
+            *ap /= (uint8_t)10;
+            inv[i++] = '0' + rem;
+        } while(*ap);
+        while(i--) {
+            if (len++ >= buflen) {
+                return NULL;
+            }
+            *rp++ = inv[i];
+        }
+        if (len++ >= buflen) {
+            return NULL;
+        }
+        *rp++ = '.';
+        ap++;
+    }
+    *--rp = 0;
+    return buf;
+}
+
+} // mbed_cc3000 namespace
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/WifiRobot/cc3000/cc3000_socket.h	Tue Dec 09 05:06:37 2014 +0000
@@ -0,0 +1,229 @@
+/*****************************************************************************
+*
+*  C++ interface/implementation created by Martin Kojtal (0xc0170). Thanks to
+*  Jim Carver and Frank Vannieuwkerke for their inital cc3000 mbed port and
+*  provided help.
+*
+*  This version of "host driver" uses CC3000 Host Driver Implementation. Thus
+*  read the following copyright:
+*
+*  Copyright (C) 2011 Texas Instruments Incorporated - http://www.ti.com/
+*
+*  Redistribution and use in source and binary forms, with or without
+*  modification, are permitted provided that the following conditions
+*  are met:
+*
+*    Redistributions of source code must retain the above copyright
+*    notice, this list of conditions and the following disclaimer.
+*
+*    Redistributions in binary form must reproduce the above copyright
+*    notice, this list of conditions and the following disclaimer in the
+*    documentation and/or other materials provided with the
+*    distribution.
+*
+*    Neither the name of Texas Instruments Incorporated nor the names of
+*    its contributors may be used to endorse or promote products derived
+*    from this software without specific prior written permission.
+*
+*  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+*  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+*  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
+*  A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
+*  OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
+*  SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
+*  LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
+*  DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
+*  THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+*  (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
+*  OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+*
+*****************************************************************************/
+#ifndef CC3000_SOCKET_H
+#define CC3000_SOCKET_H
+
+#define SOCKET_MAX_FREE_BUFFERS    6
+
+#define SOCKET_STATUS_ACTIVE       0
+#define SOCKET_STATUS_INACTIVE     1
+
+#define SOCKET_STATUS_INIT_VAL  0xFFFF
+#define M_IS_VALID_SD(sd) ((0 <= (sd)) && ((sd) <= 7))
+#define M_IS_VALID_STATUS(status) (((status) == SOCKET_STATUS_ACTIVE)||((status) == SOCKET_STATUS_INACTIVE))
+
+#ifdef _API_USE_BSD_CLOSE
+    #define close(sd) closesocket(sd)
+#endif
+
+//Enable this flag if and only if you must comply with BSD socket read() and
+//write() functions
+#ifdef _API_USE_BSD_READ_WRITE
+    #define read(sd, buf, len, flags) recv(sd, buf, len, flags)
+    #define write(sd, buf, len, flags) send(sd, buf, len, flags)
+#endif
+
+#define SOCKET_OPEN_PARAMS_LEN                 (12)
+#define SOCKET_CLOSE_PARAMS_LEN                (4)
+#define SOCKET_ACCEPT_PARAMS_LEN               (4)
+#define SOCKET_BIND_PARAMS_LEN                 (20)
+#define SOCKET_LISTEN_PARAMS_LEN               (8)
+#define SOCKET_GET_HOST_BY_NAME_PARAMS_LEN     (9)
+#define SOCKET_CONNECT_PARAMS_LEN              (20)
+#define SOCKET_SELECT_PARAMS_LEN               (44)
+#define SOCKET_SET_SOCK_OPT_PARAMS_LEN         (20)
+#define SOCKET_GET_SOCK_OPT_PARAMS_LEN         (12)
+#define SOCKET_RECV_FROM_PARAMS_LEN            (12)
+#define SOCKET_SENDTO_PARAMS_LEN               (24)
+#define SOCKET_MDNS_ADVERTISE_PARAMS_LEN       (12)
+
+//#define NULL 0
+
+// The legnth of arguments for the SEND command: sd + buff_offset + len + flags,
+// while size of each parameter is 32 bit - so the total length is 16 bytes;
+
+#define HCI_CMND_SEND_ARG_LENGTH                    (16)
+#define SELECT_TIMEOUT_MIN_MICRO_SECONDS            5000
+#define HEADERS_SIZE_DATA                           (SPI_HEADER_SIZE + 5)
+#define SIMPLE_LINK_HCI_CMND_TRANSPORT_HEADER_SIZE  (SPI_HEADER_SIZE + SIMPLE_LINK_HCI_CMND_HEADER_SIZE)
+#define MDNS_DEVICE_SERVICE_MAX_LENGTH              (32)
+
+
+#define HOSTNAME_MAX_LENGTH (230)  // 230 bytes + header shouldn't exceed 8 bit value
+
+//--------- Address Families --------
+
+#define  AF_INET                2
+#define  AF_INET6               23
+
+//------------ Socket Types ------------
+
+#define  SOCK_STREAM            1
+#define  SOCK_DGRAM             2
+#define  SOCK_RAW               3           // Raw sockets allow new IPv4 protocols to be implemented in user space. A raw socket receives or sends the raw datagram not including link level headers
+#define  SOCK_RDM               4
+#define  SOCK_SEQPACKET         5
+
+//----------- Socket Protocol ----------
+
+#define IPPROTO_IP              0           // dummy for IP
+#define IPPROTO_ICMP            1           // control message protocol
+#define IPPROTO_IPV4            IPPROTO_IP  // IP inside IP
+#define IPPROTO_TCP             6           // tcp
+#define IPPROTO_UDP             17          // user datagram protocol
+#define IPPROTO_IPV6            41          // IPv6 in IPv6
+#define IPPROTO_NONE            59          // No next header
+#define IPPROTO_RAW             255         // raw IP packet
+#define IPPROTO_MAX             256
+
+//----------- Socket retunr codes  -----------
+
+#define SOC_ERROR                (-1)        // error
+#define SOC_IN_PROGRESS          (-2)        // socket in progress
+
+//----------- Socket Options -----------
+#define  SOL_SOCKET             0xffff       //  socket level
+#define  SOCKOPT_RECV_TIMEOUT   1            //  optname to configure recv and recvfromtimeout
+#define  SOCKOPT_NONBLOCK       2            // accept non block mode set SOCK_ON or SOCK_OFF (default block mode )
+#define  SOCK_ON                0            // socket non-blocking mode    is enabled
+#define  SOCK_OFF               1            // socket blocking mode is enabled
+
+#define  TCP_NODELAY            0x0001
+#define  TCP_BSDURGENT          0x7000
+
+#define  MAX_PACKET_SIZE        1500
+#define  MAX_LISTEN_QUEUE       4
+
+#define  IOCTL_SOCKET_EVENTMASK
+
+#define __FD_SETSIZE            32
+
+#define  ASIC_ADDR_LEN          8
+
+#define NO_QUERY_RECIVED        -3
+
+
+typedef struct _in_addr_t
+{
+    uint32_t s_addr;                   // load with inet_aton()
+} in_addr;
+
+/*typedef struct _sockaddr_t
+{
+    unsigned short int  sa_family;
+    unsigned char       sa_data[14];
+} sockaddr;*/
+
+typedef struct _sockaddr_in_t
+{
+    int16_t  sin_family;            // e.g. AF_INET
+    uint16_t sin_port;              // e.g. htons(3490)
+    in_addr  sin_addr;              // see struct in_addr, below
+    uint8_t  sin_zero[8];           // zero this if you want to
+} sockaddr_in;
+
+typedef uint32_t socklen_t;
+
+// The fd_set member is required to be an array of longs.
+typedef int32_t __fd_mask;
+
+// It's easier to assume 8-bit bytes than to get CHAR_BIT.
+#define __NFDBITS               (8 * sizeof (__fd_mask))
+#define __FDELT(d)              ((d) / __NFDBITS)
+#define __FDMASK(d)             ((__fd_mask) 1 << ((d) % __NFDBITS))
+
+#ifndef FD_SET
+//not used in the current code
+#define ENOBUFS                 55          // No buffer space available
+
+// Access macros for 'fd_set'.
+#define FD_SET(fd, fdsetp)      __FD_SET (fd, fdsetp)
+#define FD_CLR(fd, fdsetp)      __FD_CLR (fd, fdsetp)
+#define FD_ISSET(fd, fdsetp)    __FD_ISSET (fd, fdsetp)
+#define FD_ZERO(fdsetp)         __FD_ZERO (fdsetp)
+
+// fd_set for select and pselect.
+typedef struct
+{
+    __fd_mask fds_bits[__FD_SETSIZE / __NFDBITS];
+#define __FDS_BITS(set)        ((set)->fds_bits)
+} fd_set;
+
+#endif /* FD_SET */
+
+// We don't use `memset' because this would require a prototype and
+//   the array isn't too big.
+#define __FD_ZERO(set)                               \
+  do {                                                \
+    uint32_t __i;                                 \
+    fd_set *__arr = (set);                            \
+    for (__i = 0; __i < sizeof (fd_set) / sizeof (__fd_mask); ++__i) \
+      __FDS_BITS (__arr)[__i] = 0;                    \
+  } while (0)
+#define __FD_SET(d, set)       (__FDS_BITS (set)[__FDELT (d)] |= __FDMASK (d))
+#define __FD_CLR(d, set)       (__FDS_BITS (set)[__FDELT (d)] &= ~__FDMASK (d))
+#define __FD_ISSET(d, set)     (__FDS_BITS (set)[__FDELT (d)] & __FDMASK (d))
+
+//Use in case of Big Endian only
+
+#define htonl(A)    ((((uint32_t)(A) & 0xff000000) >> 24) | \
+                     (((uint32_t)(A) & 0x00ff0000) >> 8) | \
+                     (((uint32_t)(A) & 0x0000ff00) << 8) | \
+                     (((uint32_t)(A) & 0x000000ff) << 24))
+
+#define ntohl                   htonl
+
+//Use in case of Big Endian only
+#define htons(A)     ((((uint32_t)(A) & 0xff00) >> 8) | \
+                      (((uint32_t)(A) & 0x00ff) << 8))
+
+
+#define ntohs                   htons
+
+// mDNS port - 5353    mDNS multicast address - 224.0.0.251
+#define SET_mDNS_ADD(sockaddr) sockaddr.sa_data[0] = 0x14; \
+                               sockaddr.sa_data[1] = 0xe9; \
+                               sockaddr.sa_data[2] = 0xe0; \
+                               sockaddr.sa_data[3] = 0x0;  \
+                               sockaddr.sa_data[4] = 0x0;  \
+                               sockaddr.sa_data[5] = 0xfb;
+
+#endif
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/WifiRobot/cc3000/cc3000_spi.cpp	Tue Dec 09 05:06:37 2014 +0000
@@ -0,0 +1,255 @@
+/*****************************************************************************
+*
+*  C++ interface/implementation created by Martin Kojtal (0xc0170). Thanks to
+*  Jim Carver and Frank Vannieuwkerke for their inital cc3000 mbed port and
+*  provided help.
+*
+*  This version of "host driver" uses CC3000 Host Driver Implementation. Thus
+*  read the following copyright:
+*
+*  Copyright (C) 2011 Texas Instruments Incorporated - http://www.ti.com/
+*
+*  Redistribution and use in source and binary forms, with or without
+*  modification, are permitted provided that the following conditions
+*  are met:
+*
+*    Redistributions of source code must retain the above copyright
+*    notice, this list of conditions and the following disclaimer.
+*
+*    Redistributions in binary form must reproduce the above copyright
+*    notice, this list of conditions and the following disclaimer in the
+*    documentation and/or other materials provided with the
+*    distribution.
+*
+*    Neither the name of Texas Instruments Incorporated nor the names of
+*    its contributors may be used to endorse or promote products derived
+*    from this software without specific prior written permission.
+*
+*  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+*  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+*  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
+*  A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
+*  OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
+*  SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
+*  LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
+*  DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
+*  THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+*  (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
+*  OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+*
+*****************************************************************************/
+#include "cc3000.h"
+#include "cc3000_spi.h"
+
+namespace mbed_cc3000 {
+
+cc3000_spi::cc3000_spi(PinName cc3000_irq, PinName cc3000_en, PinName cc3000_cs, SPI cc3000_spi, cc3000_event &event, cc3000_simple_link &simple_link)
+  : _wlan_irq(cc3000_irq), _wlan_en(cc3000_en), _wlan_cs(cc3000_cs), _wlan_spi(cc3000_spi), _event(event), _simple_link(simple_link) {
+
+    _wlan_spi.format(8,1);
+    _wlan_spi.frequency(12000000);
+    _wlan_irq.fall(this, &cc3000_spi::WLAN_IRQHandler);
+
+    _wlan_en = 0;
+    _wlan_cs = 1;
+    wait_ms(50); /* mbed board delay */
+}
+
+cc3000_spi::~cc3000_spi() {
+
+}
+
+void cc3000_spi::wlan_irq_enable()
+{
+    _process_irq = true;
+    //_wlan_irq.enable_irq();
+
+    if (wlan_irq_read() == 0) {
+        WLAN_IRQHandler();
+    }
+}
+
+void cc3000_spi::wlan_irq_disable() {
+    _process_irq = false;
+    //_wlan_irq.disable_irq();
+}
+
+uint32_t cc3000_spi::wlan_irq_read() {
+    return _wlan_irq.read();
+}
+
+void cc3000_spi::close() {
+    wlan_irq_disable();
+}
+
+void cc3000_spi::open() {
+   _spi_info.spi_state = eSPI_STATE_POWERUP;
+   _spi_info.tx_packet_length = 0;
+   _spi_info.rx_packet_length = 0;
+    wlan_irq_enable();
+}
+
+uint32_t cc3000_spi::first_write(uint8_t *buffer, uint16_t length) {
+    _wlan_cs = 0;
+    wait_us(50);
+
+    /* first 4 bytes of the data */
+    write_synchronous(buffer, 4);
+    wait_us(50);
+    write_synchronous(buffer + 4, length - 4);
+    _spi_info.spi_state = eSPI_STATE_IDLE;
+    _wlan_cs = 1;
+
+    return 0;
+}
+
+
+uint32_t cc3000_spi::write(uint8_t *buffer, uint16_t length) {
+    uint8_t pad = 0;
+    // check the total length of the packet in order to figure out if padding is necessary
+    if(!(length & 0x0001)) {
+      pad++;
+    }
+    buffer[0] = WRITE;
+    buffer[1] = HI(length + pad);
+    buffer[2] = LO(length + pad);
+    buffer[3] = 0;
+    buffer[4] = 0;
+
+    length += (SPI_HEADER_SIZE + pad);
+
+    // The magic number resides at the end of the TX/RX buffer (1 byte after the allocated size)
+    // If the magic number is overwitten - buffer overrun occurred - we will be stuck here forever!
+    uint8_t *transmit_buffer = _simple_link.get_transmit_buffer();
+    if (transmit_buffer[CC3000_TX_BUFFER_SIZE - 1] != CC3000_BUFFER_MAGIC_NUMBER) {
+        while (1);
+    }
+
+    if (_spi_info.spi_state == eSPI_STATE_POWERUP) {
+        while (_spi_info.spi_state != eSPI_STATE_INITIALIZED);
+    }
+
+    if (_spi_info.spi_state == eSPI_STATE_INITIALIZED) {
+        // TX/RX transaction over SPI after powerup: IRQ is low - send read buffer size command
+        first_write(buffer, length);
+    } else {
+        // Prevent occurence of a race condition when 2 back to back packets are sent to the
+        // device, so the state will move to IDLE and once again to not IDLE due to IRQ
+        wlan_irq_disable();
+
+        while (_spi_info.spi_state != eSPI_STATE_IDLE);
+
+        _spi_info.spi_state = eSPI_STATE_WRITE_IRQ;
+        //_spi_info.pTxPacket = buffer;
+        _spi_info.tx_packet_length = length;
+
+        // Assert the CS line and wait until the IRQ line is active, then initialize the write operation
+        _wlan_cs = 0;
+
+        wlan_irq_enable();
+    }
+
+    // Wait until the transaction ends
+    while (_spi_info.spi_state != eSPI_STATE_IDLE);
+
+    return 0;
+}
+
+void cc3000_spi::write_synchronous(uint8_t *data, uint16_t size) {
+    while(size) {
+        _wlan_spi.write(*data++);
+        size--;
+    }
+}
+
+void cc3000_spi::read_synchronous(uint8_t *data, uint16_t size) {
+    for (uint32_t i = 0; i < size; i++) {
+        data[i] = _wlan_spi.write(0x03);
+    }
+}
+
+uint32_t cc3000_spi::read_data_cont() {
+   int32_t data_to_recv;
+   uint8_t *evnt_buff, type;
+
+   //determine the packet type
+   evnt_buff = _simple_link.get_received_buffer();
+   data_to_recv = 0;
+   STREAM_TO_UINT8((uint8_t *)(evnt_buff + SPI_HEADER_SIZE), HCI_PACKET_TYPE_OFFSET, type);
+
+    switch(type) {
+        case HCI_TYPE_DATA:
+            // Read the remaining data..
+            STREAM_TO_UINT16((uint8_t *)(evnt_buff + SPI_HEADER_SIZE), HCI_DATA_LENGTH_OFFSET, data_to_recv);
+            if (!((HEADERS_SIZE_EVNT + data_to_recv) & 1)) {
+               data_to_recv++;
+            }
+
+            if (data_to_recv) {
+               read_synchronous(evnt_buff + 10, data_to_recv);
+            }
+            break;
+        case HCI_TYPE_EVNT:
+            // Calculate the rest length of the data
+            STREAM_TO_UINT8((char *)(evnt_buff + SPI_HEADER_SIZE), HCI_EVENT_LENGTH_OFFSET, data_to_recv);
+            data_to_recv -= 1;
+            // Add padding byte if needed
+            if ((HEADERS_SIZE_EVNT + data_to_recv) & 1) {
+                 data_to_recv++;
+            }
+
+            if (data_to_recv) {
+               read_synchronous(evnt_buff + 10, data_to_recv);
+            }
+
+            _spi_info.spi_state = eSPI_STATE_READ_EOT;
+            break;
+    }
+    return 0;
+}
+
+void cc3000_spi::set_wlan_en(uint8_t value) {
+    if (value) {
+        _wlan_en = 1;
+    } else {
+        _wlan_en = 0;
+    }
+}
+
+void cc3000_spi::WLAN_IRQHandler() {
+    if (_process_irq) {
+        if (_spi_info.spi_state == eSPI_STATE_POWERUP) {
+            // Inform HCI Layer that IRQ occured after powerup
+            _spi_info.spi_state = eSPI_STATE_INITIALIZED;
+        } else if (_spi_info.spi_state == eSPI_STATE_IDLE) {
+            _spi_info.spi_state = eSPI_STATE_READ_IRQ;
+            /* IRQ line goes low - acknowledge it */
+             _wlan_cs = 0;
+            read_synchronous(_simple_link.get_received_buffer(), 10);
+            _spi_info.spi_state = eSPI_STATE_READ_EOT;
+
+            // The header was read - continue with the payload read
+            if (!read_data_cont()) {
+                // All the data was read - finalize handling by switching to the task
+                // Trigger Rx processing
+                wlan_irq_disable();
+                _wlan_cs = 1;
+                // The magic number resides at the end of the TX/RX buffer (1 byte after the allocated size)
+                // If the magic number is overwitten - buffer overrun occurred - we will be stuck here forever!
+                uint8_t *received_buffer = _simple_link.get_received_buffer();
+                if (received_buffer[CC3000_RX_BUFFER_SIZE - 1] != CC3000_BUFFER_MAGIC_NUMBER) {
+                    while (1);
+                }
+
+                _spi_info.spi_state = eSPI_STATE_IDLE;
+                _event.received_handler(received_buffer + SPI_HEADER_SIZE);
+            }
+        } else if (_spi_info.spi_state == eSPI_STATE_WRITE_IRQ) {
+            write_synchronous(_simple_link.get_transmit_buffer(), _spi_info.tx_packet_length);
+            _spi_info.spi_state = eSPI_STATE_IDLE;
+            _wlan_cs = 1;
+        }
+    }
+}
+
+} // namespace mbed_cc3000
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/WifiRobot/cc3000/cc3000_spi.h	Tue Dec 09 05:06:37 2014 +0000
@@ -0,0 +1,251 @@
+/*****************************************************************************
+*
+*  C++ interface/implementation created by Martin Kojtal (0xc0170). Thanks to
+*  Jim Carver and Frank Vannieuwkerke for their inital cc3000 mbed port and
+*  provided help.
+*
+*  This version of "host driver" uses CC3000 Host Driver Implementation. Thus
+*  read the following copyright:
+*
+*  Copyright (C) 2011 Texas Instruments Incorporated - http://www.ti.com/
+*
+*  Redistribution and use in source and binary forms, with or without
+*  modification, are permitted provided that the following conditions
+*  are met:
+*
+*    Redistributions of source code must retain the above copyright
+*    notice, this list of conditions and the following disclaimer.
+*
+*    Redistributions in binary form must reproduce the above copyright
+*    notice, this list of conditions and the following disclaimer in the
+*    documentation and/or other materials provided with the
+*    distribution.
+*
+*    Neither the name of Texas Instruments Incorporated nor the names of
+*    its contributors may be used to endorse or promote products derived
+*    from this software without specific prior written permission.
+*
+*  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+*  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+*  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
+*  A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
+*  OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
+*  SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
+*  LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
+*  DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
+*  THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+*  (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
+*  OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+*
+*****************************************************************************/
+#ifndef CC3000_SPI_H
+#define CC3000_SPI_H
+
+typedef struct
+{
+   uint16_t tx_packet_length;
+   uint16_t rx_packet_length;
+   uint32_t spi_state;
+} tSpiInfo;
+
+
+/* ===========================================================================================
+                                              SPI
+   =========================================================================================== */
+#define READ                    3
+#define WRITE                   1
+
+#define HI(value)               (((value) & 0xFF00) >> 8)
+#define LO(value)               ((value) & 0x00FF)
+
+#define HEADERS_SIZE_EVNT    (SPI_HEADER_SIZE + 5)
+
+#define SPI_HEADER_SIZE      (5)
+
+#define  eSPI_STATE_POWERUP             (0)
+#define  eSPI_STATE_INITIALIZED         (1)
+#define  eSPI_STATE_IDLE                (2)
+#define  eSPI_STATE_WRITE_IRQ           (3)
+#define  eSPI_STATE_WRITE_FIRST_PORTION (4)
+#define  eSPI_STATE_WRITE_EOT           (5)
+#define  eSPI_STATE_READ_IRQ            (6)
+#define  eSPI_STATE_READ_FIRST_PORTION  (7)
+#define  eSPI_STATE_READ_EOT            (8)
+
+// The magic number that resides at the end of the TX/RX buffer (1 byte after the allocated size)
+// for the purpose of detection of the overrun. The location of the memory where the magic number
+// resides shall never be written. In case it is written - overrun occured and either recevie function
+// or send function will be stuck forever.
+#define CC3000_BUFFER_MAGIC_NUMBER (0xDE)
+
+/* ===========================================================================================
+                                              HCI
+   =========================================================================================== */
+
+#define SL_PATCH_PORTION_SIZE                        (1000)
+
+#define SPI_HEADER_SIZE                              (5)
+#define SIMPLE_LINK_HCI_CMND_HEADER_SIZE             (4)
+#define HEADERS_SIZE_CMD                             (SPI_HEADER_SIZE + SIMPLE_LINK_HCI_CMND_HEADER_SIZE)
+#define SIMPLE_LINK_HCI_DATA_CMND_HEADER_SIZE        (5)
+#define SIMPLE_LINK_HCI_DATA_HEADER_SIZE             (5)
+#define SIMPLE_LINK_HCI_PATCH_HEADER_SIZE            (2)
+
+// Values that can be used as HCI Commands and HCI Packet header defines
+#define  HCI_TYPE_CMND          0x1
+#define  HCI_TYPE_DATA          0x2
+#define  HCI_TYPE_PATCH         0x3
+#define  HCI_TYPE_EVNT          0x4
+
+
+#define HCI_EVENT_PATCHES_DRV_REQ             (1)
+#define HCI_EVENT_PATCHES_FW_REQ              (2)
+#define HCI_EVENT_PATCHES_BOOTLOAD_REQ        (3)
+
+
+#define  HCI_CMND_WLAN_BASE                              (0x0000)
+#define  HCI_CMND_WLAN_CONNECT                            0x0001
+#define  HCI_CMND_WLAN_DISCONNECT                         0x0002
+#define  HCI_CMND_WLAN_IOCTL_SET_SCANPARAM                0x0003
+#define  HCI_CMND_WLAN_IOCTL_SET_CONNECTION_POLICY        0x0004
+#define  HCI_CMND_WLAN_IOCTL_ADD_PROFILE                  0x0005
+#define  HCI_CMND_WLAN_IOCTL_DEL_PROFILE                  0x0006
+#define  HCI_CMND_WLAN_IOCTL_GET_SCAN_RESULTS             0x0007
+#define  HCI_CMND_EVENT_MASK                              0x0008
+#define  HCI_CMND_WLAN_IOCTL_STATUSGET                    0x0009
+#define  HCI_CMND_WLAN_IOCTL_SIMPLE_CONFIG_START          0x000A
+#define  HCI_CMND_WLAN_IOCTL_SIMPLE_CONFIG_STOP           0x000B
+#define  HCI_CMND_WLAN_IOCTL_SIMPLE_CONFIG_SET_PREFIX     0x000C
+#define  HCI_CMND_WLAN_CONFIGURE_PATCH                    0x000D
+
+
+#define  HCI_CMND_SOCKET_BASE          0x1000
+#define  HCI_CMND_SOCKET               0x1001
+#define  HCI_CMND_BIND                 0x1002
+#define  HCI_CMND_RECV                 0x1004
+#define  HCI_CMND_ACCEPT               0x1005
+#define  HCI_CMND_LISTEN               0x1006
+#define  HCI_CMND_CONNECT              0x1007
+#define  HCI_CMND_BSD_SELECT           0x1008
+#define  HCI_CMND_SETSOCKOPT           0x1009
+#define  HCI_CMND_GETSOCKOPT           0x100A
+#define  HCI_CMND_CLOSE_SOCKET         0x100B
+#define  HCI_CMND_RECVFROM             0x100D
+#define  HCI_CMND_GETHOSTNAME          0x1010
+#define  HCI_CMND_MDNS_ADVERTISE       0x1011
+
+
+#define HCI_DATA_BASE                                0x80
+
+#define HCI_CMND_SEND                               (0x01 + HCI_DATA_BASE)
+#define HCI_CMND_SENDTO                             (0x03 + HCI_DATA_BASE)
+#define HCI_DATA_BSD_RECVFROM                       (0x04 + HCI_DATA_BASE)
+#define HCI_DATA_BSD_RECV                           (0x05 + HCI_DATA_BASE)
+
+
+#define HCI_CMND_NVMEM_CBASE        (0x0200)
+
+
+#define HCI_CMND_NVMEM_CREATE_ENTRY (0x0203)
+#define HCI_CMND_NVMEM_SWAP_ENTRY   (0x0205)
+#define HCI_CMND_NVMEM_READ         (0x0201)
+#define HCI_CMND_NVMEM_WRITE        (0x0090)
+#define HCI_CMND_NVMEM_WRITE_PATCH  (0x0204)
+#define HCI_CMND_READ_SP_VERSION    (0x0207)
+
+#define  HCI_CMND_READ_BUFFER_SIZE  0x400B
+#define  HCI_CMND_SIMPLE_LINK_START 0x4000
+
+#define HCI_CMND_NETAPP_BASE        0x2000
+
+#define HCI_NETAPP_DHCP                    (0x0001 + HCI_CMND_NETAPP_BASE)
+#define HCI_NETAPP_PING_SEND               (0x0002 + HCI_CMND_NETAPP_BASE)
+#define HCI_NETAPP_PING_REPORT             (0x0003 + HCI_CMND_NETAPP_BASE)
+#define HCI_NETAPP_PING_STOP               (0x0004 + HCI_CMND_NETAPP_BASE)
+#define HCI_NETAPP_IPCONFIG                (0x0005 + HCI_CMND_NETAPP_BASE)
+#define HCI_NETAPP_ARP_FLUSH               (0x0006 + HCI_CMND_NETAPP_BASE)
+#define HCI_NETAPP_SET_DEBUG_LEVEL         (0x0008 + HCI_CMND_NETAPP_BASE)
+#define HCI_NETAPP_SET_TIMERS              (0x0009 + HCI_CMND_NETAPP_BASE)
+
+// Values that can be used as HCI Events defines
+#define  HCI_EVNT_WLAN_BASE     0x0000
+#define  HCI_EVNT_WLAN_CONNECT  0x0001
+#define  HCI_EVNT_WLAN_DISCONNECT \
+                                0x0002
+#define  HCI_EVNT_WLAN_IOCTL_ADD_PROFILE  \
+                                0x0005
+
+
+#define  HCI_EVNT_SOCKET              HCI_CMND_SOCKET
+#define  HCI_EVNT_BIND                HCI_CMND_BIND
+#define  HCI_EVNT_RECV                HCI_CMND_RECV
+#define  HCI_EVNT_ACCEPT              HCI_CMND_ACCEPT
+#define  HCI_EVNT_LISTEN              HCI_CMND_LISTEN
+#define  HCI_EVNT_CONNECT             HCI_CMND_CONNECT
+#define  HCI_EVNT_SELECT              HCI_CMND_BSD_SELECT
+#define  HCI_EVNT_CLOSE_SOCKET        HCI_CMND_CLOSE_SOCKET
+#define  HCI_EVNT_RECVFROM            HCI_CMND_RECVFROM
+#define  HCI_EVNT_SETSOCKOPT          HCI_CMND_SETSOCKOPT
+#define  HCI_EVNT_GETSOCKOPT          HCI_CMND_GETSOCKOPT
+#define  HCI_EVNT_BSD_GETHOSTBYNAME   HCI_CMND_GETHOSTNAME
+#define  HCI_EVNT_MDNS_ADVERTISE      HCI_CMND_MDNS_ADVERTISE
+
+#define  HCI_EVNT_SEND                0x1003
+#define  HCI_EVNT_WRITE               0x100E
+#define  HCI_EVNT_SENDTO              0x100F
+
+#define HCI_EVNT_PATCHES_REQ          0x1000
+
+#define HCI_EVNT_UNSOL_BASE           0x4000
+
+#define HCI_EVNT_WLAN_UNSOL_BASE     (0x8000)
+
+#define HCI_EVNT_WLAN_UNSOL_CONNECT             (0x0001 + HCI_EVNT_WLAN_UNSOL_BASE)
+#define HCI_EVNT_WLAN_UNSOL_DISCONNECT          (0x0002 + HCI_EVNT_WLAN_UNSOL_BASE)
+#define HCI_EVNT_WLAN_UNSOL_INIT                (0x0004 + HCI_EVNT_WLAN_UNSOL_BASE)
+#define HCI_EVNT_WLAN_TX_COMPLETE               (0x0008 + HCI_EVNT_WLAN_UNSOL_BASE)
+#define HCI_EVNT_WLAN_UNSOL_DHCP                (0x0010 + HCI_EVNT_WLAN_UNSOL_BASE)
+#define HCI_EVNT_WLAN_ASYNC_PING_REPORT         (0x0040 + HCI_EVNT_WLAN_UNSOL_BASE)
+#define HCI_EVNT_WLAN_ASYNC_SIMPLE_CONFIG_DONE  (0x0080 + HCI_EVNT_WLAN_UNSOL_BASE)
+#define HCI_EVNT_WLAN_KEEPALIVE                 (0x0200  + HCI_EVNT_WLAN_UNSOL_BASE)
+#define    HCI_EVNT_BSD_TCP_CLOSE_WAIT          (0x0800 + HCI_EVNT_WLAN_UNSOL_BASE)
+
+#define HCI_EVNT_DATA_UNSOL_FREE_BUFF \
+                                0x4100
+
+#define HCI_EVNT_NVMEM_CREATE_ENTRY \
+                                HCI_CMND_NVMEM_CREATE_ENTRY
+#define HCI_EVNT_NVMEM_SWAP_ENTRY HCI_CMND_NVMEM_SWAP_ENTRY
+
+#define HCI_EVNT_NVMEM_READ     HCI_CMND_NVMEM_READ
+#define HCI_EVNT_NVMEM_WRITE    (0x0202)
+
+#define HCI_EVNT_READ_SP_VERSION      \
+                HCI_CMND_READ_SP_VERSION
+
+#define  HCI_EVNT_INPROGRESS    0xFFFF
+
+
+#define HCI_DATA_RECVFROM       0x84
+#define HCI_DATA_RECV           0x85
+#define HCI_DATA_NVMEM          0x91
+
+#define HCI_EVENT_CC3000_CAN_SHUT_DOWN 0x99
+
+// Prototypes for the structures for HCI APIs.
+#define HCI_DATA_HEADER_SIZE        (5)
+#define HCI_EVENT_HEADER_SIZE       (5)
+#define HCI_DATA_CMD_HEADER_SIZE    (5)
+#define HCI_PATCH_HEADER_SIZE       (6)
+
+#define HCI_PACKET_TYPE_OFFSET      (0)
+#define HCI_PACKET_ARGSIZE_OFFSET   (2)
+#define HCI_PACKET_LENGTH_OFFSET    (3)
+
+
+#define HCI_EVENT_OPCODE_OFFSET     (1)
+#define HCI_EVENT_LENGTH_OFFSET     (3)
+#define HCI_EVENT_STATUS_OFFSET     (4)
+#define HCI_DATA_LENGTH_OFFSET      (3)
+
+#endif
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/WifiRobot/cc3000/cc3000_wlan.cpp	Tue Dec 09 05:06:37 2014 +0000
@@ -0,0 +1,658 @@
+/*****************************************************************************
+*
+*  C++ interface/implementation created by Martin Kojtal (0xc0170). Thanks to
+*  Jim Carver and Frank Vannieuwkerke for their inital cc3000 mbed port and
+*  provided help.
+*
+*  This version of "host driver" uses CC3000 Host Driver Implementation. Thus
+*  read the following copyright:
+*
+*  Copyright (C) 2011 Texas Instruments Incorporated - http://www.ti.com/
+*
+*  Redistribution and use in source and binary forms, with or without
+*  modification, are permitted provided that the following conditions
+*  are met:
+*
+*    Redistributions of source code must retain the above copyright
+*    notice, this list of conditions and the following disclaimer.
+*
+*    Redistributions in binary form must reproduce the above copyright
+*    notice, this list of conditions and the following disclaimer in the
+*    documentation and/or other materials provided with the
+*    distribution.
+*
+*    Neither the name of Texas Instruments Incorporated nor the names of
+*    its contributors may be used to endorse or promote products derived
+*    from this software without specific prior written permission.
+*
+*  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+*  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+*  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
+*  A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
+*  OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
+*  SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
+*  LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
+*  DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
+*  THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+*  (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
+*  OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+*
+*****************************************************************************/
+#include "cc3000.h"
+
+namespace mbed_cc3000 {
+
+cc3000_wlan::cc3000_wlan(cc3000_simple_link &simple_link, cc3000_event &event, cc3000_spi &spi, cc3000_hci &hci) :
+    _simple_link(simple_link), _event(event), _spi(spi), _hci(hci) {
+
+}
+
+cc3000_wlan::~cc3000_wlan() {
+
+}
+
+void cc3000_wlan::simpleLink_init_start(uint16_t patches_available_host) {
+    uint8_t *ptr;
+    uint8_t *args;
+
+    ptr = _simple_link.get_transmit_buffer();
+    args = (uint8_t *)(ptr + HEADERS_SIZE_CMD);
+
+    UINT8_TO_STREAM(args, ((patches_available_host) ? SL_PATCHES_REQUEST_FORCE_HOST : SL_PATCHES_REQUEST_DEFAULT));
+
+    // IRQ Line asserted - send HCI_CMND_SIMPLE_LINK_START to CC3000
+    _hci.command_send(HCI_CMND_SIMPLE_LINK_START, ptr, WLAN_SL_INIT_START_PARAMS_LEN);
+    _event.simplelink_wait_event(HCI_CMND_SIMPLE_LINK_START, 0);
+}
+
+void cc3000_wlan::start(uint16_t patches_available_host) {
+    uint32_t spi_irq_state;
+
+    _simple_link.set_sent_packets(0);
+    _simple_link.set_number_of_released_packets(0);
+    _simple_link.set_op_code(0);
+    _simple_link.set_number_free_buffers(0);
+    _simple_link.set_buffer_length(0);
+    _simple_link.set_buffer_size(0);
+    _simple_link.set_pending_data(0);
+    _simple_link.set_transmit_error(0);
+    _simple_link.set_data_received_flag(0);
+    _simple_link.set_buffer_size(0);
+
+    // init spi
+    _spi.open();
+    // Check the IRQ line
+    spi_irq_state = _spi.wlan_irq_read();
+    // ASIC 1273 chip enable: toggle WLAN EN line
+    _spi.set_wlan_en(WLAN_ENABLE);
+
+    if (spi_irq_state) {
+        // wait till the IRQ line goes low
+        while(_spi.wlan_irq_read() != 0);
+    } else {
+        // wait till the IRQ line goes high and then low
+        while(_spi.wlan_irq_read() == 0);
+        while(_spi.wlan_irq_read() != 0);
+    }
+    simpleLink_init_start(patches_available_host);
+
+    // Read Buffer's size and finish
+    _hci.command_send(HCI_CMND_READ_BUFFER_SIZE, _simple_link.get_transmit_buffer(), 0);
+    _event.simplelink_wait_event(HCI_CMND_READ_BUFFER_SIZE, 0);
+}
+
+
+void cc3000_wlan::stop() {
+    // ASIC 1273 chip disable
+    _spi.set_wlan_en(WLAN_DISABLE);
+
+    // Wait till IRQ line goes high
+    while(_spi.wlan_irq_read() == 0);
+
+    _spi.close();
+}
+
+
+int32_t cc3000_wlan::disconnect() {
+    int32_t ret;
+    uint8_t *ptr;
+
+    ret = EFAIL;
+    ptr = _simple_link.get_transmit_buffer();
+
+    _hci.command_send(HCI_CMND_WLAN_DISCONNECT, ptr, 0);
+
+    // Wait for command complete event
+    _event.simplelink_wait_event(HCI_CMND_WLAN_DISCONNECT, &ret);
+    errno = ret;
+
+    return ret;
+}
+
+
+int32_t cc3000_wlan::ioctl_set_connection_policy(uint32_t should_connect_to_open_ap,
+                                      uint32_t use_fast_connect,
+                                      uint32_t use_profiles) {
+    int32_t ret;
+    uint8_t *ptr;
+    uint8_t *args;
+
+    ret = EFAIL;
+    ptr = _simple_link.get_transmit_buffer();
+    args = (uint8_t *)(ptr + HEADERS_SIZE_CMD);
+
+    // Fill in HCI packet structure
+    args = UINT32_TO_STREAM(args, should_connect_to_open_ap);
+    args = UINT32_TO_STREAM(args, use_fast_connect);
+    args = UINT32_TO_STREAM(args, use_profiles);
+
+    // Initiate a HCI command
+    _hci.command_send(HCI_CMND_WLAN_IOCTL_SET_CONNECTION_POLICY, ptr, WLAN_SET_CONNECTION_POLICY_PARAMS_LEN);
+
+    // Wait for command complete event
+    _event.simplelink_wait_event(HCI_CMND_WLAN_IOCTL_SET_CONNECTION_POLICY, &ret);
+
+    return ret;
+}
+
+
+int32_t cc3000_wlan::ioctl_del_profile(uint32_t index) {
+    int32_t ret;
+    uint8_t *ptr;
+    uint8_t *args;
+
+    ptr = _simple_link.get_transmit_buffer();
+    args = (uint8_t *)(ptr + HEADERS_SIZE_CMD);
+
+    // Fill in HCI packet structure
+    args = UINT32_TO_STREAM(args, index);
+    ret = EFAIL;
+
+    // Initiate a HCI command
+    _hci.command_send(HCI_CMND_WLAN_IOCTL_DEL_PROFILE, ptr, WLAN_DEL_PROFILE_PARAMS_LEN);
+
+    // Wait for command complete event
+    _event.simplelink_wait_event(HCI_CMND_WLAN_IOCTL_DEL_PROFILE, &ret);
+
+    return ret;
+}
+
+int32_t cc3000_wlan::set_event_mask(uint32_t mask) {
+    int32_t ret;
+    uint8_t *ptr;
+    uint8_t *args;
+
+
+    if ((mask & HCI_EVNT_WLAN_TX_COMPLETE) == HCI_EVNT_WLAN_TX_COMPLETE) {
+        _simple_link.set_tx_complete_signal(0);
+
+        // Since an event is a virtual event - i.e. it is not coming from CC3000
+        // there is no need to send anything to the device if it was an only event
+        if (mask == HCI_EVNT_WLAN_TX_COMPLETE) {
+            return 0;
+        }
+
+        mask &= ~HCI_EVNT_WLAN_TX_COMPLETE;
+        mask |= HCI_EVNT_WLAN_UNSOL_BASE;
+    } else {
+        _simple_link.set_tx_complete_signal(1);
+    }
+
+    ret = EFAIL;
+    ptr = _simple_link.get_transmit_buffer();
+    args = (uint8_t *)(ptr + HEADERS_SIZE_CMD);
+
+    // Fill in HCI packet structure
+    args = UINT32_TO_STREAM(args, mask);
+
+    // Initiate a HCI command
+    _hci.command_send(HCI_CMND_EVENT_MASK, ptr, WLAN_SET_MASK_PARAMS_LEN);
+
+    // Wait for command complete event
+    _event.simplelink_wait_event(HCI_CMND_EVENT_MASK, &ret);
+
+    return ret;
+}
+
+
+int32_t cc3000_wlan::smart_config_start(uint32_t encrypted_flag) {
+    int32_t ret;
+    uint8_t *ptr;
+    uint8_t *args;
+
+    ret = EFAIL;
+    ptr = _simple_link.get_transmit_buffer();
+    args = (uint8_t *)(ptr + HEADERS_SIZE_CMD);
+
+    // Fill in HCI packet structure
+    args = UINT32_TO_STREAM(args, encrypted_flag);
+    ret = EFAIL;
+
+    _hci.command_send(HCI_CMND_WLAN_IOCTL_SIMPLE_CONFIG_START, ptr, WLAN_SMART_CONFIG_START_PARAMS_LEN);
+
+    // Wait for command complete event
+    _event.simplelink_wait_event(HCI_CMND_WLAN_IOCTL_SIMPLE_CONFIG_START, &ret);
+
+    return ret;
+}
+
+
+int32_t cc3000_wlan::smart_config_stop(void) {
+    int32_t ret;
+    uint8_t *ptr;
+
+    ret = EFAIL;
+    ptr = _simple_link.get_transmit_buffer();
+
+    _hci.command_send(HCI_CMND_WLAN_IOCTL_SIMPLE_CONFIG_STOP, ptr, 0);
+
+    // Wait for command complete event
+    _event.simplelink_wait_event(HCI_CMND_WLAN_IOCTL_SIMPLE_CONFIG_STOP, &ret);
+
+    return ret;
+}
+
+int32_t cc3000_wlan::smart_config_set_prefix(uint8_t *new_prefix) {
+    int32_t ret;
+    uint8_t *ptr;
+    uint8_t *args;
+
+    ret = EFAIL;
+    ptr = _simple_link.get_transmit_buffer();
+    args = (ptr + HEADERS_SIZE_CMD);
+
+    if (new_prefix == NULL) {
+        return ret;
+    } else {
+        // with the new Smart Config, prefix must be TTT
+        *new_prefix = 'T';
+        *(new_prefix + 1) = 'T';
+        *(new_prefix + 2) = 'T';
+    }
+
+    ARRAY_TO_STREAM(args, new_prefix, SL_SIMPLE_CONFIG_PREFIX_LENGTH);
+
+    _hci.command_send(HCI_CMND_WLAN_IOCTL_SIMPLE_CONFIG_SET_PREFIX, ptr, SL_SIMPLE_CONFIG_PREFIX_LENGTH);
+
+    // Wait for command complete event
+    _event.simplelink_wait_event(HCI_CMND_WLAN_IOCTL_SIMPLE_CONFIG_SET_PREFIX, &ret);
+
+    return ret;
+}
+
+#ifndef CC3000_TINY_DRIVER
+int32_t cc3000_wlan::connect(uint32_t sec_type, const uint8_t *ssid, int32_t ssid_len, uint8_t *bssid,
+              uint8_t *key, int32_t key_len) {
+    int32_t ret;
+    uint8_t *ptr;
+    uint8_t *args;
+    uint8_t bssid_zero[] = {0, 0, 0, 0, 0, 0};
+
+    ret      = EFAIL;
+    ptr      = _simple_link.get_transmit_buffer();
+    args     = (ptr + HEADERS_SIZE_CMD);
+
+    // Fill in command buffer
+    args = UINT32_TO_STREAM(args, 0x0000001c);
+    args = UINT32_TO_STREAM(args, ssid_len);
+    args = UINT32_TO_STREAM(args, sec_type);
+    args = UINT32_TO_STREAM(args, 0x00000010 + ssid_len);
+    args = UINT32_TO_STREAM(args, key_len);
+    args = UINT16_TO_STREAM(args, 0);
+
+    // padding shall be zeroed
+    if (bssid) {
+        ARRAY_TO_STREAM(args, bssid, ETH_ALEN);
+    } else {
+        ARRAY_TO_STREAM(args, bssid_zero, ETH_ALEN);
+    }
+
+    ARRAY_TO_STREAM(args, ssid, ssid_len);
+
+    if (key_len && key) {
+        ARRAY_TO_STREAM(args, key, key_len);
+    }
+
+    // Initiate a HCI command
+    _hci.command_send(HCI_CMND_WLAN_CONNECT, ptr, WLAN_CONNECT_PARAM_LEN + ssid_len + key_len - 1);
+
+    // Wait for command complete event
+    _event.simplelink_wait_event(HCI_CMND_WLAN_CONNECT, &ret);
+    errno = ret;
+
+    return ret;
+}
+
+int32_t cc3000_wlan::add_profile(uint32_t sec_type,
+                      uint8_t* ssid,
+                      uint32_t ssid_length,
+                      uint8_t *b_ssid,
+                      uint32_t priority,
+                      uint32_t pairwise_cipher_or_tx_key_len,
+                      uint32_t group_cipher_tx_key_index,
+                      uint32_t key_mgmt,
+                      uint8_t* pf_or_key,
+                      uint32_t pass_phrase_len) {
+    uint16_t arg_len = 0x00;
+    int32_t ret;
+    uint8_t *ptr;
+    int32_t i = 0;
+    uint8_t *args;
+    uint8_t bssid_zero[] = {0, 0, 0, 0, 0, 0};
+
+    ptr = _simple_link.get_transmit_buffer();
+    args = (ptr + HEADERS_SIZE_CMD);
+
+    args = UINT32_TO_STREAM(args, sec_type);
+
+    // Setup arguments in accordance with the security type
+    switch (sec_type)
+    {
+        //OPEN
+        case WLAN_SEC_UNSEC:
+        {
+            args = UINT32_TO_STREAM(args, 0x00000014);
+            args = UINT32_TO_STREAM(args, ssid_length);
+            args = UINT16_TO_STREAM(args, 0);
+            if(b_ssid) {
+                ARRAY_TO_STREAM(args, b_ssid, ETH_ALEN);
+            } else {
+                ARRAY_TO_STREAM(args, bssid_zero, ETH_ALEN);
+            }
+            args = UINT32_TO_STREAM(args, priority);
+            ARRAY_TO_STREAM(args, ssid, ssid_length);
+
+            arg_len = WLAN_ADD_PROFILE_NOSEC_PARAM_LEN + ssid_length;
+        }
+        break;
+
+        //WEP
+        case WLAN_SEC_WEP:
+        {
+            args = UINT32_TO_STREAM(args, 0x00000020);
+            args = UINT32_TO_STREAM(args, ssid_length);
+            args = UINT16_TO_STREAM(args, 0);
+            if (b_ssid) {
+                ARRAY_TO_STREAM(args, b_ssid, ETH_ALEN);
+            } else {
+                ARRAY_TO_STREAM(args, bssid_zero, ETH_ALEN);
+            }
+            args = UINT32_TO_STREAM(args, priority);
+            args = UINT32_TO_STREAM(args, 0x0000000C + ssid_length);
+            args = UINT32_TO_STREAM(args, pairwise_cipher_or_tx_key_len);
+            args = UINT32_TO_STREAM(args, group_cipher_tx_key_index);
+            ARRAY_TO_STREAM(args, ssid, ssid_length);
+
+            for(i = 0; i < 4; i++) {
+                uint8_t *p = &pf_or_key[i * pairwise_cipher_or_tx_key_len];
+
+                ARRAY_TO_STREAM(args, p, pairwise_cipher_or_tx_key_len);
+            }
+
+            arg_len = WLAN_ADD_PROFILE_WEP_PARAM_LEN + ssid_length +
+                pairwise_cipher_or_tx_key_len * 4;
+
+        }
+        break;
+
+        //WPA
+        //WPA2
+        case WLAN_SEC_WPA:
+        case WLAN_SEC_WPA2:
+        {
+            args = UINT32_TO_STREAM(args, 0x00000028);
+            args = UINT32_TO_STREAM(args, ssid_length);
+            args = UINT16_TO_STREAM(args, 0);
+            if (b_ssid) {
+                ARRAY_TO_STREAM(args, b_ssid, ETH_ALEN);
+            } else {
+                ARRAY_TO_STREAM(args, bssid_zero, ETH_ALEN);
+            }
+            args = UINT32_TO_STREAM(args, priority);
+            args = UINT32_TO_STREAM(args, pairwise_cipher_or_tx_key_len);
+            args = UINT32_TO_STREAM(args, group_cipher_tx_key_index);
+            args = UINT32_TO_STREAM(args, key_mgmt);
+            args = UINT32_TO_STREAM(args, 0x00000008 + ssid_length);
+            args = UINT32_TO_STREAM(args, pass_phrase_len);
+            ARRAY_TO_STREAM(args, ssid, ssid_length);
+            ARRAY_TO_STREAM(args, pf_or_key, pass_phrase_len);
+
+            arg_len = WLAN_ADD_PROFILE_WPA_PARAM_LEN + ssid_length + pass_phrase_len;
+        }
+
+        break;
+    }
+
+    // Initiate a HCI command
+    _hci.command_send(HCI_CMND_WLAN_IOCTL_ADD_PROFILE, ptr, arg_len);
+
+    // Wait for command complete event
+    _event.simplelink_wait_event(HCI_CMND_WLAN_IOCTL_ADD_PROFILE, &ret);
+
+    return ret;
+}
+
+int32_t cc3000_wlan::ioctl_get_scan_results(uint32_t scan_timeout, uint8_t *results) {
+    uint8_t *ptr;
+    uint8_t *args;
+
+    ptr = _simple_link.get_transmit_buffer();
+    args = (ptr + HEADERS_SIZE_CMD);
+
+    // Fill in temporary command buffer
+    args = UINT32_TO_STREAM(args, scan_timeout);
+
+    // Initiate a HCI command
+    _hci.command_send(HCI_CMND_WLAN_IOCTL_GET_SCAN_RESULTS, ptr, WLAN_GET_SCAN_RESULTS_PARAMS_LEN);
+
+    // Wait for command complete event
+    _event.simplelink_wait_event(HCI_CMND_WLAN_IOCTL_GET_SCAN_RESULTS, results);
+
+    return 0;
+}
+
+int32_t cc3000_wlan::ioctl_set_scan_params(uint32_t enable,
+                                uint32_t min_dwell_time,
+                                uint32_t max_dwell_time,
+                                uint32_t num_probe_requests,
+                                uint32_t channel_mask,
+                                int32_t rssi_threshold,
+                                uint32_t snr_threshold,
+                                uint32_t default_tx_power,
+                                uint32_t *interval_list) {
+    uint32_t  uiRes;
+    uint8_t *ptr;
+    uint8_t *args;
+
+    ptr = _simple_link.get_transmit_buffer();
+    args = (ptr + HEADERS_SIZE_CMD);
+
+    // Fill in temporary command buffer
+    args = UINT32_TO_STREAM(args, 36);
+    args = UINT32_TO_STREAM(args, enable);
+    args = UINT32_TO_STREAM(args, min_dwell_time);
+    args = UINT32_TO_STREAM(args, max_dwell_time);
+    args = UINT32_TO_STREAM(args, num_probe_requests);
+    args = UINT32_TO_STREAM(args, channel_mask);
+    args = UINT32_TO_STREAM(args, rssi_threshold);
+    args = UINT32_TO_STREAM(args, snr_threshold);
+    args = UINT32_TO_STREAM(args, default_tx_power);
+    ARRAY_TO_STREAM(args, interval_list, sizeof(uint32_t) * SL_SET_SCAN_PARAMS_INTERVAL_LIST_SIZE);
+
+    // Initiate a HCI command
+    _hci.command_send(HCI_CMND_WLAN_IOCTL_SET_SCANPARAM, ptr, WLAN_SET_SCAN_PARAMS_LEN);
+
+    // Wait for command complete event
+    _event.simplelink_wait_event(HCI_CMND_WLAN_IOCTL_SET_SCANPARAM, &uiRes);
+
+    return(uiRes);
+}
+
+int32_t cc3000_wlan::ioctl_statusget(void) {
+    int32_t ret;
+    uint8_t *ptr;
+
+    ret = EFAIL;
+    ptr = _simple_link.get_transmit_buffer();
+
+    _hci.command_send(HCI_CMND_WLAN_IOCTL_STATUSGET,ptr, 0);
+
+    // Wait for command complete event
+    _event.simplelink_wait_event(HCI_CMND_WLAN_IOCTL_STATUSGET, &ret);
+
+    return ret;
+}
+
+#else
+int32_t cc3000_wlan::add_profile(uint32_t sec_type,
+                      uint8_t *ssid,
+                      uint32_t ssid_length,
+                      uint8_t *b_ssid,
+                      uint32_t priority,
+                      uint32_t pairwise_cipher_or_tx_key_len,
+                      uint32_t group_cipher_tx_key_index,
+                      uint32_t key_mgmt,
+                      uint8_t* pf_or_key,
+                      uint32_t pass_phrase_length)
+{
+    return -1;
+}
+
+int32_t cc3000_wlan::connect(const uint8_t *ssid, int32_t ssid_len) {
+    int32_t ret;
+    uint8_t *ptr;
+    uint8_t *args;
+    uint8_t bssid_zero[] = {0, 0, 0, 0, 0, 0};
+
+    ret      = EFAIL;
+    ptr      = _simple_link.get_transmit_buffer();
+    args     = (ptr + HEADERS_SIZE_CMD);
+
+    // Fill in command buffer
+    args = UINT32_TO_STREAM(args, 0x0000001c);
+    args = UINT32_TO_STREAM(args, ssid_len);
+    args = UINT32_TO_STREAM(args, 0);
+    args = UINT32_TO_STREAM(args, 0x00000010 + ssid_len);
+    args = UINT32_TO_STREAM(args, 0);
+    args = UINT16_TO_STREAM(args, 0);
+
+    // padding shall be zeroed
+    ARRAY_TO_STREAM(args, bssid_zero, ETH_ALEN);
+    ARRAY_TO_STREAM(args, ssid, ssid_len);
+
+    // Initiate a HCI command
+    _hci.command_send(HCI_CMND_WLAN_CONNECT, ptr, WLAN_CONNECT_PARAM_LEN + ssid_len  - 1);
+
+    // Wait for command complete event
+    _event.simplelink_wait_event(HCI_CMND_WLAN_CONNECT, &ret);
+    errno = ret;
+
+    return ret;
+}
+#endif
+
+
+
+#ifndef CC3000_UNENCRYPTED_SMART_CONFIG
+int32_t cc3000_wlan::smart_config_process(void) {
+    int32_t  returnValue;
+    uint32_t ssidLen, keyLen;
+    uint8_t *decKeyPtr;
+    uint8_t *ssidPtr;
+
+    // read the key from EEPROM - fileID 12
+    returnValue = aes_read_key(key);
+
+    if (returnValue != 0)
+        return returnValue;
+
+    // read the received data from fileID #13 and parse it according to the followings:
+    // 1) SSID LEN - not encrypted
+    // 2) SSID - not encrypted
+    // 3) KEY LEN - not encrypted. always 32 bytes long
+    // 4) Security type - not encrypted
+    // 5) KEY - encrypted together with true key length as the first byte in KEY
+    //     to elaborate, there are two corner cases:
+    //        1) the KEY is 32 bytes long. In this case, the first byte does not represent KEY length
+    //        2) the KEY is 31 bytes long. In this case, the first byte represent KEY length and equals 31
+    returnValue = nvmem_read(NVMEM_SHARED_MEM_FILEID, SMART_CONFIG_PROFILE_SIZE, 0, profileArray);
+
+    if (returnValue != 0)
+        return returnValue;
+
+    ssidPtr = &profileArray[1];
+
+    ssidLen = profileArray[0];
+
+    decKeyPtr = &profileArray[profileArray[0] + 3];
+
+    aes_decrypt(decKeyPtr, key);
+    if (profileArray[profileArray[0] + 1] > 16)
+        aes_decrypt((uint8_t *)(decKeyPtr + 16), key);
+
+    if (*(uint8_t *)(decKeyPtr +31) != 0) {
+        if (*decKeyPtr == 31) {
+            keyLen = 31;
+            decKeyPtr++;
+        } else {
+            keyLen = 32;
+        }
+    } else {
+        keyLen = *decKeyPtr;
+        decKeyPtr++;
+    }
+
+    // add a profile
+    switch (profileArray[profileArray[0] + 2])
+    {
+    case WLAN_SEC_UNSEC://None
+         {
+            returnValue = wlan_add_profile(profileArray[profileArray[0] + 2],     // security type
+                                           ssidPtr,                               // SSID
+                                           ssidLen,                               // SSID length
+                                           NULL,                                  // BSSID
+                                           1,                                     // Priority
+                                           0, 0, 0, 0, 0);
+
+            break;
+         }
+
+    case WLAN_SEC_WEP://WEP
+        {
+            returnValue = wlan_add_profile(profileArray[profileArray[0] + 2],     // security type
+                                           ssidPtr,                               // SSID
+                                           ssidLen,                               // SSID length
+                                           NULL,                                  // BSSID
+                                           1,                                     // Priority
+                                           keyLen,                                // KEY length
+                                           0,                                     // KEY index
+                                           0,
+                                           decKeyPtr,                             // KEY
+                                           0);
+
+            break;
+        }
+
+    case WLAN_SEC_WPA:  //WPA
+    case WLAN_SEC_WPA2: //WPA2
+        {
+            returnValue = wlan_add_profile(WLAN_SEC_WPA2,     // security type
+                                           ssidPtr,
+                                           ssidLen,
+                                           NULL,              // BSSID
+                                           1,                 // Priority
+                                           0x18,              // PairwiseCipher
+                                           0x1e,              // GroupCipher
+                                           2,                 // KEY management
+                                           decKeyPtr,         // KEY
+                                           keyLen);           // KEY length
+
+            break;
+        }
+    }
+
+    return returnValue;
+}
+#endif
+
+}
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/WifiRobot/charter/charter.aux Tue Dec 09 05:06:37 2014 +0000 @@ -0,0 +1,1 @@ +\relax
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/WifiRobot/charter/charter.log	Tue Dec 09 05:06:37 2014 +0000
@@ -0,0 +1,680 @@
+This is pdfTeX, Version 3.1415926-2.5-1.40.14 (TeX Live 2013) (format=pdflatex 2013.5.30)  21 OCT 2014 18:56
+entering extended mode
+ restricted \write18 enabled.
+ %&-line parsing enabled.
+**charter.tex
+(./charter.tex
+LaTeX2e <2011/06/27>
+Babel <3.9f> and hyphenation patterns for 78 languages loaded.
+(/usr/local/texlive/2013/texmf-dist/tex/latex/base/article.cls
+Document Class: article 2007/10/19 v1.4h Standard LaTeX document class
+(/usr/local/texlive/2013/texmf-dist/tex/latex/base/size10.clo
+File: size10.clo 2007/10/19 v1.4h Standard LaTeX file (size option)
+)
+\c@part=\count79
+\c@section=\count80
+\c@subsection=\count81
+\c@subsubsection=\count82
+\c@paragraph=\count83
+\c@subparagraph=\count84
+\c@figure=\count85
+\c@table=\count86
+\abovecaptionskip=\skip41
+\belowcaptionskip=\skip42
+\bibindent=\dimen102
+)
+(/usr/local/texlive/2013/texmf-dist/tex/latex/geometry/geometry.sty
+Package: geometry 2010/09/12 v5.6 Page Geometry
+
+(/usr/local/texlive/2013/texmf-dist/tex/latex/graphics/keyval.sty
+Package: keyval 1999/03/16 v1.13 key=value parser (DPC)
+\KV@toks@=\toks14
+)
+(/usr/local/texlive/2013/texmf-dist/tex/generic/oberdiek/ifpdf.sty
+Package: ifpdf 2011/01/30 v2.3 Provides the ifpdf switch (HO)
+Package ifpdf Info: pdfTeX in PDF mode is detected.
+)
+(/usr/local/texlive/2013/texmf-dist/tex/generic/oberdiek/ifvtex.sty
+Package: ifvtex 2010/03/01 v1.5 Detect VTeX and its facilities (HO)
+Package ifvtex Info: VTeX not detected.
+)
+(/usr/local/texlive/2013/texmf-dist/tex/generic/ifxetex/ifxetex.sty
+Package: ifxetex 2010/09/12 v0.6 Provides ifxetex conditional
+)
+\Gm@cnth=\count87
+\Gm@cntv=\count88
+\c@Gm@tempcnt=\count89
+\Gm@bindingoffset=\dimen103
+\Gm@wd@mp=\dimen104
+\Gm@odd@mp=\dimen105
+\Gm@even@mp=\dimen106
+\Gm@layoutwidth=\dimen107
+\Gm@layoutheight=\dimen108
+\Gm@layouthoffset=\dimen109
+\Gm@layoutvoffset=\dimen110
+\Gm@dimlist=\toks15
+)
+(/usr/local/texlive/2013/texmf-dist/tex/latex/amsmath/amsmath.sty
+Package: amsmath 2013/01/14 v2.14 AMS math features
+\@mathmargin=\skip43
+
+For additional information on amsmath, use the `?' option.
+(/usr/local/texlive/2013/texmf-dist/tex/latex/amsmath/amstext.sty
+Package: amstext 2000/06/29 v2.01
+
+(/usr/local/texlive/2013/texmf-dist/tex/latex/amsmath/amsgen.sty
+File: amsgen.sty 1999/11/30 v2.0
+\@emptytoks=\toks16
+\ex@=\dimen111
+))
+(/usr/local/texlive/2013/texmf-dist/tex/latex/amsmath/amsbsy.sty
+Package: amsbsy 1999/11/29 v1.2d
+\pmbraise@=\dimen112
+)
+(/usr/local/texlive/2013/texmf-dist/tex/latex/amsmath/amsopn.sty
+Package: amsopn 1999/12/14 v2.01 operator names
+)
+\inf@bad=\count90
+LaTeX Info: Redefining \frac on input line 210.
+\uproot@=\count91
+\leftroot@=\count92
+LaTeX Info: Redefining \overline on input line 306.
+\classnum@=\count93
+\DOTSCASE@=\count94
+LaTeX Info: Redefining \ldots on input line 378.
+LaTeX Info: Redefining \dots on input line 381.
+LaTeX Info: Redefining \cdots on input line 466.
+\Mathstrutbox@=\box26
+\strutbox@=\box27
+\big@size=\dimen113
+LaTeX Font Info:    Redeclaring font encoding OML on input line 566.
+LaTeX Font Info:    Redeclaring font encoding OMS on input line 567.
+\macc@depth=\count95
+\c@MaxMatrixCols=\count96
+\dotsspace@=\muskip10
+\c@parentequation=\count97
+\dspbrk@lvl=\count98
+\tag@help=\toks17
+\row@=\count99
+\column@=\count100
+\maxfields@=\count101
+\andhelp@=\toks18
+\eqnshift@=\dimen114
+\alignsep@=\dimen115
+\tagshift@=\dimen116
+\tagwidth@=\dimen117
+\totwidth@=\dimen118
+\lineht@=\dimen119
+\@envbody=\toks19
+\multlinegap=\skip44
+\multlinetaggap=\skip45
+\mathdisplay@stack=\toks20
+LaTeX Info: Redefining \[ on input line 2665.
+LaTeX Info: Redefining \] on input line 2666.
+)
+(/usr/local/texlive/2013/texmf-dist/tex/latex/amsfonts/amssymb.sty
+Package: amssymb 2013/01/14 v3.01 AMS font symbols
+
+(/usr/local/texlive/2013/texmf-dist/tex/latex/amsfonts/amsfonts.sty
+Package: amsfonts 2013/01/14 v3.01 Basic AMSFonts support
+\symAMSa=\mathgroup4
+\symAMSb=\mathgroup5
+LaTeX Font Info:    Overwriting math alphabet `\mathfrak' in version `bold'
+(Font)                  U/euf/m/n --> U/euf/b/n on input line 106.
+))
+(/usr/local/texlive/2013/texmf-dist/tex/latex/amscls/amsthm.sty
+Package: amsthm 2004/08/06 v2.20
+\thm@style=\toks21
+\thm@bodyfont=\toks22
+\thm@headfont=\toks23
+\thm@notefont=\toks24
+\thm@headpunct=\toks25
+\thm@preskip=\skip46
+\thm@postskip=\skip47
+\thm@headsep=\skip48
+\dth@everypar=\toks26
+)
+(/usr/local/texlive/2013/texmf-dist/tex/latex/tools/enumerate.sty
+Package: enumerate 1999/03/05 v3.00 enumerate extensions (DPC)
+\@enLab=\toks27
+)
+(/usr/local/texlive/2013/texmf-dist/tex/latex/listings/listings.sty
+\lst@mode=\count102
+\lst@gtempboxa=\box28
+\lst@token=\toks28
+\lst@length=\count103
+\lst@currlwidth=\dimen120
+\lst@column=\count104
+\lst@pos=\count105
+\lst@lostspace=\dimen121
+\lst@width=\dimen122
+\lst@newlines=\count106
+\lst@lineno=\count107
+\lst@maxwidth=\dimen123
+
+(/usr/local/texlive/2013/texmf-dist/tex/latex/listings/lstmisc.sty
+File: lstmisc.sty 2007/02/22 1.4 (Carsten Heinz)
+\c@lstnumber=\count108
+\lst@skipnumbers=\count109
+\lst@framebox=\box29
+)
+(/usr/local/texlive/2013/texmf-dist/tex/latex/listings/listings.cfg
+File: listings.cfg 2007/02/22 1.4 listings configuration
+))
+Package: listings 2007/02/22 1.4 (Carsten Heinz)
+
+(/usr/local/texlive/2013/texmf-dist/tex/latex/pgf/frontendlayer/tikz.sty
+(/usr/local/texlive/2013/texmf-dist/tex/latex/pgf/basiclayer/pgf.sty
+(/usr/local/texlive/2013/texmf-dist/tex/latex/pgf/utilities/pgfrcs.sty
+(/usr/local/texlive/2013/texmf-dist/tex/generic/pgf/utilities/pgfutil-common.te
+x
+\pgfutil@everybye=\toks29
+)
+(/usr/local/texlive/2013/texmf-dist/tex/generic/pgf/utilities/pgfutil-latex.def
+\pgfutil@abb=\box30
+(/usr/local/texlive/2013/texmf-dist/tex/latex/ms/everyshi.sty
+Package: everyshi 2001/05/15 v3.00 EveryShipout Package (MS)
+))
+(/usr/local/texlive/2013/texmf-dist/tex/generic/pgf/utilities/pgfrcs.code.tex
+Package: pgfrcs 2010/10/25 v2.10 (rcs-revision 1.24)
+))
+Package: pgf 2008/01/15 v2.10 (rcs-revision 1.12)
+(/usr/local/texlive/2013/texmf-dist/tex/latex/pgf/basiclayer/pgfcore.sty
+(/usr/local/texlive/2013/texmf-dist/tex/latex/graphics/graphicx.sty
+Package: graphicx 1999/02/16 v1.0f Enhanced LaTeX Graphics (DPC,SPQR)
+
+(/usr/local/texlive/2013/texmf-dist/tex/latex/graphics/graphics.sty
+Package: graphics 2009/02/05 v1.0o Standard LaTeX Graphics (DPC,SPQR)
+
+(/usr/local/texlive/2013/texmf-dist/tex/latex/graphics/trig.sty
+Package: trig 1999/03/16 v1.09 sin cos tan (DPC)
+)
+(/usr/local/texlive/2013/texmf-dist/tex/latex/latexconfig/graphics.cfg
+File: graphics.cfg 2010/04/23 v1.9 graphics configuration of TeX Live
+)
+Package graphics Info: Driver file: pdftex.def on input line 91.
+
+(/usr/local/texlive/2013/texmf-dist/tex/latex/pdftex-def/pdftex.def
+File: pdftex.def 2011/05/27 v0.06d Graphics/color for pdfTeX
+
+(/usr/local/texlive/2013/texmf-dist/tex/generic/oberdiek/infwarerr.sty
+Package: infwarerr 2010/04/08 v1.3 Providing info/warning/error messages (HO)
+)
+(/usr/local/texlive/2013/texmf-dist/tex/generic/oberdiek/ltxcmds.sty
+Package: ltxcmds 2011/11/09 v1.22 LaTeX kernel commands for general use (HO)
+)
+\Gread@gobject=\count110
+))
+\Gin@req@height=\dimen124
+\Gin@req@width=\dimen125
+)
+(/usr/local/texlive/2013/texmf-dist/tex/latex/pgf/systemlayer/pgfsys.sty
+(/usr/local/texlive/2013/texmf-dist/tex/generic/pgf/systemlayer/pgfsys.code.tex
+Package: pgfsys 2010/06/30 v2.10 (rcs-revision 1.37)
+(/usr/local/texlive/2013/texmf-dist/tex/generic/pgf/utilities/pgfkeys.code.tex
+\pgfkeys@pathtoks=\toks30
+\pgfkeys@temptoks=\toks31
+
+(/usr/local/texlive/2013/texmf-dist/tex/generic/pgf/utilities/pgfkeysfiltered.c
+ode.tex
+\pgfkeys@tmptoks=\toks32
+))
+\pgf@x=\dimen126
+\pgf@y=\dimen127
+\pgf@xa=\dimen128
+\pgf@ya=\dimen129
+\pgf@xb=\dimen130
+\pgf@yb=\dimen131
+\pgf@xc=\dimen132
+\pgf@yc=\dimen133
+\w@pgf@writea=\write3
+\r@pgf@reada=\read1
+\c@pgf@counta=\count111
+\c@pgf@countb=\count112
+\c@pgf@countc=\count113
+\c@pgf@countd=\count114
+
+(/usr/local/texlive/2013/texmf-dist/tex/generic/pgf/systemlayer/pgf.cfg
+File: pgf.cfg 2008/05/14  (rcs-revision 1.7)
+)
+Package pgfsys Info: Driver file for pgf: pgfsys-pdftex.def on input line 900.
+
+(/usr/local/texlive/2013/texmf-dist/tex/generic/pgf/systemlayer/pgfsys-pdftex.d
+ef
+File: pgfsys-pdftex.def 2009/05/22  (rcs-revision 1.26)
+
+(/usr/local/texlive/2013/texmf-dist/tex/generic/pgf/systemlayer/pgfsys-common-p
+df.def
+File: pgfsys-common-pdf.def 2008/05/19  (rcs-revision 1.10)
+)))
+(/usr/local/texlive/2013/texmf-dist/tex/generic/pgf/systemlayer/pgfsyssoftpath.
+code.tex
+File: pgfsyssoftpath.code.tex 2008/07/18  (rcs-revision 1.7)
+\pgfsyssoftpath@smallbuffer@items=\count115
+\pgfsyssoftpath@bigbuffer@items=\count116
+)
+(/usr/local/texlive/2013/texmf-dist/tex/generic/pgf/systemlayer/pgfsysprotocol.
+code.tex
+File: pgfsysprotocol.code.tex 2006/10/16  (rcs-revision 1.4)
+)) (/usr/local/texlive/2013/texmf-dist/tex/latex/xcolor/xcolor.sty
+Package: xcolor 2007/01/21 v2.11 LaTeX color extensions (UK)
+
+(/usr/local/texlive/2013/texmf-dist/tex/latex/latexconfig/color.cfg
+File: color.cfg 2007/01/18 v1.5 color configuration of teTeX/TeXLive
+)
+Package xcolor Info: Driver file: pdftex.def on input line 225.
+Package xcolor Info: Model `cmy' substituted by `cmy0' on input line 1337.
+Package xcolor Info: Model `hsb' substituted by `rgb' on input line 1341.
+Package xcolor Info: Model `RGB' extended on input line 1353.
+Package xcolor Info: Model `HTML' substituted by `rgb' on input line 1355.
+Package xcolor Info: Model `Hsb' substituted by `hsb' on input line 1356.
+Package xcolor Info: Model `tHsb' substituted by `hsb' on input line 1357.
+Package xcolor Info: Model `HSB' substituted by `hsb' on input line 1358.
+Package xcolor Info: Model `Gray' substituted by `gray' on input line 1359.
+Package xcolor Info: Model `wave' substituted by `hsb' on input line 1360.
+)
+(/usr/local/texlive/2013/texmf-dist/tex/generic/pgf/basiclayer/pgfcore.code.tex
+Package: pgfcore 2010/04/11 v2.10 (rcs-revision 1.7)
+(/usr/local/texlive/2013/texmf-dist/tex/generic/pgf/math/pgfmath.code.tex
+(/usr/local/texlive/2013/texmf-dist/tex/generic/pgf/math/pgfmathcalc.code.tex
+(/usr/local/texlive/2013/texmf-dist/tex/generic/pgf/math/pgfmathutil.code.tex)
+(/usr/local/texlive/2013/texmf-dist/tex/generic/pgf/math/pgfmathparser.code.tex
+\pgfmath@dimen=\dimen134
+\pgfmath@count=\count117
+\pgfmath@box=\box31
+\pgfmath@toks=\toks33
+\pgfmath@stack@operand=\toks34
+\pgfmath@stack@operation=\toks35
+)
+(/usr/local/texlive/2013/texmf-dist/tex/generic/pgf/math/pgfmathfunctions.code.
+tex
+(/usr/local/texlive/2013/texmf-dist/tex/generic/pgf/math/pgfmathfunctions.basic
+.code.tex)
+(/usr/local/texlive/2013/texmf-dist/tex/generic/pgf/math/pgfmathfunctions.trigo
+nometric.code.tex)
+(/usr/local/texlive/2013/texmf-dist/tex/generic/pgf/math/pgfmathfunctions.rando
+m.code.tex)
+(/usr/local/texlive/2013/texmf-dist/tex/generic/pgf/math/pgfmathfunctions.compa
+rison.code.tex)
+(/usr/local/texlive/2013/texmf-dist/tex/generic/pgf/math/pgfmathfunctions.base.
+code.tex)
+(/usr/local/texlive/2013/texmf-dist/tex/generic/pgf/math/pgfmathfunctions.round
+.code.tex)
+(/usr/local/texlive/2013/texmf-dist/tex/generic/pgf/math/pgfmathfunctions.misc.
+code.tex)))
+(/usr/local/texlive/2013/texmf-dist/tex/generic/pgf/math/pgfmathfloat.code.tex
+\c@pgfmathroundto@lastzeros=\count118
+))
+(/usr/local/texlive/2013/texmf-dist/tex/generic/pgf/basiclayer/pgfcorepoints.co
+de.tex
+File: pgfcorepoints.code.tex 2010/04/09  (rcs-revision 1.20)
+\pgf@picminx=\dimen135
+\pgf@picmaxx=\dimen136
+\pgf@picminy=\dimen137
+\pgf@picmaxy=\dimen138
+\pgf@pathminx=\dimen139
+\pgf@pathmaxx=\dimen140
+\pgf@pathminy=\dimen141
+\pgf@pathmaxy=\dimen142
+\pgf@xx=\dimen143
+\pgf@xy=\dimen144
+\pgf@yx=\dimen145
+\pgf@yy=\dimen146
+\pgf@zx=\dimen147
+\pgf@zy=\dimen148
+)
+(/usr/local/texlive/2013/texmf-dist/tex/generic/pgf/basiclayer/pgfcorepathconst
+ruct.code.tex
+File: pgfcorepathconstruct.code.tex 2010/08/03  (rcs-revision 1.24)
+\pgf@path@lastx=\dimen149
+\pgf@path@lasty=\dimen150
+)
+(/usr/local/texlive/2013/texmf-dist/tex/generic/pgf/basiclayer/pgfcorepathusage
+.code.tex
+File: pgfcorepathusage.code.tex 2008/04/22  (rcs-revision 1.12)
+\pgf@shorten@end@additional=\dimen151
+\pgf@shorten@start@additional=\dimen152
+)
+(/usr/local/texlive/2013/texmf-dist/tex/generic/pgf/basiclayer/pgfcorescopes.co
+de.tex
+File: pgfcorescopes.code.tex 2010/09/08  (rcs-revision 1.34)
+\pgfpic=\box32
+\pgf@hbox=\box33
+\pgf@layerbox@main=\box34
+\pgf@picture@serial@count=\count119
+)
+(/usr/local/texlive/2013/texmf-dist/tex/generic/pgf/basiclayer/pgfcoregraphicst
+ate.code.tex
+File: pgfcoregraphicstate.code.tex 2008/04/22  (rcs-revision 1.9)
+\pgflinewidth=\dimen153
+)
+(/usr/local/texlive/2013/texmf-dist/tex/generic/pgf/basiclayer/pgfcoretransform
+ations.code.tex
+File: pgfcoretransformations.code.tex 2009/06/10  (rcs-revision 1.11)
+\pgf@pt@x=\dimen154
+\pgf@pt@y=\dimen155
+\pgf@pt@temp=\dimen156
+)
+(/usr/local/texlive/2013/texmf-dist/tex/generic/pgf/basiclayer/pgfcorequick.cod
+e.tex
+File: pgfcorequick.code.tex 2008/10/09  (rcs-revision 1.3)
+)
+(/usr/local/texlive/2013/texmf-dist/tex/generic/pgf/basiclayer/pgfcoreobjects.c
+ode.tex
+File: pgfcoreobjects.code.tex 2006/10/11  (rcs-revision 1.2)
+)
+(/usr/local/texlive/2013/texmf-dist/tex/generic/pgf/basiclayer/pgfcorepathproce
+ssing.code.tex
+File: pgfcorepathprocessing.code.tex 2008/10/09  (rcs-revision 1.8)
+)
+(/usr/local/texlive/2013/texmf-dist/tex/generic/pgf/basiclayer/pgfcorearrows.co
+de.tex
+File: pgfcorearrows.code.tex 2008/04/23  (rcs-revision 1.11)
+)
+(/usr/local/texlive/2013/texmf-dist/tex/generic/pgf/basiclayer/pgfcoreshade.cod
+e.tex
+File: pgfcoreshade.code.tex 2008/11/23  (rcs-revision 1.13)
+\pgf@max=\dimen157
+\pgf@sys@shading@range@num=\count120
+)
+(/usr/local/texlive/2013/texmf-dist/tex/generic/pgf/basiclayer/pgfcoreimage.cod
+e.tex
+File: pgfcoreimage.code.tex 2010/03/25  (rcs-revision 1.16)
+
+(/usr/local/texlive/2013/texmf-dist/tex/generic/pgf/basiclayer/pgfcoreexternal.
+code.tex
+File: pgfcoreexternal.code.tex 2010/09/01  (rcs-revision 1.17)
+\pgfexternal@startupbox=\box35
+))
+(/usr/local/texlive/2013/texmf-dist/tex/generic/pgf/basiclayer/pgfcorelayers.co
+de.tex
+File: pgfcorelayers.code.tex 2010/08/27  (rcs-revision 1.2)
+)
+(/usr/local/texlive/2013/texmf-dist/tex/generic/pgf/basiclayer/pgfcoretranspare
+ncy.code.tex
+File: pgfcoretransparency.code.tex 2008/01/17  (rcs-revision 1.2)
+)
+(/usr/local/texlive/2013/texmf-dist/tex/generic/pgf/basiclayer/pgfcorepatterns.
+code.tex
+File: pgfcorepatterns.code.tex 2009/07/02  (rcs-revision 1.3)
+)))
+(/usr/local/texlive/2013/texmf-dist/tex/generic/pgf/modules/pgfmoduleshapes.cod
+e.tex
+File: pgfmoduleshapes.code.tex 2010/09/09  (rcs-revision 1.13)
+\pgfnodeparttextbox=\box36
+)
+(/usr/local/texlive/2013/texmf-dist/tex/generic/pgf/modules/pgfmoduleplot.code.
+tex
+File: pgfmoduleplot.code.tex 2010/10/22  (rcs-revision 1.8)
+)
+(/usr/local/texlive/2013/texmf-dist/tex/latex/pgf/compatibility/pgfcomp-version
+-0-65.sty
+Package: pgfcomp-version-0-65 2007/07/03 v2.10 (rcs-revision 1.7)
+\pgf@nodesepstart=\dimen158
+\pgf@nodesepend=\dimen159
+)
+(/usr/local/texlive/2013/texmf-dist/tex/latex/pgf/compatibility/pgfcomp-version
+-1-18.sty
+Package: pgfcomp-version-1-18 2007/07/23 v2.10 (rcs-revision 1.1)
+))
+(/usr/local/texlive/2013/texmf-dist/tex/latex/pgf/utilities/pgffor.sty
+(/usr/local/texlive/2013/texmf-dist/tex/latex/pgf/utilities/pgfkeys.sty
+(/usr/local/texlive/2013/texmf-dist/tex/generic/pgf/utilities/pgfkeys.code.tex)
+) (/usr/local/texlive/2013/texmf-dist/tex/generic/pgf/utilities/pgffor.code.tex
+Package: pgffor 2010/03/23 v2.10 (rcs-revision 1.18)
+\pgffor@iter=\dimen160
+\pgffor@skip=\dimen161
+\pgffor@stack=\toks36
+\pgffor@toks=\toks37
+))
+(/usr/local/texlive/2013/texmf-dist/tex/generic/pgf/frontendlayer/tikz/tikz.cod
+e.tex
+Package: tikz 2010/10/13 v2.10 (rcs-revision 1.76)
+
+(/usr/local/texlive/2013/texmf-dist/tex/generic/pgf/libraries/pgflibraryplothan
+dlers.code.tex
+File: pgflibraryplothandlers.code.tex 2010/05/31 v2.10 (rcs-revision 1.15)
+\pgf@plot@mark@count=\count121
+\pgfplotmarksize=\dimen162
+)
+\tikz@lastx=\dimen163
+\tikz@lasty=\dimen164
+\tikz@lastxsaved=\dimen165
+\tikz@lastysaved=\dimen166
+\tikzleveldistance=\dimen167
+\tikzsiblingdistance=\dimen168
+\tikz@figbox=\box37
+\tikz@tempbox=\box38
+\tikztreelevel=\count122
+\tikznumberofchildren=\count123
+\tikznumberofcurrentchild=\count124
+\tikz@fig@count=\count125
+
+(/usr/local/texlive/2013/texmf-dist/tex/generic/pgf/modules/pgfmodulematrix.cod
+e.tex
+File: pgfmodulematrix.code.tex 2010/08/24  (rcs-revision 1.4)
+\pgfmatrixcurrentrow=\count126
+\pgfmatrixcurrentcolumn=\count127
+\pgf@matrix@numberofcolumns=\count128
+)
+\tikz@expandcount=\count129
+
+(/usr/local/texlive/2013/texmf-dist/tex/generic/pgf/frontendlayer/tikz/librarie
+s/tikzlibrarytopaths.code.tex
+File: tikzlibrarytopaths.code.tex 2008/06/17 v2.10 (rcs-revision 1.2)
+)))
+(/usr/local/texlive/2013/texmf-dist/tex/latex/psnfss/courier.sty
+Package: courier 2005/04/12 PSNFSS-v9.2a (WaS) 
+)
+(/usr/local/texlive/2013/texmf-dist/tex/latex/mh/mathtools.sty
+Package: mathtools 2013/02/12 v1.13 mathematical typesetting tools
+
+(/usr/local/texlive/2013/texmf-dist/tex/latex/tools/calc.sty
+Package: calc 2007/08/22 v4.3 Infix arithmetic (KKT,FJ)
+\calc@Acount=\count130
+\calc@Bcount=\count131
+\calc@Adimen=\dimen169
+\calc@Bdimen=\dimen170
+\calc@Askip=\skip49
+\calc@Bskip=\skip50
+LaTeX Info: Redefining \setlength on input line 76.
+LaTeX Info: Redefining \addtolength on input line 77.
+\calc@Ccount=\count132
+\calc@Cskip=\skip51
+)
+(/usr/local/texlive/2013/texmf-dist/tex/latex/mh/mhsetup.sty
+Package: mhsetup 2010/01/21 v1.2a programming setup (MH)
+)
+LaTeX Info: Thecontrolsequence`\['isalreadyrobust on input line 129.
+LaTeX Info: Thecontrolsequence`\]'isalreadyrobust on input line 129.
+\g_MT_multlinerow_int=\count133
+\l_MT_multwidth_dim=\dimen171
+\origjot=\skip52
+\l_MT_shortvdotswithinadjustabove_dim=\dimen172
+\l_MT_shortvdotswithinadjustbelow_dim=\dimen173
+\l_MT_above_intertext_sep=\dimen174
+\l_MT_below_intertext_sep=\dimen175
+\l_MT_above_shortintertext_sep=\dimen176
+\l_MT_below_shortintertext_sep=\dimen177
+)
+(/usr/local/texlive/2013/texmf-dist/tex/latex/listings/lstlang1.sty
+File: lstlang1.sty 2004/09/05 1.3 listings language file
+)
+(/usr/local/texlive/2013/texmf-dist/tex/latex/listings/lstlang2.sty
+File: lstlang2.sty 2004/09/05 1.3 listings language file
+)
+(/usr/local/texlive/2013/texmf-dist/tex/latex/listings/lstlang3.sty
+File: lstlang3.sty 2004/09/05 1.3 listings language file
+)
+(/usr/local/texlive/2013/texmf-dist/tex/latex/listings/lstlang1.sty
+File: lstlang1.sty 2004/09/05 1.3 listings language file
+)
+(/usr/local/texlive/2013/texmf-dist/tex/latex/listings/lstlang2.sty
+File: lstlang2.sty 2004/09/05 1.3 listings language file
+)
+(/usr/local/texlive/2013/texmf-dist/tex/latex/listings/lstlang3.sty
+File: lstlang3.sty 2004/09/05 1.3 listings language file
+)
+(/usr/local/texlive/2013/texmf-dist/tex/latex/listings/lstlang1.sty
+File: lstlang1.sty 2004/09/05 1.3 listings language file
+)
+(/usr/local/texlive/2013/texmf-dist/tex/latex/listings/lstlang2.sty
+File: lstlang2.sty 2004/09/05 1.3 listings language file
+)
+(/usr/local/texlive/2013/texmf-dist/tex/latex/listings/lstlang3.sty
+File: lstlang3.sty 2004/09/05 1.3 listings language file
+)
+(/usr/local/texlive/2013/texmf-dist/tex/latex/listings/lstmisc.sty
+File: lstmisc.sty 2007/02/22 1.4 (Carsten Heinz)
+)
+(./charter.aux)
+\openout1 = `charter.aux'.
+
+LaTeX Font Info:    Checking defaults for OML/cmm/m/it on input line 22.
+LaTeX Font Info:    ... okay on input line 22.
+LaTeX Font Info:    Checking defaults for T1/cmr/m/n on input line 22.
+LaTeX Font Info:    ... okay on input line 22.
+LaTeX Font Info:    Checking defaults for OT1/cmr/m/n on input line 22.
+LaTeX Font Info:    ... okay on input line 22.
+LaTeX Font Info:    Checking defaults for OMS/cmsy/m/n on input line 22.
+LaTeX Font Info:    ... okay on input line 22.
+LaTeX Font Info:    Checking defaults for OMX/cmex/m/n on input line 22.
+LaTeX Font Info:    ... okay on input line 22.
+LaTeX Font Info:    Checking defaults for U/cmr/m/n on input line 22.
+LaTeX Font Info:    ... okay on input line 22.
+
+*geometry* driver: auto-detecting
+*geometry* detected driver: pdftex
+*geometry* verbose mode - [ preamble ] result:
+* driver: pdftex
+* paper: letterpaper
+* layout: <same size as paper>
+* layoutoffset:(h,v)=(0.0pt,0.0pt)
+* modes: 
+* h-part:(L,W,R)=(72.26999pt, 469.75502pt, 72.26999pt)
+* v-part:(T,H,B)=(72.26999pt, 650.43001pt, 72.26999pt)
+* \paperwidth=614.295pt
+* \paperheight=794.96999pt
+* \textwidth=469.75502pt
+* \textheight=650.43001pt
+* \oddsidemargin=0.0pt
+* \evensidemargin=0.0pt
+* \topmargin=-37.0pt
+* \headheight=12.0pt
+* \headsep=25.0pt
+* \topskip=10.0pt
+* \footskip=30.0pt
+* \marginparwidth=65.0pt
+* \marginparsep=11.0pt
+* \columnsep=10.0pt
+* \skip\footins=9.0pt plus 4.0pt minus 2.0pt
+* \hoffset=0.0pt
+* \voffset=0.0pt
+* \mag=1000
+* \@twocolumnfalse
+* \@twosidefalse
+* \@mparswitchfalse
+* \@reversemarginfalse
+* (1in=72.27pt=25.4mm, 1cm=28.453pt)
+
+\c@lstlisting=\count134
+ABD: EveryShipout initializing macros
+(/usr/local/texlive/2013/texmf-dist/tex/context/base/supp-pdf.mkii
+[Loading MPS to PDF converter (version 2006.09.02).]
+\scratchcounter=\count135
+\scratchdimen=\dimen178
+\scratchbox=\box39
+\nofMPsegments=\count136
+\nofMParguments=\count137
+\everyMPshowfont=\toks38
+\MPscratchCnt=\count138
+\MPscratchDim=\dimen179
+\MPnumerator=\count139
+\makeMPintoPDFobject=\count140
+\everyMPtoPDFconversion=\toks39
+) (/usr/local/texlive/2013/texmf-dist/tex/generic/oberdiek/pdftexcmds.sty
+Package: pdftexcmds 2011/11/29 v0.20 Utility functions of pdfTeX for LuaTeX (HO
+)
+
+(/usr/local/texlive/2013/texmf-dist/tex/generic/oberdiek/ifluatex.sty
+Package: ifluatex 2010/03/01 v1.3 Provides the ifluatex switch (HO)
+Package ifluatex Info: LuaTeX not detected.
+)
+Package pdftexcmds Info: LuaTeX not detected.
+Package pdftexcmds Info: \pdf@primitive is available.
+Package pdftexcmds Info: \pdf@ifprimitive is available.
+Package pdftexcmds Info: \pdfdraftmode found.
+)
+(/usr/local/texlive/2013/texmf-dist/tex/latex/oberdiek/epstopdf-base.sty
+Package: epstopdf-base 2010/02/09 v2.5 Base part for package epstopdf
+
+(/usr/local/texlive/2013/texmf-dist/tex/latex/oberdiek/grfext.sty
+Package: grfext 2010/08/19 v1.1 Manage graphics extensions (HO)
+
+(/usr/local/texlive/2013/texmf-dist/tex/generic/oberdiek/kvdefinekeys.sty
+Package: kvdefinekeys 2011/04/07 v1.3 Define keys (HO)
+))
+(/usr/local/texlive/2013/texmf-dist/tex/latex/oberdiek/kvoptions.sty
+Package: kvoptions 2011/06/30 v3.11 Key value format for package options (HO)
+
+(/usr/local/texlive/2013/texmf-dist/tex/generic/oberdiek/kvsetkeys.sty
+Package: kvsetkeys 2012/04/25 v1.16 Key value parser (HO)
+
+(/usr/local/texlive/2013/texmf-dist/tex/generic/oberdiek/etexcmds.sty
+Package: etexcmds 2011/02/16 v1.5 Avoid name clashes with e-TeX commands (HO)
+Package etexcmds Info: Could not find \expanded.
+(etexcmds)             That can mean that you are not using pdfTeX 1.50 or
+(etexcmds)             that some package has redefined \expanded.
+(etexcmds)             In the latter case, load this package earlier.
+)))
+Package grfext Info: Graphics extension search list:
+(grfext)             [.png,.pdf,.jpg,.mps,.jpeg,.jbig2,.jb2,.PNG,.PDF,.JPG,.JPE
+G,.JBIG2,.JB2,.eps]
+(grfext)             \AppendGraphicsExtensions on input line 452.
+
+(/usr/local/texlive/2013/texmf-dist/tex/latex/latexconfig/epstopdf-sys.cfg
+File: epstopdf-sys.cfg 2010/07/13 v1.3 Configuration of (r)epstopdf for TeX Liv
+e
+))
+LaTeX Font Info:    Try loading font information for U+msa on input line 27.
+
+(/usr/local/texlive/2013/texmf-dist/tex/latex/amsfonts/umsa.fd
+File: umsa.fd 2013/01/14 v3.01 AMS symbols A
+)
+LaTeX Font Info:    Try loading font information for U+msb on input line 27.
+
+(/usr/local/texlive/2013/texmf-dist/tex/latex/amsfonts/umsb.fd
+File: umsb.fd 2013/01/14 v3.01 AMS symbols B
+)
+LaTeX Font Info:    Try loading font information for OMS+cmr on input line 46.
+
+(/usr/local/texlive/2013/texmf-dist/tex/latex/base/omscmr.fd
+File: omscmr.fd 1999/05/25 v2.5h Standard LaTeX font definitions
+)
+LaTeX Font Info:    Font shape `OMS/cmr/m/n' in size <10> not available
+(Font)              Font shape `OMS/cmsy/m/n' tried instead on input line 46.
+ [1
+
+{/usr/local/texlive/2013/texmf-var/fonts/map/pdftex/updmap/pdftex.map}] [2] (./
+charter.aux) ) 
+Here is how much of TeX's memory you used:
+ 13061 strings out of 493315
+ 236415 string characters out of 6137904
+ 330959 words of memory out of 5000000
+ 16226 multiletter control sequences out of 15000+600000
+ 8891 words of font info for 34 fonts, out of 8000000 for 9000
+ 957 hyphenation exceptions out of 8191
+ 56i,6n,67p,594b,219s stack positions out of 5000i,500n,10000p,200000b,80000s
+</usr/local/texlive/2013/texmf-dist/fonts/type1/public/amsfonts/c
+m/cmbx12.pfb></usr/local/texlive/2013/texmf-dist/fonts/type1/public/amsfonts/cm
+/cmr10.pfb></usr/local/texlive/2013/texmf-dist/fonts/type1/public/amsfonts/cm/c
+mr12.pfb></usr/local/texlive/2013/texmf-dist/fonts/type1/public/amsfonts/cm/cmr
+17.pfb></usr/local/texlive/2013/texmf-dist/fonts/type1/public/amsfonts/cm/cmsy1
+0.pfb>
+Output written on charter.pdf (2 pages, 65910 bytes).
+PDF statistics:
+ 34 PDF objects out of 1000 (max. 8388607)
+ 24 compressed objects within 1 object stream
+ 0 named destinations out of 1000 (max. 500000)
+ 13 words of extra memory for PDF output out of 10000 (max. 10000000)
+
Binary file WifiRobot/charter/charter.pdf has changed
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/WifiRobot/charter/charter.tex	Tue Dec 09 05:06:37 2014 +0000
@@ -0,0 +1,62 @@
+\documentclass[letterpaper]{article}
+
+\usepackage[margin=1in]{geometry}
+\usepackage{amsmath,amssymb,amsthm}
+\usepackage{enumerate}
+\usepackage{listings}
+\usepackage{tikz}
+\usepackage{courier}
+
+\usepackage{mathtools}
+\DeclarePairedDelimiter{\ceil}{\lceil}{\rceil}
+
+\lstset{%
+  language=[LaTeX]TeX,
+  basicstyle=\ttfamily,
+  breaklines=true,
+  columns=fullflexible
+}
+
+
+
+\begin{document}
+
+\title{WiFi-nder Project Charter}
+\author{Chaitanya Aluru \\ Sean Roberts \\ Eric Wu}
+\date{}
+\maketitle
+
+\subsection*{Project Goal}
+
+This project will create an autonomous wheeled robot that seeks out strong WiFi signal in a room to perform a basic internet operation.
+
+\subsection*{Project Approach}
+
+The project will model the radiation pattern of WiFi present in the room and attempt to seek out an area with signal strength above a specific threshold. We anticipate that there will be many local maxima of WiFi signal strengths due to interference patterns. Therefore, our exploration algorithm will be governed by a state machine that first attempts to find local maxima and then move towards higher higher local maxima. The goal will be to consistently find signal strength above a predefined threshold if such a condition exists within the space reachable by our project.
+
+\subsection*{Resources}
+
+The plan is to initially use the mbed FRMD KL25Z board as the processor core for the robot, and to use the iRobot Create as the robot platform. We will also need a wifi shield for the mbed. Preliminary searches have led us to the Adafruit CC3000 WiFi Breakout board, though this may change. In addition, depending on the wifi shield that we choose, we may need an antenna for the board. Since the project goal requires that we travel in the direction of the strongest wifi signal, a directional antenna may be used to give our robot a better sense of which direction to travel in.
+
+In addition, if we have extra time, we may attempt to replace the Roomba with our own car design. In this case, we will require at least two servo motors, wheels, and some sort of physical enclosure to hold our electronics.
+
+\subsection*{Schedule}
+
+\begin{itemize}
+\item October 21 - Project Charter due, project repository created
+\item October 28 - Discuss project with GSI, finalize parts and order
+\item November 4 - Project review with GSI, hopefully have ordered/received parts at this time
+\item November 11 - Have mbed and wifi shield running, and wifi shield outputting signal intensity measurements
+\item November 18 - mbed should be able to drive the wheels of the iRobot
+\item November 25 - Project milestone report due. If we are ahead of schedule we may try to get servo motors for our own car
+\item December 17 - 15 minute project demo
+\item December 19 - Project Report due
+\end{itemize}
+
+\subsection*{Risk and Feasibility}
+
+There are a couple of substantial unknowns. Merely using the spatial wifi signal intensities to plan movement may be unreliable, and reflections off of various surfaces and the movement of objects and people may complicate our intensity measurements. There is also the potential difficulty of having to modify the provided library code for our wifi shield to provide intensity measurements. In addition, it may be difficult to determine the direction to travel in, since we will likely have only a single antenna, though this may be remedied by using a directional antenna.
+
+Developing on the iRobot Create platform should be relatively straightforward, since the robot has been thoroughly tested and we have some experience working with it. However, using the mbed board in conjunction with the iRobot Create may not be entirely straightforward, as we may have to reimplement the portions of the code that allow the robot to move and rotate.
+
+\end{document}
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/WifiRobot/copy_code.sh Tue Dec 09 05:06:37 2014 +0000 @@ -0,0 +1,3 @@ +#!/bin/bash +sudo mount -u -w -o sync /Volumes/MBED +cp "$1" /Volumes/MBED
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/WifiRobot/wifi_test_main.cpp	Tue Dec 09 05:06:37 2014 +0000
@@ -0,0 +1,148 @@
+#include "mbed.h"
+#include "cc3000.h"
+#include "IntensityScanner.h"
+#include <MMA8451Q.h>
+#include <stdio.h>
+#include <stdlib.h>
+#include <stdbool.h>
+#include <string.h>
+#include "irobot.h"
+#include "irobotSensorTypes.h"
+#include "accelerometer.h"
+#include "TimeoutMultipleSerial.h"
+
+#define MMA8451_I2C_ADDRESS (0x1d)
+
+typedef enum a {
+    FORWARD,
+    TURN
+    
+    } robotState_t;
+    
+static robotState_t robotState = FORWARD;
+
+void irobotTestNavigate(
+    int32_t* netDistance,
+    int32_t* netAngle,
+    irobotSensorGroup6_t* sensors,
+    AccelMeasure* acc_meas,
+    int32_t* leftWheelSpeed,
+    int32_t* rightWheelSpeed) {
+
+    /*
+    switch (robotState) {
+        case FORWARD:
+            {
+                
+                if (*netDistance > 100) {
+                    robotState = TURN;
+                    *netDistance = 0;
+                    *netAngle = 0;
+                    }
+                else {
+                    *leftWheelSpeed = 50;
+                    *rightWheelSpeed = 50;
+                    }
+                
+            }
+        case TURN:
+            {
+                if (*netAngle > 90) {
+                        *netDistance = 0;
+                        *netAngle = 0;
+                        robotState = FORWARD;
+                    }
+                else {
+                    *leftWheelSpeed = 50;
+                    *rightWheelSpeed = -50;
+                    }
+            }
+        }
+        */
+        *leftWheelSpeed = 100;
+        *rightWheelSpeed = 100;
+}
+
+// KL25Z wifi connection
+// we need to define connection pins for:
+// - IRQ      => (pin D3)
+// - Enable   => (pin D5)
+// - SPI CS   => (pin D10)
+// - SPI MOSI => (pin D11)
+// - SPI MISO => (pin D12)
+// - SPI CLK  => (pin D13)
+// plus wifi network SSID, password, security level and smart-configuration flag.
+
+Serial pc(USBTX, USBRX);
+DigitalOut led_red(LED_RED);
+DigitalOut led_green(LED_GREEN);
+/*
+int main () {
+    // by default, it's red
+    printf("beginning\r\n");
+    led_red = 1;
+    led_green = 0;
+
+    IntensityScanner rssi_scanner = IntensityScanner(PTD7, PTD6, D10, SPI(D11, D12, PTC5), 
+        SSID, key, mbed_cc3000::WPA2, false, 200);
+        
+    uint8_t rssi;
+    while (1) {
+        if (rssi_scanner.rssi_for_ssid("attwifi", &rssi) == 0)
+            printf("Rssi is %d\r\n", rssi);
+        wait_ms(100);
+    }
+}
+*/
+
+int main (int argc, char** argv) {
+
+    MMA8451Q accelerometer(PTE25, PTE24, MMA8451_I2C_ADDRESS);
+
+    TimeoutMultipleSerial port_as_serial = TimeoutMultipleSerial(PTC4, PTC3, 
+        NULL, 100);
+    irobotUARTPort_t port = (irobotUARTPort_t) (&port_as_serial);
+
+    int32_t irobotStatus;
+    
+    irobotSensorGroup6_t sensors;
+    int32_t netDistance = 0;
+    int32_t netAngle = 0;
+
+    int32_t rightWheelSpeed = 0;
+    int32_t leftWheelSpeed = 0;
+
+    AccelMeasure accelMeasurements(0.0f, 0.0f, 0.0f);
+    AccelMeasure accelPrevMeasurements(0.0f, 0.0f, 0.0f);
+
+    int32_t status = irobotOpen(port);
+
+    
+    /*
+    For debugging only
+    */
+    DigitalOut myled(LED2);
+
+    irobotSensorPollSensorGroup6(port, &sensors);
+    
+    while (!sensors.buttons.advance || true) {
+        myled = 1;
+
+        // update from sensors
+        irobotSensorPollSensorGroup6(port, &sensors);
+
+
+
+        irobotTestNavigate(&netDistance,
+            &netAngle,
+            &sensors,
+            &accelMeasurements,
+            &leftWheelSpeed,
+            &rightWheelSpeed);
+       
+        irobotDriveDirect(port, leftWheelSpeed, rightWheelSpeed); 
+    }
+
+    status = irobotClose(port);
+    return status;
+}
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed.bld Tue Dec 09 05:06:37 2014 +0000 @@ -0,0 +1,1 @@ +http://mbed.org/users/mbed_official/code/mbed/builds/031413cf7a89 \ No newline at end of file
