Can Kocak / Mbed 2 deprecated FRDM-KL25Z_WiFly_Access_Point_Mode_Zumo_RC

Dependencies:   mbed

Files at this revision

API Documentation at this revision

Comitter:
can90
Date:
Sat Jun 22 22:00:43 2013 +0000
Commit message:
FRDM-KL25Z WiFly Access Point iPhone Android Controlled Zumo RC Tracked Vehicle mbed Code

Changed in this revision

Wifly/CBuffer.h Show annotated file Show diff for this revision Revisions of this file
Wifly/Wifly.cpp Show annotated file Show diff for this revision Revisions of this file
Wifly/Wifly.h Show annotated file Show diff for this revision Revisions of this file
main.cpp Show annotated file Show diff for this revision Revisions of this file
mbed.bld Show annotated file Show diff for this revision Revisions of this file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Wifly/CBuffer.h	Sat Jun 22 22:00:43 2013 +0000
@@ -0,0 +1,75 @@
+/* Copyright (C) 2012 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 CIRCBUFFER_H_
+#define CIRCBUFFER_H_
+
+template <class T>
+class CircBuffer {
+public:
+    CircBuffer(int length) {
+        write = 0;
+        read = 0;
+        size = length + 1;
+        buf = (T *)malloc(size * sizeof(T));
+    };
+
+    bool isFull() {
+        return (((write + 1) % size) == read);
+    };
+
+    bool isEmpty() {
+        return (read == write);
+    };
+
+    void queue(T k) {
+        if (isFull()) {
+            read++;
+            read %= size;
+        }
+        buf[write++] = k;
+        write %= size;
+    }
+    
+    void flush() {
+        read = 0;
+        write = 0;
+    }
+    
+
+    uint32_t available() {
+        return (write >= read) ? write - read : size - read + write;
+    };
+
+    bool dequeue(T * c) {
+        bool empty = isEmpty();
+        if (!empty) {
+            *c = buf[read++];
+            read %= size;
+        }
+        return(!empty);
+    };
+
+private:
+    volatile uint32_t write;
+    volatile uint32_t read;
+    uint32_t size;
+    T * buf;
+};
+
+#endif
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Wifly/Wifly.cpp	Sat Jun 22 22:00:43 2013 +0000
@@ -0,0 +1,546 @@
+/* Copyright (C) 2012 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 "mbed.h"
+#include "Wifly.h"
+#include <string>
+#include <algorithm>
+
+//Debug is disabled by default
+#if (0 && !defined(TARGET_LPC11U24))
+#define DBG(x, ...) std::printf("[Wifly : DBG]"x"\r\n", ##__VA_ARGS__);
+#define WARN(x, ...) std::printf("[Wifly : WARN]"x"\r\n", ##__VA_ARGS__);
+#define ERR(x, ...) std::printf("[Wifly : ERR]"x"\r\n", ##__VA_ARGS__);
+#else
+#define DBG(x, ...)
+#define WARN(x, ...)
+#define ERR(x, ...)
+#endif
+
+#if !defined(TARGET_LPC11U24)
+#define INFO(x, ...) printf("[Wifly : INFO]"x"\r\n", ##__VA_ARGS__);
+#else
+#define INFO(x, ...)
+#endif
+
+#define MAX_TRY_JOIN 3
+
+Wifly * Wifly::inst;
+
+Wifly::Wifly(   PinName tx, PinName rx, PinName _reset, PinName tcp_status, const char * ssid, const char * phrase, Security sec):
+    wifi(tx, rx), reset_pin(_reset), tcp_status(tcp_status), buf_wifly(256)
+{
+    memset(&state, 0, sizeof(state));
+    state.sec = sec;
+
+    // change all ' ' in '$' in the ssid and the passphrase
+    strcpy(this->ssid, ssid);
+    for (int i = 0; i < strlen(ssid); i++) {
+        if (this->ssid[i] == ' ')
+            this->ssid[i] = '$';
+    }
+    strcpy(this->phrase, phrase);
+    for (int i = 0; i < strlen(phrase); i++) {
+        if (this->phrase[i] == ' ')
+            this->phrase[i] = '$';
+    }
+
+    inst = this;
+    attach_rx(false);
+    state.cmd_mode = false;
+}
+
+bool Wifly::join()
+{
+    char cmd[20];
+
+    for (int i= 0; i < MAX_TRY_JOIN; i++) {
+
+        // no auto join
+        if (!sendCommand("set w j 0\r", "AOK"))
+            continue;
+
+        //no echo
+        if (!sendCommand("set u m 1\r", "AOK"))
+            continue;
+
+        // set time
+        if (!sendCommand("set c t 30\r", "AOK"))
+            continue;
+
+        // set size
+        if (!sendCommand("set c s 1024\r", "AOK"))
+            continue;
+
+        // red led on when tcp connection active
+        if (!sendCommand("set s i 0x40\r", "AOK"))
+            continue;
+
+        // no string sent to the tcp client
+        if (!sendCommand("set c r 0\r", "AOK"))
+            continue;
+
+        // tcp protocol
+        if (!sendCommand("set i p 2\r", "AOK"))
+            continue;
+
+        // tcp retry
+        if (!sendCommand("set i f 0x7\r", "AOK"))
+            continue;
+            
+        // set dns server
+        if (!sendCommand("set d n rn.microchip.com\r", "AOK"))
+            continue;
+
+        //dhcp
+        sprintf(cmd, "set i d %d\r", (state.dhcp) ? 1 : 0);
+        if (!sendCommand(cmd, "AOK"))
+            continue;
+
+        // ssid
+        sprintf(cmd, "set w s %s\r", ssid);
+        if (!sendCommand(cmd, "AOK"))
+            continue;
+
+        //auth
+        sprintf(cmd, "set w a %d\r", state.sec);
+        if (!sendCommand(cmd, "AOK"))
+            continue;
+
+        // if no dhcp, set ip, netmask and gateway
+        if (!state.dhcp) {
+            DBG("not dhcp\r");
+
+            sprintf(cmd, "set i a %s\r\n", ip);
+            if (!sendCommand(cmd, "AOK"))
+                continue;
+
+            sprintf(cmd, "set i n %s\r", netmask);
+            if (!sendCommand(cmd, "AOK"))
+                continue;
+
+            sprintf(cmd, "set i g %s\r", gateway);
+            if (!sendCommand(cmd, "AOK"))
+                continue;
+        }
+
+        //key step
+        if (state.sec != NONE) {
+            if (state.sec == WPA)
+                sprintf(cmd, "set w p %s\r", phrase);
+            else if (state.sec == WEP_128)
+                sprintf(cmd, "set w k %s\r", phrase);
+
+            if (!sendCommand(cmd, "AOK"))
+                continue;
+        }
+
+        //join the network (10s timeout)
+        if (state.dhcp) {
+            if (!sendCommand("join\r", "DHCP=ON", NULL, 10000))
+                continue;
+        } else {
+            if (!sendCommand("join\r", "Associated", NULL, 10000))
+                continue;
+        }
+
+        if (!sendCommand("save\r", "Stor"))
+            continue;
+
+        exit();
+
+        state.associated = true;
+        INFO("\r\nssid: %s\r\nphrase: %s\r\nsecurity: %s\r\n\r\n", this->ssid, this->phrase, getStringSecurity());
+        return true;
+    }
+    return false;
+}
+
+
+bool Wifly::setProtocol(Protocol p)
+{
+    // use udp auto pairing
+    char cmd[20];
+    sprintf(cmd, "set i p %d\r", p);
+    if (!sendCommand(cmd, "AOK"))
+        return false;
+
+    switch(p) {
+        case TCP:
+            // set ip flags: tcp retry enabled
+            if (!sendCommand("set i f 0x07\r", "AOK"))
+                return false;
+            break;
+        case UDP:
+            // set ip flags: udp auto pairing enabled
+            if (!sendCommand("set i h 0.0.0.0\r", "AOK"))
+                return false;
+            if (!sendCommand("set i f 0x40\r", "AOK"))
+                return false;
+            break;
+    }
+    state.proto = p;
+    return true;
+}
+
+char * Wifly::getStringSecurity()
+{
+    switch(state.sec) {
+        case NONE:
+            return "NONE";
+        case WEP_128:
+            return "WEP_128";
+        case WPA:
+            return "WPA";
+    }
+    return "UNKNOWN";
+}
+
+bool Wifly::connect(const char * host, int port)
+{
+    char rcv[20];
+    char cmd[20];
+
+    // try to open
+    sprintf(cmd, "open %s %d\r", host, port);
+    if (sendCommand(cmd, "OPEN", NULL, 10000)) {
+        state.tcp = true;
+        state.cmd_mode = false;
+        return true;
+    }
+
+    // if failed, retry and parse the response
+    if (sendCommand(cmd, NULL, rcv, 5000)) {
+        if (strstr(rcv, "OPEN") == NULL) {
+            if (strstr(rcv, "Connected") != NULL) {
+                wait(0.25);
+                if (!sendCommand("close\r", "CLOS"))
+                    return false;
+                wait(0.25);
+                if (!sendCommand(cmd, "OPEN", NULL, 10000))
+                    return false;
+            } else {
+                return false;
+            }
+        }
+    } else {
+        return false;
+    }
+
+    state.tcp = true;
+    state.cmd_mode = false;
+
+    return true;
+}
+
+
+bool Wifly::gethostbyname(const char * host, char * ip)
+{
+    string h = host;
+    char cmd[30], rcv[100];
+    int l = 0;
+    char * point;
+    int nb_digits = 0;
+
+    // no dns needed
+    int pos = h.find(".");
+    if (pos != string::npos) {
+        string sub = h.substr(0, h.find("."));
+        nb_digits = atoi(sub.c_str());
+    }
+    //printf("substrL %s\r\n", sub.c_str());
+    if (count(h.begin(), h.end(), '.') == 3 && nb_digits > 0) {
+        strcpy(ip, host);
+    }
+    // dns needed
+    else {
+        nb_digits = 0;
+        sprintf(cmd, "lookup %s\r", host);
+        if (!sendCommand(cmd, NULL, rcv))
+            return false;
+
+        // look for the ip address
+        char * begin = strstr(rcv, "=") + 1;
+        for (int i = 0; i < 3; i++) {
+            point = strstr(begin + l, ".");
+            DBG("str: %s", begin + l);
+            l += point - (begin + l) + 1;
+        }
+        DBG("str: %s", begin + l);
+        while(*(begin + l + nb_digits) >= '0' && *(begin + l + nb_digits) <= '9') {
+            DBG("digit: %c", *(begin + l + nb_digits));
+            nb_digits++;
+        }
+        memcpy(ip, begin, l + nb_digits);
+        ip[l+nb_digits] = 0;
+        DBG("ip from dns: %s", ip);
+    }
+    return true;
+}
+
+
+void Wifly::flush()
+{
+    buf_wifly.flush();
+}
+
+bool Wifly::sendCommand(const char * cmd, const char * ack, char * res, int timeout)
+{
+    if (!state.cmd_mode) {
+        cmdMode();
+    }
+    if (send(cmd, strlen(cmd), ack, res, timeout) == -1) {
+        ERR("sendCommand: cannot %s\r\n", cmd);
+        exit();
+        return false;
+    }
+    return true;
+}
+
+bool Wifly::cmdMode()
+{
+    // if already in cmd mode, return
+    if (state.cmd_mode)
+        return true;
+
+    if (send("$$$", 3, "CMD") == -1) {
+        ERR("cannot enter in cmd mode\r\n");
+        exit();
+        return false;
+    }
+    state.cmd_mode = true;
+    return true;
+}
+
+bool Wifly::disconnect()
+{
+    // if already disconnected, return
+    if (!state.associated)
+        return true;
+
+    if (!sendCommand("leave\r", "DeAuth"))
+        return false;
+    exit();
+
+    state.associated = false;
+    return true;
+
+}
+
+bool Wifly::is_connected()
+{
+    return (tcp_status.read() ==  1) ? true : false;
+}
+
+
+void Wifly::reset()
+{
+    reset_pin = 0;
+    wait(0.2);
+    reset_pin = 1;
+    wait(0.2);
+}
+
+bool Wifly::reboot()
+{
+    // if already in cmd mode, return
+    if (!sendCommand("reboot\r"))
+        return false;
+    
+    wait(0.3);
+
+    state.cmd_mode = false;
+    return true;
+}
+
+bool Wifly::close()
+{
+    // if not connected, return
+    if (!state.tcp)
+        return true;
+
+    wait(0.25);
+    if (!sendCommand("close\r", "CLOS"))
+        return false;
+    exit();
+
+    state.tcp = false;
+    return true;
+}
+
+
+int Wifly::putc(char c)
+{
+    while (!wifi.writeable());
+    return wifi.putc(c);
+}
+
+
+bool Wifly::exit()
+{
+    flush();
+    if (!state.cmd_mode)
+        return true;
+    if (!sendCommand("exit\r", "EXIT"))
+        return false;
+    state.cmd_mode = false;
+    flush();
+    return true;
+}
+
+
+int Wifly::readable()
+{
+    return buf_wifly.available();
+}
+
+int Wifly::writeable()
+{
+    return wifi.writeable();
+}
+
+char Wifly::getc()
+{
+    char c;
+    while (!buf_wifly.available());
+    buf_wifly.dequeue(&c);
+    return c;
+}
+
+void Wifly::handler_rx(void)
+{
+    //read characters
+    while (wifi.readable())
+        buf_wifly.queue(wifi.getc());
+}
+
+void Wifly::attach_rx(bool callback)
+{
+    if (!callback)
+        wifi.attach(NULL);
+    else
+        wifi.attach(this, &Wifly::handler_rx);
+}
+
+
+int Wifly::send(const char * str, int len, const char * ACK, char * res, int timeout)
+{
+    char read;
+    size_t found = string::npos;
+    string checking;
+    Timer tmr;
+    int result = 0;
+
+    DBG("will send: %s\r\n",str);
+
+    attach_rx(false);
+
+    //We flush the buffer
+    while (wifi.readable())
+        wifi.getc();
+
+    if (!ACK || !strcmp(ACK, "NO")) {
+        for (int i = 0; i < len; i++)
+            result = (putc(str[i]) == str[i]) ? result + 1 : result;
+    } else {
+        //We flush the buffer
+        while (wifi.readable())
+            wifi.getc();
+
+        tmr.start();
+        for (int i = 0; i < len; i++)
+            result = (putc(str[i]) == str[i]) ? result + 1 : result;
+
+        while (1) {
+            if (tmr.read_ms() > timeout) {
+                //We flush the buffer
+                while (wifi.readable())
+                    wifi.getc();
+
+                DBG("check: %s\r\n", checking.c_str());
+
+                attach_rx(true);
+                return -1;
+            } else if (wifi.readable()) {
+                read = wifi.getc();
+                if ( read != '\r' && read != '\n') {
+                    checking += read;
+                    found = checking.find(ACK);
+                    if (found != string::npos) {
+                        wait(0.01);
+
+                        //We flush the buffer
+                        while (wifi.readable())
+                            wifi.getc();
+
+                        break;
+                    }
+                }
+            }
+        }
+        DBG("check: %s\r\n", checking.c_str());
+
+        attach_rx(true);
+        return result;
+    }
+
+    //the user wants the result from the command (ACK == NULL, res != NULL)
+    if ( res != NULL) {
+        int i = 0;
+        Timer timeout;
+        timeout.start();
+        tmr.reset();
+        while (1) {
+            if (timeout.read() > 2) {
+                if (i == 0) {
+                    res = NULL;
+                    break;
+                }
+                res[i] = '\0';
+                DBG("user str 1: %s\r\n", res);
+
+                break;
+            } else {
+                if (tmr.read_ms() > 300) {
+                    res[i] = '\0';
+                    DBG("user str: %s\r\n", res);
+
+                    break;
+                }
+                if (wifi.readable()) {
+                    tmr.start();
+                    read = wifi.getc();
+
+                    // we drop \r and \n
+                    if ( read != '\r' && read != '\n') {
+                        res[i++] = read;
+                    }
+                }
+            }
+        }
+        DBG("user str: %s\r\n", res);
+    }
+
+    //We flush the buffer
+    while (wifi.readable())
+        wifi.getc();
+
+    attach_rx(true);
+    DBG("result: %d\r\n", result)
+    return result;
+}
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Wifly/Wifly.h	Sat Jun 22 22:00:43 2013 +0000
@@ -0,0 +1,238 @@
+/* Copyright (C) 2012 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.
+ *
+ * @section DESCRIPTION
+ *
+ * Wifly RN131-C, wifi module
+ *
+ * Datasheet:
+ *
+ * http://dlnmh9ip6v2uc.cloudfront.net/datasheets/Wireless/WiFi/WiFly-RN-UM.pdf
+ */
+
+#ifndef WIFLY_H
+#define WIFLY_H
+
+#include "mbed.h"
+#include "CBuffer.h"
+
+#define DEFAULT_WAIT_RESP_TIMEOUT 500
+
+enum Security {
+    NONE = 0,
+    WEP_128 = 1,
+    WPA = 3
+};
+
+enum Protocol {
+    UDP = (1 << 0),
+    TCP = (1 << 1)
+};
+
+class Wifly
+{
+
+public:
+    /*
+    * Constructor
+    *
+    * @param tx mbed pin to use for tx line of Serial interface
+    * @param rx mbed pin to use for rx line of Serial interface
+    * @param reset reset pin of the wifi module ()
+    * @param tcp_status connection status pin of the wifi module (GPIO 6)
+    * @param ssid ssid of the network
+    * @param phrase WEP or WPA key
+    * @param sec Security type (NONE, WEP_128 or WPA)
+    */
+    Wifly(  PinName tx, PinName rx, PinName reset, PinName tcp_status, const char * ssid, const char * phrase, Security sec);
+
+    /*
+    * Connect the wifi module to the ssid contained in the constructor.
+    *
+    * @return true if connected, false otherwise
+    */
+    bool join();
+
+    /*
+    * Disconnect the wifly module from the access point
+    *
+    * @ returns true if successful
+    */
+    bool disconnect();
+
+    /*
+    * Open a tcp connection with the specified host on the specified port
+    *
+    * @param host host (can be either an ip address or a name. If a name is provided, a dns request will be established)
+    * @param port port
+    * @ returns true if successful
+    */
+    bool connect(const char * host, int port);
+
+
+    /*
+    * Set the protocol (UDP or TCP)
+    *
+    * @param p protocol
+    * @ returns true if successful
+    */
+    bool setProtocol(Protocol p);
+
+    /*
+    * Reset the wifi module
+    */
+    void reset();
+    
+    /*
+    * Reboot the wifi module
+    */
+    bool reboot();
+
+    /*
+    * Check if characters are available
+    *
+    * @return number of available characters
+    */
+    int readable();
+
+    /*
+    * Check if characters are available
+    *
+    * @return number of available characters
+    */
+    int writeable();
+
+    /*
+    * Check if a tcp link is active
+    *
+    * @returns true if successful
+    */
+    bool is_connected();
+
+    /*
+    * Read a character
+    *
+    * @return the character read
+    */
+    char getc();
+
+    /*
+    * Flush the buffer
+    */
+    void flush();
+
+    /*
+    * Write a character
+    *
+    * @param the character which will be written
+    */
+    int putc(char c);
+
+
+    /*
+    * To enter in command mode (we can configure the module)
+    *
+    * @return true if successful, false otherwise
+    */
+    bool cmdMode();
+
+    /*
+    * To exit the command mode
+    *
+    * @return true if successful, false otherwise
+    */
+    bool exit();
+
+    /*
+    * Close a tcp connection
+    *
+    * @ returns true if successful
+    */
+    bool close();
+
+    /*
+    * Send a string to the wifi module by serial port. This function desactivates the user interrupt handler when a character is received to analyze the response from the wifi module.
+    * Useful to send a command to the module and wait a response.
+    *
+    *
+    * @param str string to be sent
+    * @param len string length
+    * @param ACK string which must be acknowledge by the wifi module. If ACK == NULL, no string has to be acknoledged. (default: "NO")
+    * @param res this field will contain the response from the wifi module, result of a command sent. This field is available only if ACK = "NO" AND res != NULL (default: NULL)
+    *
+    * @return true if ACK has been found in the response from the wifi module. False otherwise or if there is no response in 5s.
+    */
+    int send(const char * str, int len, const char * ACK = NULL, char * res = NULL, int timeout = DEFAULT_WAIT_RESP_TIMEOUT);
+
+    /*
+    * Send a command to the wify module. Check if the module is in command mode. If not enter in command mode
+    *
+    * @param str string to be sent
+    * @param ACK string which must be acknowledge by the wifi module. If ACK == NULL, no string has to be acknoledged. (default: "NO")
+    * @param res this field will contain the response from the wifi module, result of a command sent. This field is available only if ACK = "NO" AND res != NULL (default: NULL)
+    *
+    * @returns true if successful
+    */
+    bool sendCommand(const char * cmd, const char * ack = NULL, char * res = NULL, int timeout = DEFAULT_WAIT_RESP_TIMEOUT);
+    
+    /*
+    * Return true if the module is using dhcp
+    *
+    * @returns true if the module is using dhcp
+    */
+    bool isDHCP() {
+        return state.dhcp;
+    }
+
+    bool gethostbyname(const char * host, char * ip);
+
+    static Wifly * getInstance() {
+        return inst;
+    };
+
+protected:
+    Serial wifi;
+    DigitalOut reset_pin;
+    DigitalIn tcp_status;
+    char phrase[30];
+    char ssid[30];
+    const char * ip;
+    const char * netmask;
+    const char * gateway;
+    int channel;
+    CircBuffer<char> buf_wifly;
+
+    static Wifly * inst;
+
+    void attach_rx(bool null);
+    void handler_rx(void);
+
+
+    typedef struct STATE {
+        bool associated;
+        bool tcp;
+        bool dhcp;
+        Security sec;
+        Protocol proto;
+        bool cmd_mode;
+    } State;
+
+    State state;
+    char * getStringSecurity();
+};
+
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/main.cpp	Sat Jun 22 22:00:43 2013 +0000
@@ -0,0 +1,222 @@
+#include "mbed.h"
+#include "Wifly.h"
+
+//wifly instance is created with no security, without ssid and password
+Wifly wifly(PTD3, PTD2, PTC8, PTC7, NULL, NULL, NONE);
+
+Serial pc(USBTX,USBRX);
+
+//motor control pins
+DigitalOut dirRight(PTC9);
+DigitalOut dirLeft(PTA13);
+PwmOut pwmRight(PTD5);
+PwmOut pwmLeft(PTD0);
+
+//LED control pin. LED is located on Zumo Shield
+DigitalOut led(PTD1);
+
+//append function appends a char to
+void append(char* s, char c);
+
+//send function sends the given char* to wifly
+void sendString(char* str);
+
+int main() {
+    //factory reset Wifly
+    wifly.reset();
+    pc.printf("\nFactory Reset\n");
+    //reboot wifly
+    bool success = wifly.reboot();
+    pc.printf("Reboot: %d\n", success); //success = 1 -> successful process
+    //set TCP Listen port that will be used to 2000. You can set this to your preferred port number.
+    success = wifly.sendCommand("set ip local 2000\r", "AOK");
+    pc.printf("Local = 2000: %d\n", success); //success = 1 -> successful process
+    //make WiFly Module work as an Access Point
+    success = wifly.sendCommand("apmode\r", "AP mode");
+    pc.printf("AP Mode: %d\n", success); //success = 1 -> successful process
+    
+    char str[15] = "";
+    int count = 0; //count will be used to count characters after finding 'L' for "Listen"
+    bool foundL = false; //will be made true when wifly sends 'L' character to mbed from its serial port
+    bool foundO = false; //will be made true when wifly sends 'O' character to mbed from its serial port
+    
+    /*
+    After this state, the code will monitor input characters from WiFly and executes some code
+    after finding "Listen" or "OPEN" keywords
+    */
+    
+    while(true) {
+        //get current character from wifly's serial port
+        char ch = wifly.getc();
+        
+        //----Find "Listen" to find the port number----
+        if(!foundL) {
+            if(ch == 'L') {
+                foundL = true;
+                append(str, ch);
+                continue;
+            }
+        }
+        else {
+            if(count <= 4) {
+                append(str, ch);
+                count++;
+                continue;
+            }
+            else {
+                if(!strcmp(str, "Listen")) {
+                    char portString[5] = "";
+                    for(int i = 0; i < 7; i++) {
+                        char portChar = wifly.getc();
+                        if(i >= 3) {
+                            append(portString, portChar);
+                        }
+                    }
+                    //print the port number that WiFly Module listens
+                    pc.printf("\nPort: %s", portString);
+                }
+                foundL = false;
+                count = 0;
+                str[0] = 0; //clear char* array
+                continue;
+            }
+        }
+        //----End of Find "Listen" to find the port number----
+        
+        //----Find "OPEN" to find out if a TCP Connection is established----
+        if(!foundO) {
+            if(ch == 'O') {
+                foundO = true;
+                append(str, ch);
+                continue;
+            }
+        }
+        else {
+            if(count <= 2) {
+                append(str, ch);
+                count++;
+                continue;
+            }
+            else {
+                if(!strcmp(str, "OPEN")) { //"OPEN" is found, start the demo program
+                    pc.printf("\nConnection Established!");
+                    //commandChar will be used to store current character came from TCP
+                    char commandChar = 0;
+                    //when "CLOS" is received, connectionEnded will be made true and the while loop
+                    //contains demo program will be ended
+                    bool connectionEnded = false;
+                    const int period = 60;
+                    pwmRight.period_us(period);
+                    pwmLeft.period_us(period);
+                    int speed = 20;
+                    do {
+                        //get current character from TCP (using wifly)
+                        commandChar = wifly.getc();
+                        //When 'C' is received, this could be "CLOS" message,
+                        //check this in else
+                        if(commandChar != 'C') {
+                            
+                            //You can send messages to the connected device with:
+                            //wifly.putc(<char>);
+                            //sendString(<char*>);
+                            if(commandChar == '0') { //stop
+                                pwmRight.pulsewidth_us(0);
+                                pwmLeft.pulsewidth_us(0);
+                            }
+                            else if(commandChar == '1') { //forward
+                                dirRight = 0;
+                                dirLeft = 0;
+                                pwmRight.pulsewidth_us(speed);
+                                pwmLeft.pulsewidth_us(speed);
+                            }
+                            else if(commandChar == '2') { //backward
+                                dirRight = 1;
+                                dirLeft = 1;
+                                pwmRight.pulsewidth_us(speed);
+                                pwmLeft.pulsewidth_us(speed);
+                            }
+                            else if(commandChar == '3') { //right
+                                dirRight = 1;
+                                dirLeft = 0;
+                                pwmRight.pulsewidth_us(speed);
+                                pwmLeft.pulsewidth_us(speed);
+                            }
+                            else if(commandChar == '4') { //left
+                                dirRight = 0;
+                                dirLeft = 1;
+                                pwmRight.pulsewidth_us(speed);
+                                pwmLeft.pulsewidth_us(speed);
+                            }
+                            else if(commandChar == '5') { //forward right
+                                dirRight = 0;
+                                dirLeft = 0;
+                                pwmRight.pulsewidth_us(speed/2);
+                                pwmLeft.pulsewidth_us(speed);
+                            }
+                            else if(commandChar == '6') { //forward left
+                                dirRight = 0;
+                                dirLeft = 0;
+                                pwmRight.pulsewidth_us(speed);
+                                pwmLeft.pulsewidth_us(speed/2);
+                            }
+                            else if(commandChar == '7') { //backward right
+                                dirRight = 1;
+                                dirLeft = 1;
+                                pwmRight.pulsewidth_us(speed/2);
+                                pwmLeft.pulsewidth_us(speed);
+                            }
+                            else if(commandChar == '8') { //backward left
+                                dirRight = 1;
+                                dirLeft = 1;
+                                pwmRight.pulsewidth_us(speed);
+                                pwmLeft.pulsewidth_us(speed/2);
+                            }
+                            else if(commandChar == '9') { //speed0
+                                speed = 0;
+                            }
+                            else if(commandChar == 'a') { //speed1
+                                speed = 20;
+                            }
+                            else if(commandChar == 'b') { //speed2
+                                speed = 40;
+                            }
+                            else if(commandChar == 'c') { //speed3
+                                speed = 60;
+                            }
+                        }
+                        else {
+                            //construct 4 letter word from wifly serial connection and check if it is "CLOS" or not.
+                            char closString[5] = "";
+                            append(closString, commandChar);
+                            for(int i = 0; i <= 2; i++) {
+                                char closChar = wifly.getc();
+                                append(closString, closChar);
+                            }
+                            //
+                            if(!strcmp(closString, "CLOS")) {
+                                pc.printf("\nConnection Closed!");
+                                connectionEnded = true;
+                            }
+                        }
+                    } while(!connectionEnded);
+                }
+                foundO = false;
+                count = 0;
+                str[0] = 0;
+                continue;
+            }
+        }
+    }
+}
+
+void append(char* s, char c) {
+    int len = strlen(s);
+    s[len] = c;
+    s[len+1] = '\0';
+}
+
+void sendString(char* str) {
+    for(int i = 0; i < strlen(str); i++) {
+        wifly.putc(str[i]);
+    }
+}
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed.bld	Sat Jun 22 22:00:43 2013 +0000
@@ -0,0 +1,1 @@
+http://mbed.org/users/mbed_official/code/mbed/builds/b3110cd2dd17
\ No newline at end of file