Wifi Controlled Robot is done as a mini project (Lab4) for ECE 4180 class (Georgia Tech). Robot is assembled in Sparkfun's Shadow chasis robot kit. This robot takes the command from the webpage to move forward, reverse without colliding. The distance sensor is used as a mechanism for collision detection and play a short beep sound. It turn 90 degree with magnetometer when the turn command is sent.

Dependencies:   Motordriver mbed

/media/uploads/pkoirala3/capture.jpg Showing the setup and calibration: Part1 In this part the Wifi setups and attains an IP address so we can control it through a webpage on our phone/PC. After it obtains an IP address it calibrates the IMU so we can have accurate compass headings for precise turns.

The parts that we use are as follows:

  • Mbed
  • 2 DC motors
  • H-Bridge (to drive the DC motors)
  • Speaker
  • Class D Amp (to drive the Speaker)
  • IMU (use the magnometer for compass headings)
  • Wifi card (ESP8266)

Showing webpage functionality and Robot Functionality: In this part we demonstrate the functionality of the robot and the webpage to control it.

Final Code

[Repository '/teams/Prana-Koirala/code/Wifi_controlled_Robot_ECE4180/docs/tip/main_8cpp_source.html' not found]

Revision:
3:fff9904d2ecb
Parent:
1:bbe16318d747
Child:
4:166570fa7fda
--- a/main.cpp	Sun Mar 12 21:17:06 2017 +0000
+++ b/main.cpp	Mon Mar 13 05:23:32 2017 +0000
@@ -6,7 +6,7 @@
 #define DECLINATION -4.94 // Declination (degrees) in Atlanta,GA.
 
 DigitalOut  ledFwd(p8);
-DigitalOut  ledRev(p9);
+DigitalOut  ledRev(p11);
 
 Motor A(p26, p16, p25, 1); // pwm, fwd, rev, can brake
 Motor B(p21, p22, p23, 1); // pwm, fwd, rev, can brake
@@ -16,7 +16,7 @@
 
 PwmOut mySpeaker(p24);
 
-LSM9DS1 IMU(p9, p10, 0xD6, 0x3C);
+// LSM9DS1 IMU(p9, p10, 0xD6, 0x3C);
 
 AnalogIn DistSensorFwd(p19);
 AnalogIn DistSensorRev(p20);
@@ -37,14 +37,14 @@
 int update;
 char cmdbuff[1024];
 char replybuff[4096];
-char webdata[4096]; // This may need to be bigger depending on WEB browser used
-char webbuff[4096];     // Currently using 1986 characters, Increase this if more web page data added
+char webdata[4096];
+char webbuff[4096];
+char stateBuff[50];
 void SendCMD(),getreply(),ReadWebData(),startserver();
-void ImuCheck(), ObsDetected(float);
+void ImuCheck(), ObjDetect(float);
 char rx_line[1024];
 int port = 80;  // set server port
 int SERVtimeout = 5;    // set server timeout in seconds in case link breaks.
-struct tm t;
 
 int main()
 {
@@ -56,28 +56,45 @@
     wait(0.01);
     DataRX=0;
 
-    mySpeaker.period(1.0/500.0); // 500hz period
-
-    IMU.begin();
-    IMU.calibrate(1);
-    IMU.calibrateMag(0);
-
+    mySpeaker.period(1.0/200.0); // 500hz period
+    A.stop(0.0);
+    B.stop(0.0);
+    /*
+        IMU.begin();
+        IMU.calibrate(1);
+        IMU.calibrateMag(0);
+        pc.printf("Final Calibration done, prana");
+    */
     while(1) {
         if(DataRX==1) {
             ReadWebData();
             esp.attach(&Rx_interrupt, Serial::RxIrq);
         }
+
         float stateA = A.state();
         float stateB = B.state();
-        if((stateA > 0 && stateA <= 1)&&(stateB > 0 && stateB <= 1)) { // obstacle within 10 cm and robot is still moving
-            // Add second distance Sensor code
+        char temp_buff[50];
+        if(abs(stateA) > 1  && abs(stateB) > 1) strcpy(temp_buff, "Robot Stopped!");
+        else if((stateA > 0 && stateA <= 1)&&(stateB > 0 && stateB <= 1)) { // obstacle within 10 cm and robot is still moving
             float Dist = DistSensorFwd;
-            pc.printf("currDist: %f",Dist);
-            ObsDectected(Dist);
+            ObjDetect(Dist);
+            strcpy(temp_buff, "Robot Moving Forward!");
         } else if((stateA < 0 && stateA >= -1)&&(stateB < 0 && stateB >= -1)) { // If moving rev
             float Dist = DistSensorRev;
-            pc.printf("currDist: %f",Dist);
-            ObsDectected(Dist);
+            ObjDetect(Dist);
+            strcpy(temp_buff, "Robot Moving Reverse!");
+        } else if(abs(stateA) > 0 && abs(stateA) <= 1 && abs(stateB) > 1) {
+            strcpy(temp_buff, "Robot turning right!");
+        } else if(abs(stateB) > 0 && abs(stateB) <= 1 && abs(stateA) > 1) {
+            strcpy(temp_buff, "Robot turning left!");
+        } else strcpy(temp_buff, "Error getting Robot state");
+
+        if(update==1) { // update the state of Robot in webpage
+            sprintf(stateBuff, "%s",temp_buff);
+            sprintf(cmdbuff, "BotState=\"%s\"\r\n",stateBuff);
+            SendCMD();
+            getreply();
+            update=0;
         }
     }
 }
@@ -95,34 +112,40 @@
     rx_out = 0;
     // check web data for form information
     if( strstr(webdata, "check=BotFwd") != NULL ) {
+        if(abs(A.state()) <= 1) A.stop(0.0);
+        if(abs(B.state()) <= 1) B.stop(0.0);
         A.speed(0.75);
         B.speed(0.75);
         ledRev = 0;
         ledFwd = 1;
     }
     if( strstr(webdata, "check=BotRev") != NULL ) {
+        if(abs(A.state()) <= 1) A.stop(0.0);
+        if(abs(B.state()) <= 1) B.stop(0.0);
         A.speed(-0.75);
         B.speed(-0.75);
         ledFwd = 0;
         ledRev = 1;
     }
     if( strstr(webdata, "check=BotStop") != NULL ) {
-        A.stop(0.5);
-        B.stop(0.5);
+        A.stop(0.0);
+        B.stop(0.0);
         ledFwd = 0;
         ledRev = 0;
     }
     if( strstr(webdata, "check=BotLeft") != NULL ) {
-        B.stop(0.5);
-        A.speed(0.5);
-        ImuCheck();
-        A.stop(0.5);
+        B.stop(0.0);
+        A.speed(0.75);
+        // ImuCheck();
+        wait(1.0);
+        A.stop(0.0);
     }
     if( strstr(webdata, "check=BotRight") != NULL ) {
-        A.stop(0.5);
+        A.stop(0.0);
         B.speed(0.5);
-        ImuCheck();
-        B.stop(0.5);
+        // ImuCheck();
+        wait(1.0);
+        B.stop(0.0);
     }
     if( strstr(webdata, "POST") != NULL ) { // set update flag if POST request
         update=1;
@@ -142,6 +165,13 @@
     getreply();
 
     pc.printf("\nStarting Server.....\r\n> ");
+
+    // initial values
+    sprintf(cmdbuff, "BotState=\"%s\"\r\n",stateBuff);
+    SendCMD();
+    getreply();
+    wait(0.5);
+
     //create server
     sprintf(cmdbuff, "srv=net.createServer(net.TCP,%d)\r\n",SERVtimeout);
     SendCMD();
@@ -167,6 +197,11 @@
     SendCMD();
     getreply();
     wait(0.4);
+
+    strcpy(cmdbuff,"conn:send('<br>Current State of Robot: '..BotState..'<br><hr>')\r\n");
+    SendCMD();
+    getreply();
+    wait(0.2);
     strcpy(cmdbuff,"conn:send('<form method=\"POST\"')\r\n");
     SendCMD();
     getreply();
@@ -355,18 +390,21 @@
     bool rotFlag = true;
     IMU.readMag();
     float initial_heading;
-    if(my == 0.0) initial_heading = (-1*mx < 0.0) ? 180.0 : 0.0;
-    else initial_heading = atan2(-1*mx,my)*360.0/(2.0*PI);
+    float mx = -1*IMU.mx;
+    float my = IMU.my;
+    if(my == 0.0) initial_heading = (mx < 0.0) ? 180.0 : 0.0;
+    else initial_heading = atan2(mx,my)*360.0/(2.0*PI);
     initial_heading -= DECLINATION;
     if(initial_heading>180.0) initial_heading = initial_heading - 360.0;
     else if(initial_heading<0) initial_heading += 360.0;
 
     while(rotFlag) {
         IMU.readMag();
-        float mx = -1*(imu.mx);
+        float mx = -1*IMU.mx;
+        float my = IMU.my;
         float heading;
-        if (my == 0.0) heading = (-1*mx < 0.0) ? 180.0 : 0.0;
-        else heading = atan2(-1*mx, my)*360.0/(2.0*PI);
+        if (my == 0.0) heading = (mx < 0.0) ? 180.0 : 0.0;
+        else heading = atan2(mx, my)*360.0/(2.0*PI);
         heading -= DECLINATION; //correct for geo location
         if(heading>180.0) heading = heading - 360.0;
         else if(heading<0.0) heading += 360.0;
@@ -374,14 +412,16 @@
     }
 }
 
-// Checking if object there is obstacles in the way( Fwd and Rev )
-void ObsDetected(float currDist)
+// Checking for obstacles in the way while moving Fwd and Rev
+void ObjDetect(float currDist)
 {
     if(currDist <= 0.5f) {
-        A.stop(0.5);
-        B.stop(0.5);
+        A.stop(0.0);
+        B.stop(0.0);
         ledFwd = 0;
         ledRev = 0;
-        mySpeaker = 0.5; // Play Beep sound
+        mySpeaker = 0.5;  // Play Beep sound
+        wait(1.0);
+        mySpeaker=0.0;    // turn off audio
     }
 }
\ No newline at end of file