Components and supplies
1
Adafruit Ultimate GPS Breakout
1
Arduino Due
1
esp8266 olimexino
1
Dagu Robot Shield
Project description
Code
ARTe Arduino Sketch
arduino
1#include <Ultrasonic.h> 2#include <Motor.h> 3#include <WiFiESP8266.h> 4#include <Adafruit_GPS.h> 5// Attach GPS module to Arduino Due Serial2 6#define GPSSerial Serial2 7#define PMTK_SET_NMEA_UPDATE_1HZ "$PMTK220,1000*1F" 8#define PMTK_SET_NMEA_UPDATE_5HZ "$PMTK220,200*2C" 9#define PMTK_SET_NMEA_UPDATE_10HZ "$PMTK220,100*2F" 10 11// turn on only the second sentence (GPRMC) 12#define PMTK_SET_NMEA_OUTPUT_RMCONLY "$PMTK314,0,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0*29" 13// turn on GPRMC and GGA 14#define PMTK_SET_NMEA_OUTPUT_RMCGGA "$PMTK314,0,1,0,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0*28" 15// turn on ALL THE DATA 16#define PMTK_SET_NMEA_OUTPUT_ALLDATA "$PMTK314,1,1,1,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0*28" 17// turn off output 18#define PMTK_SET_NMEA_OUTPUT_OFF "$PMTK314,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0*28" 19#define PMTK_Q_RELEASE "$PMTK605*31" 20//------------------------------------------------ 21// Pins connected to Ultrasonic 22const int ul_trig = 43; 23const int ul_eco = 41; 24// Pins connected to H-bridge to drive motors 25const int mR_en = 3; 26const int mL_en = 2; 27const int mR_A = 31; 28const int mR_B = 30; 29const int mL_A = 33; 30const int mL_B = 32; 31// Pins connected to Encoder 32const int enR_sen = 24; 33const int enL_sen = 26; 34// Wi-Fi module attached to Arduino Due Serial1 35// Netwoek parameters 36String Network = "INO_ESP8266"; 37String Password = "12345678"; 38String KeyType = "2"; 39String Channel = "1"; 40//------------------------------------------------ 41// Duty Cycle Max and Min used to PWM driving of motors : 42const int dc_min = 3000; 43const int dc_max = 4096; 44// Encoder variables 45const int CFL = 20; // Rising for a lap 46static unsigned long cL; // Left rising counter 47static unsigned long cR; // Right rising counter 48static unsigned long turnTimeL; //Time used to control right turn of vehicle 49static unsigned long turnTimeR; //Time used to control left turn of vehicle 50static unsigned long t; // Arduino time 51static float rpsL; // Estimated Left wheel velocity 52static float rpsR; // Estimated Right wheel velocity 53static int dcL; // Duty cycle used for left wheel when control is active 54static int dcR; // Duty cycle used for right wheel when control is active 55 56 57// Buffer used to store the data recived from Wi-Fi 58String Buffer; 59// Buffer used to store the data will send by Wi-Fi 60String Data; 61// Buffer used to store the command recived from Wi-Fi or from PC 62String Command; 63// Buffer used to store the data recived from GPS 64String BufferGPS; 65 66static bool start; // set to true after Wi-Fi module initialization 67static bool wifiCon; // set to true after a client is connected to network 68static bool okfound; // set to true during Wi-Fi module initialization 69static bool readyfound; // set to true during Wi-Fi module initialization 70static bool motFon; // set to true when vheicle go forward 71static bool motBon; // set to true when vheicle go back 72static bool motRotR; // set to true when vheicle turn Left 73static bool motRotL; // set to true when vheicle turn Right 74static bool controlStartL; // set to true when control of left wheel is enable 75static bool controlStartR; // set to true when control of right wheel is enable 76static bool GPSstart; // set to true after GPS module initialization 77static bool GPSfix; // set to true after reciving a fix from GPS 78//------------------------------------------------ 79// Function used to select the command to execute 80void SendCommand(int dc_L, int dc_R) { 81 static Motor L_motor(mL_en, mL_A, mL_B); 82 static Motor R_motor(mR_en, mR_A, mR_B); 83 //Serial.println(Command); 84 // Motors commands 85 if (Command == "q") { 86 // Veicle turn Left 87 turnTimeR = millis(); 88 controlStartL = false; 89 controlStartR = true; 90 motRotR = true; 91 L_motor.stopMot(); 92 R_motor.stopMot(); 93 delay(1); 94 //R_motor.forward(dc_R); 95 R_motor.forward(dc_max); // turn left the vehicle trought right wheel 96 //L_motor.forward(dc_min); // this line can be commented on 97 Command = ""; 98 } 99 else if (Command == "z") { 100 // Veicle turn Left 101 controlStartL = false; 102 controlStartR = false; 103 L_motor.back(dc_L); // turn left the vehicle trought left wheel 104 Command = ""; 105 } 106 else if (Command == "a") { 107 // Stop Left wheel 108 controlStartL = false; 109 controlStartR = false; 110 L_motor.stopMot(); 111 Command = ""; 112 } 113 else if (Command == "e") { 114 // Veicle turn Right 115 turnTimeL = millis(); 116 controlStartR = false; 117 controlStartL = true; 118 motRotL = true; 119 R_motor.stopMot(); 120 L_motor.stopMot(); 121 delay(1); 122 //L_motor.forward(dc_L); 123 L_motor.forward(dc_max); // turn right the vehicle trought left wheel 124 //R_motor.forward(dc_min); // this line can be commented on 125 Command = ""; 126 } 127 else if (Command == "c") { 128 // Veicle turn Right 129 controlStartL = false; 130 controlStartR = false; 131 R_motor.back(dc_R); // turn right the vehicle trought right wheel 132 Command = ""; 133 } 134 else if (Command == "d") { 135 // Stop Rigth wheel 136 controlStartL = false; 137 controlStartR = false; 138 R_motor.stopMot(); 139 Command = ""; 140 } 141 else if (Command == "s") { 142 // Stop vehicle 143 controlStartL = false; 144 controlStartR = false; 145 motFon = false; 146 motBon = false; 147 L_motor.stopMot(); 148 R_motor.stopMot(); 149 Command = ""; 150 } 151 else if (Command == "w") { 152 // Vehicle Forward 153 controlStartL = true; 154 controlStartR = true; 155 motFon = true; 156 motBon = false; 157 L_motor.forward(dc_L); 158 R_motor.forward(dc_R); 159 Command = ""; 160 } 161 else if (Command == "x") { 162 // Vehicle Back 163 controlStartL = true; 164 controlStartR = true; 165 motBon = true; 166 motFon = false; 167 L_motor.back(dc_L); 168 R_motor.back(dc_R); 169 Command = ""; 170 } 171} 172//------------------------------------------------ 173void setup() { 174 Serial.begin(115200); 175 // Serial for wi-fi communaication 176 Serial1.begin (115200); 177 178 // Attach motors pins 179 analogWriteResolution(12); 180 pinMode(mL_en, OUTPUT); 181 pinMode(mR_en, OUTPUT); 182 pinMode(mL_A, OUTPUT); 183 pinMode(mL_B, OUTPUT); 184 pinMode(mR_A, OUTPUT); 185 pinMode(mR_B, OUTPUT); 186 // Attach Encoder pins and interrupts 187 pinMode(enL_sen, INPUT_PULLUP); 188 pinMode(enR_sen, INPUT_PULLUP); 189 attachInterrupt(digitalPinToInterrupt(enL_sen), IncLc, RISING); 190 attachInterrupt(digitalPinToInterrupt(enR_sen), IncRc, RISING); 191 192 t = 0; 193 cL = 0; 194 cR = 0; 195 rpsL = 0; 196 rpsR = 0; 197 dcL = 0; 198 dcR = 0; 199 200 Buffer = ""; 201 Data = ""; 202 Command = ""; 203 BufferGPS = ""; 204 205 start = false; 206 wifiCon = false; 207 okfound = false; 208 readyfound = false; 209 motFon = false; 210 motBon = false; 211 controlStartL = false; 212 controlStartR = false; 213 motRotR = false; 214 motRotL = false; 215 GPSstart = false; 216 GPSfix = false; 217} 218//------------------------------------------------ 219void loop() { 220} 221// Function attached to interrupt of left wheel 222void IncLc() 223{ 224 cL++; 225} 226// Function attached to interrupt of right wheel 227void IncRc() 228{ 229 cR++; 230} 231//------------------------------------------------ 232// TASKS: 233// T1: Control left wheel 234void loop1(100) { 235 static int k = 0; 236 const int Ns = 10; // number of samplings 237 const int dcMax = 4096;// Max duty cycle 238 const int dcMin = 1000;// Min duty cycle 239 const int dcNom = 3600;// Nominal duty cycle 240 const double v_ref = 1.5;// Velocity of reference 241 const double KpL = 150;// K proportional 242 const double KiL = 80;// K integrative 243 //static int dcL = 0; 244 static unsigned long tk[Ns]; // Time samples 245 static unsigned long ckL[Ns]; // Rises detetcted from encoder 246 static double vL[Ns]; // Velocity 247 static double eL[Ns]; // Error 248 static double eiL = 0.0; // Integral of error 249 static double vsL = 0.0; // Sum of velocity 250 static double vmL = 0.0; // Mean velocity 251 static unsigned long cRotL = 0;// Used to control the number of rotation of wheel 252 static bool firstStartL = true; 253 static bool rotLstart = false; 254 static unsigned long AcL; // Rise variation 255 static unsigned long AcT; // Time variation 256 //------------------------------------------------ 257 tk[k] = millis(); 258 ckL[k] = cL; 259 cL = 0; 260 if (firstStartL) { 261 vL[0] = 0; 262 eL[0] = 0; 263 vmL = 0; 264 AcT = 0; 265 AcL = 0; 266 k = 1; 267 firstStartL = false; 268 //controlStartL = true; 269 } 270 else { 271 if (k == 0) { 272 // Compute changes ad time variation 273 AcT = tk[k] - tk[Ns - 1]; 274 AcL = ckL[k]; 275 vL[k] = vL[Ns - 1]; 276 vsL = vL[k]; 277 // Compute Error 278 //eL[k] = v_ref - vL[k]; 279 eL[k] = v_ref - vmL; 280 // Compute integral of Error 281 eiL = (eL[k] + eL[Ns - 1]) * (AcT / 2); 282 } 283 else { 284 // Compute changes ad time variation 285 AcT = tk[k] - tk[k - 1]; 286 AcL = ckL[k]; 287 // Compute velocity of wheels 288 vL[k] = 50.0 * double(AcL) / double(AcT); 289 // Compute mean velocity of wheels 290 vsL += vL[k]; 291 vmL = vsL / double(k + 1); 292 // Compute Error 293 //eL[k] = v_ref - vL[k]; 294 eL[k] = v_ref - vmL; 295 // Compute integral of Error 296 eiL = (eL[k] + eL[k - 1]) * (AcT / 2); 297 } 298 // compute Duty Cycle 299 //Serial.println(String(k)+" : "+String(vL[k])); 300 dcL = dcNom + int(KpL * eL[k]) + int(KiL * eiL); 301 // Limit DC left wheel 302 if (dcL > dcMax) { 303 dcL = dcMax; 304 } 305 if (dcL < dcMin) { 306 dcL = dcMin; 307 } 308 if (controlStartL) { 309 // Send control command when control start 310 if (motRotL) { 311 //cRotL += AcL; 312 //Serial.println(cRotL); 313 //if (cRotL >= 10) { 314 if (tk[k] - turnTimeL >= 500) { 315 cRotL = 0; 316 motRotL = false; 317 if (motFon) { 318 Command = "w"; 319 } else if (motBon) { 320 Command = "x"; 321 } else { 322 Command = "s"; 323 } 324 } 325 SendCommand(dcL, dcR); 326 } 327 else if (motFon) { 328 Command = "w"; 329 SendCommand(dcL, dcR); 330 } 331 else if (motBon) { 332 Command = "x"; 333 SendCommand(dcL, dcR); 334 } 335 } 336 k++; 337 if (k == Ns) { 338 rpsL = vmL; // store data 339 //cL = 0; 340 //vmL = 0; 341 k = 0; 342 } 343 } 344} 345 346// T2: Control right wheel 347void loop2(100) { 348 static int k = 0; 349 const int Ns = 10; // number of samplings 350 const int dcMax = 4096;// Max duty cycle 351 const int dcMin = 1000;// Min duty cycle 352 const int dcNom = 3600;// Nominal duty cycle 353 const double v_ref = 1.5;// Velocity of reference 354 const double KpR = 150;// K proportional 355 const double KiR = 80;// K integrative 356 //static int dcR = 0; 357 static unsigned long tk[Ns]; 358 static unsigned long ckR[Ns]; // R trans for sampling 359 static double vR[Ns]; // Velocity 360 static double eR[Ns]; // Error 361 static double eiR = 0.0; // Integral of error 362 static double vsR = 0.0; 363 static double vmR = 0.0; 364 static unsigned long cRotR = 0;// Used to control the number of rotation of wheel 365 static bool firstStartR = true; 366 static bool rotRstart = false; 367 static unsigned long AcR; // Rise variation 368 static unsigned long AcT; // Time variation 369 //------------------------------------------------ 370 tk[k] = millis(); 371 ckR[k] = cR; 372 cR = 0; 373 if (firstStartR) { 374 vR[0] = 0; 375 eR[0] = 0; 376 vmR = 0; 377 AcT = 0; 378 AcR = 0; 379 k = 1; 380 firstStartR = false; 381 } 382 else { 383 if (k == 0) { 384 // Compute changes ad time variation 385 AcT = tk[k] - tk[Ns - 1]; 386 AcR = ckR[k]; 387 vR[k] = vR[Ns - 1]; 388 vsR = vR[k]; 389 // Compute Error 390 //eR[k] = v_ref - vR[k]; 391 eR[k] = v_ref - vmR; 392 // Compute integral ofError 393 eiR = (eR[k] + eR[Ns - 1]) * (AcT / 2); 394 } 395 else { 396 // Compute changes ad time variation 397 AcT = tk[k] - tk[k - 1]; 398 AcR = ckR[k]; 399 // Compute velocity of wheels 400 vR[k] = 50.0 * double(AcR) / double(AcT); 401 // Compute mean velocity of wheels 402 vsR += vR[k]; 403 vmR = vsR / double(k + 1); 404 // Compute Error 405 //eR[k] = v_ref - vR[k]; 406 eR[k] = v_ref - vmR; 407 // Compute integral ofError 408 eiR = (eR[k] + eR[k - 1]) * (AcT / 2); 409 } 410 // Compute Duty Cycle 411 dcR = dcNom + int(KpR * eR[k]) + int(KiR * eiR); 412 // Limit DC right wheel 413 if (dcR > dcMax) { 414 dcR = dcMax; 415 } 416 if (dcR < dcMin) { 417 dcR = dcMin; 418 } 419 if (controlStartR) { 420 // Send control command 421 if (motRotR) { 422 //cRotR += AcR; 423 //Serial.println(cRotL); 424 //if (cRotR >= 10) { 425 if (tk[k] - turnTimeR >= 500) { 426 cRotR = 0; 427 motRotR = false; 428 if (motFon) { 429 Command = "w"; 430 } else if (motBon) { 431 Command = "x"; 432 } else { 433 Command = "s"; 434 } 435 } 436 SendCommand(dcL, dcR); 437 } 438 else if (motFon) { 439 Command = "w"; 440 SendCommand(dcL, dcR); 441 } 442 else if (motBon) { 443 Command = "x"; 444 SendCommand(dcL, dcR); 445 } 446 } 447 k++; 448 if (k == Ns) { 449 //rpsR = float(ckR[Ns - 1]) / CFL; 450 rpsR = vmR; // store data 451 //cR = 0; 452 //vmR=0; 453 k = 0; 454 } 455 } 456} 457// T3: Test PC serial and W-Fi serial 458void loop3(50) { 459 static int indx = 0; 460 // Test if serial command is available 461 if (Serial.available() > 0) { 462 Command = Serial.readString(); 463 SendCommand(dc_max, dc_max); 464 } 465 // Test if serial WiFi is available 466 while (Serial1.available () > 0) { 467 Buffer = Serial1.readStringUntil('\r'); 468 Serial.print(Buffer); 469 if ( Buffer.lastIndexOf("+IPD") >= 0 ) { 470 indx = Buffer.lastIndexOf(":"); 471 Command = Buffer.substring(indx + 1); 472 //Serial.print("Wi-Fi command: "); 473 //Serial.print(Command); 474 SendCommand(dc_max, dc_max); 475 Data = "ok"; 476 Buffer = ""; 477 } 478 else if (Buffer.lastIndexOf("Link") >= 0) { 479 //Serial.println(""); 480 //Serial.println("Connected"); 481 Data = "connected"; 482 wifiCon = true; 483 Buffer = ""; 484 } 485 else if (Buffer.lastIndexOf("Unlink") >= 0) { 486 //Serial.println(""); 487 //Serial.println("Disconnected"); 488 //Serial1.flush(); 489 Data = ""; 490 wifiCon = false; 491 Buffer = ""; 492 } 493 else if ( Buffer.lastIndexOf("OK") >= 0 ) { 494 okfound = true; 495 Buffer = ""; 496 } 497 else if ( Buffer.lastIndexOf("ready") >= 0 ) { 498 readyfound = true; 499 Buffer = ""; 500 } 501 //Buffer = ""; 502 } 503} 504// T4: Obstacle detecting 505void loop4(200) { 506 float cmM; 507 static Ultrasonic ultrasonic(ul_trig, ul_eco); 508 cmM = float(ultrasonic.distanceRead(CM)); 509 //Serial.print("Sensore di distanza [cm]: "); 510 //Serial.println(cmMsec); 511 if ( cmM <= 5 ) { 512 Command = "s"; 513 SendCommand(0, 0); 514 } 515} 516// T5: WiFi handle 517void loop5(500) { 518 static WiFiESP8266 wifi(Network, Password, KeyType, Channel); 519 if (!start) { 520 // WiFi initialize 521 wifi.init(); 522 delay(100); 523 wifi.SetSoftAPmode(); 524 delay(100); 525 wifi.CreateServer(); 526 delay(100); 527 Serial.println("START WiFi OK"); 528 start = true; 529 } else { 530 if (Data != "") { 531 if ( !wifiCon && start) { 532 Serial.println(Data); 533 //Serial.println(datastr); 534 Data = ""; 535 } 536 else if ( wifiCon) { //&& Serial1.available () <= 0) { 537 while (Serial1.availableForWrite() <= 0); 538 // WiFi send data 539 wifi.SendDataRequest(Data); 540 //Serial1.flush(); 541 Data = ""; 542 } 543 //Data = ""; 544 } 545 } 546 // WiFi command info 547 if (Command == "1") { 548 wifi.GetIP_ClientPC(); 549 Command = ""; 550 } 551} 552// T6: Data to send creation and GPS handler 553void loop6(500) { 554 static String datastr = ""; 555 static float lat = 0; 556 static float lon = 0; 557 // Connect to the GPS on the hardware port 558 static Adafruit_GPS GPS(&GPSSerial); 559 t = millis(); 560 if (start) { 561 if (!GPSstart ) { 562 GPS.begin(9600); 563 GPS.sendCommand(PMTK_SET_NMEA_OUTPUT_RMCONLY); 564 while (GPSSerial.available()) 565 GPS.read(); 566 Serial.print("\ 567STARTING LOGGING...."); 568 if (GPS.LOCUS_StartLogger()) 569 Serial.println(" STARTED! "); 570 else 571 Serial.println(" no response :("); 572 GPSstart = true; 573 } else { 574 while (GPSSerial.available () > 0) { 575 BufferGPS += GPS.read(); 576 } 577 if (GPS.newNMEAreceived()) { 578 //Serial.println(GPS.lastNMEA()); // sets the newNMEAreceived() flag to false 579 if (!GPS.parse(GPS.lastNMEA())) // sets the newNMEAreceived() flag to false 580 return; // we can fail to parse a sentence in which case we should just wait for another 581 lat = GPS.latitudeDegrees; 582 lon = GPS.longitudeDegrees; 583 GPSfix = GPS.fix; 584 } 585 BufferGPS = ""; 586 } 587 if (Data == "") { 588 if (!wifiCon) { 589 datastr = String(t); 590 datastr += ","; 591 datastr += String(rpsL); 592 datastr += ","; 593 datastr += String(rpsR); 594 Data = datastr; 595 } 596 else { 597 if (GPSfix) { 598 datastr = String(t); 599 datastr += ":"; 600 datastr += String(lat, 6); 601 datastr += ","; 602 datastr += String(lon, 6); 603 Data = datastr; 604 } else { 605 Data = "connected"; 606 } 607 } 608 } 609 } 610}
"TCPClient" class
java
1package com.example.myapplication; 2 3import android.provider.ContactsContract; 4import android.util.Log; 5 6import java.io.BufferedReader; 7import java.io.BufferedWriter; 8import java.io.DataInputStream; 9import java.io.DataOutputStream; 10import java.io.IOException; 11import java.io.InputStreamReader; 12import java.io.OutputStreamWriter; 13import java.io.PrintWriter; 14import java.net.InetAddress; 15import java.net.InetSocketAddress; 16import java.net.Socket; 17import java.net.SocketImpl; 18 19import static java.io.DataInputStream.readUTF; 20 21public class TCPClient { 22 23 public static final String SERVER_IP = "192.168.4.1"; //"192.168.4.1"; 24 public static final int SERVER_PORT = 333; 25 public Socket socket; 26 // while this is true, the client will continue running 27 private boolean mRun = false; 28 // sends message received notifications 29 private OnMessageReceived mMessageListener; 30 private DataOutputStream DataOut; 31 private DataInputStream DataIn; 32 private String msg; 33 byte[] buf; 34 private String cmd=""; 35 private boolean sending=false; 36 /** 37 * Constructor of the class. OnMessagedReceived listens for the messages received from server 38 */ 39 public TCPClient(OnMessageReceived listener) { 40 mMessageListener = listener; 41 } 42 /** 43 * Sends the message entered by client to the server 44 * 45 * @param message text entered by client 46 */ 47 48 49 public void sendMessage(String message) throws IOException { 50 cmd=message; 51 } 52 /* 53 public void sendMessage(final String message) { 54 Runnable runnable = new Runnable() { 55 @Override 56 public void run() { 57 if (DataOut != null && msg==null) { 58 try { 59 Log.i("Debug", "Send command"); 60 DataOut.write(message.getBytes(),0,message.length()); 61 DataOut.flush(); 62 //DataOut.close(); 63 } catch (IOException e) { 64 e.printStackTrace(); 65 } 66 } 67 } 68 }; 69 Thread thread = new Thread(runnable); 70 thread.start(); 71 } 72 */ 73 /** 74 * Close the connection and release the members 75 */ 76 public void stopClient() throws IOException { 77 Log.i("Debug", "Stop Client"); 78 // send mesage that we are closing the connection 79 //sendMessage(Constants.CLOSED_CONNECTION + "Kazy"); 80 mRun = false; 81 if (DataOut != null && socket!=null) { 82 DataOut.flush(); 83 DataOut.close(); 84 } 85 if (DataIn != null && socket!=null) { 86 DataIn.close(); 87 } 88 socket.close(); 89 mMessageListener = null; 90 DataIn=null; 91 DataOut = null; 92 msg = null; 93 cmd=""; 94 //socket=null; 95 } 96 97 public void run() { 98 int nb; 99 mRun = true; 100 try { 101 //here you must put your computer's IP address. 102 InetAddress serverAddr = InetAddress.getByName(SERVER_IP); 103 Log.i("Debug", "Connecting..."); 104 // use to send the command to server 105 //create a socket to make the connection with the server 106 //socket = new Socket(serverAddr,SERVER_PORT); 107 //if (socket==null) { 108 socket = new Socket(); 109 socket.connect(new InetSocketAddress(SERVER_IP, SERVER_PORT), 1000 * 60); 110 //} 111 try { 112 DataOut = new DataOutputStream(socket.getOutputStream()); 113 //receives the message which the server sends back 114 //mBufferIn = new BufferedReader(new InputStreamReader(socket.getInputStream())); 115 DataIn = new DataInputStream(socket.getInputStream()); 116 Log.i("Debug", "Connecting OK"); 117 buf= new byte[1024]; 118 Log.i("Debug", "Inside try catch"); 119 //in this while the client listens for the messages sent by the server 120 while (mRun) { 121 if (DataOut != null && cmd != "") { 122 DataOut.write(cmd.getBytes(), 0, cmd.length()); 123 DataOut.flush(); 124 sending=true; 125 //cmd = ""; 126 Log.i("Debug", "Send cmd: " + cmd); 127 } 128 if (!socket.isClosed()) { 129 nb = DataIn.read(buf); 130 if (nb != -1) { 131 msg = new String(buf, 0, nb); 132 if (sending && msg.contains("ok")){ 133 sending=false; 134 cmd=""; 135 } else if (!msg.contains("ok")){ 136 mMessageListener.messageReceived(msg); 137 } 138 Log.i("Debug", "Recived : " + msg); 139 msg = null; 140 } 141 } 142 } 143 //Log.i("Debug", "Received Message:"); 144 } catch (Exception e) { 145 Log.e("Debug", "Send Error", e); 146 }finally { 147 //the socket must be closed. It is not possible to reconnect to this socket 148 // after it is closed, which means a new socket instance has to be created. 149 /* 150 DataOut.flush(); 151 DataOut.close(); 152 DataIn.close(); 153 socket.close(); 154 */ 155 } 156 } catch (Exception e) { 157 Log.e("Debug", "Connecting Error", e); 158 } 159 } 160 161 //Declare the interface. The method messageReceived(String message) will must be implemented in the MyActivity 162 //class at on asynckTask doInBackground 163 164 public interface OnMessageReceived { 165 public void messageReceived(String message); 166 } 167 168}
MainActivity.java
java
1package com.example.myapplication; 2 3 4import android.Manifest; 5import android.content.BroadcastReceiver; 6import android.content.Context; 7import android.content.Intent; 8import android.content.IntentFilter; 9import android.content.pm.PackageManager; 10import android.graphics.Color; 11import android.net.wifi.ScanResult; 12import android.net.wifi.WifiConfiguration; 13import android.net.wifi.WifiManager; 14import android.os.AsyncTask; 15import android.support.v4.app.ActivityCompat; 16import android.support.v4.app.FragmentActivity; 17import android.support.v4.content.ContextCompat; 18import android.support.v7.app.AppCompatActivity; 19import android.os.Bundle; 20import android.util.Log; 21import android.view.MotionEvent; 22import android.view.View; 23import android.widget.ArrayAdapter; 24import android.widget.Button; 25import android.widget.ListView; 26import android.widget.TextView; 27import android.widget.Toast; 28 29import com.google.android.gms.maps.CameraUpdateFactory; 30import com.google.android.gms.maps.GoogleMap; 31import com.google.android.gms.maps.MapFragment; 32import com.google.android.gms.maps.OnMapReadyCallback; 33import com.google.android.gms.maps.model.LatLng; 34import com.google.android.gms.maps.model.MarkerOptions; 35import com.google.android.gms.maps.model.Polyline; 36import com.google.android.gms.maps.model.PolylineOptions; 37 38import java.io.BufferedWriter; 39import java.io.IOException; 40import java.io.OutputStreamWriter; 41import java.io.PrintWriter; 42import java.net.InetAddress; 43import java.net.InetSocketAddress; 44import java.net.Socket; 45import java.net.UnknownHostException; 46import java.util.ArrayList; 47import java.util.List; 48 49//public class MainActivity extends AppCompatActivity { 50public class MainActivity extends FragmentActivity implements OnMapReadyCallback { 51 final String AccessWifi = Manifest.permission.ACCESS_WIFI_STATE; 52 final String ChangeWifi = Manifest.permission.CHANGE_WIFI_STATE; 53 final String CoarseLoc = Manifest.permission.ACCESS_COARSE_LOCATION; 54 final String FineLoc = Manifest.permission.ACCESS_FINE_LOCATION; 55 final String ChangeNet = Manifest.permission.CHANGE_NETWORK_STATE; 56 final String AccessNet = Manifest.permission.ACCESS_NETWORK_STATE; 57 final String Internet = Manifest.permission.INTERNET; 58 public static final int ID_PERM=1; 59 60 WifiManager wifi; 61 ListView lv; 62 int size = 0; 63 List<ScanResult> results; 64 ArrayList<String> arraylist = new ArrayList<>(); 65 ArrayAdapter adapter; 66 public boolean findWifi=true; 67 public boolean connected=false; 68 //private static final int SERVERPORT = 333; 69 //private static final String SERVER_IP = "192.168.4.1"; 70 public TCPClient mTcpClient; 71 72 private GoogleMap mMap; 73 private Polyline polyline; 74 private PolylineOptions polyline_opt; 75 private List<LatLng> points; 76 TextView textState; 77 TextView textCmd; 78 Button butLstop; 79 Button butRstop; 80 81 /* 82 @Override 83 public void onRequestPermissionsResult(int requestCode, String permissions[], int[] grantResults) { 84 switch (requestCode) { 85 case ID_PERM: { 86 if (grantResults.length > 0 && grantResults[0] == PackageManager.PERMISSION_GRANTED) { 87 // permission concessa: eseguiamo il codice 88 89 } else { 90 // permission negata: provvediamo in qualche maniera 91 } 92 return; 93 } 94 } 95 } 96 */ 97 98 @Override 99 protected void onCreate(Bundle savedInstanceState) { 100 super.onCreate(savedInstanceState); 101 setContentView(R.layout.activity_main); 102 // Permessi 103 104 int permiStateAWifi = ContextCompat.checkSelfPermission(this, AccessWifi); 105 int permiStateCWifi = ContextCompat.checkSelfPermission(this, ChangeWifi); 106 int permiStateCLoc = ContextCompat.checkSelfPermission(this, CoarseLoc); 107 int permiStateFLoc = ContextCompat.checkSelfPermission(this, FineLoc); 108 int permiStateCNet = ContextCompat.checkSelfPermission(this, ChangeNet); 109 int permiStateANet = ContextCompat.checkSelfPermission(this, AccessNet); 110 int permiStateInt = ContextCompat.checkSelfPermission(this, Internet); 111 112 if (permiStateAWifi != PackageManager.PERMISSION_GRANTED && permiStateCWifi != PackageManager.PERMISSION_GRANTED && 113 permiStateCLoc != PackageManager.PERMISSION_GRANTED && permiStateFLoc != PackageManager.PERMISSION_GRANTED 114 && permiStateCNet != PackageManager.PERMISSION_GRANTED && permiStateInt != PackageManager.PERMISSION_GRANTED 115 && permiStateANet != PackageManager.PERMISSION_GRANTED) { 116 ActivityCompat.requestPermissions(this, new String[]{AccessWifi, ChangeWifi, CoarseLoc, FineLoc, ChangeNet,AccessNet, Internet},ID_PERM); 117 } 118 119 /**/ 120 wifi = (WifiManager) getApplicationContext().getSystemService(Context.WIFI_SERVICE); 121 if (wifi.isWifiEnabled() == false) 122 { 123 Toast.makeText(getApplicationContext(), "wifi is disabled..making it enabled", Toast.LENGTH_LONG).show(); 124 wifi.setWifiEnabled(true); 125 } 126 IntentFilter intentFilter = new IntentFilter(); 127 intentFilter.addAction(wifi.SCAN_RESULTS_AVAILABLE_ACTION); 128 getApplicationContext().registerReceiver(wifiScanReceiver, intentFilter); 129 130 //scanWifiNetworks(); 131 lv = (ListView)findViewById(R.id.list); 132 adapter = new ArrayAdapter<String>(this,android.R.layout.simple_list_item_1,arraylist); 133 lv.setAdapter(adapter); 134 135 MapFragment mapFragment = (MapFragment) getFragmentManager().findFragmentById(R.id.map); 136 mapFragment.getMapAsync(this); 137 points= new ArrayList<>(); 138 textState= findViewById(R.id.textView2); 139 textCmd= findViewById(R.id.textView3); 140 butLstop=findViewById(R.id.button10); 141 butRstop=findViewById(R.id.button11); 142 143 144 butLstop.setOnTouchListener(new View.OnTouchListener() { 145 @Override 146 public boolean onTouch(View v, MotionEvent event) { 147 if(event.getAction() == MotionEvent.ACTION_DOWN) { 148 textCmd.setText("L STOP"); 149 if (mTcpClient != null) { 150 try { 151 mTcpClient.sendMessage("a"); 152 } catch (IOException e) { 153 e.printStackTrace(); 154 } 155 } 156 } else if (event.getAction() == MotionEvent.ACTION_UP) { 157 if (textCmd.getText()=="L STOP" && mTcpClient != null) { 158 try { 159 mTcpClient.sendMessage("w"); 160 textCmd.setText("Forward"); 161 } catch (IOException e) { 162 e.printStackTrace(); 163 } 164 } 165 } 166 167 return true; 168 } 169 }); 170 171 butRstop.setOnTouchListener(new View.OnTouchListener() { 172 @Override 173 public boolean onTouch(View v, MotionEvent event) { 174 if(event.getAction() == MotionEvent.ACTION_DOWN) { 175 textCmd.setText("R STOP"); 176 if (mTcpClient != null) { 177 try { 178 mTcpClient.sendMessage("d"); 179 } catch (IOException e) { 180 e.printStackTrace(); 181 } 182 } 183 } else if (event.getAction() == MotionEvent.ACTION_UP) { 184 if (textCmd.getText()=="R STOP" && mTcpClient != null) { 185 try { 186 mTcpClient.sendMessage("w"); 187 textCmd.setText("Forward"); 188 } catch (IOException e) { 189 e.printStackTrace(); 190 } 191 } 192 } 193 194 return true; 195 } 196 }); 197 } 198 199 @Override 200 public void onMapReady(GoogleMap googleMap) { 201 mMap = googleMap; 202 //polyline_opt = new PolylineOptions().width(5).color(Color.BLUE); 203 //polyline = mMap.addPolyline(polyline_opt); 204 } 205 /* 206 public void addToMap(View view){ 207 Polyline line = mMap.addPolyline(new PolylineOptions() 208 .add(new LatLng(41, 9), new LatLng(42, 9)) 209 .width(5) 210 .color(Color.RED)); 211 212 } 213 */ 214 BroadcastReceiver wifiScanReceiver = new BroadcastReceiver() { 215 @Override 216 public void onReceive(Context c, Intent intent) { 217 boolean success = intent.getBooleanExtra(wifi.EXTRA_RESULTS_UPDATED, false); 218 if (success && !findWifi) { 219 scanSuccess(); 220 } 221 } 222 }; 223 224 225 public void WifiCon (View view){ 226 findWifi=false; 227 arraylist.clear(); 228 boolean success = wifi.startScan(); 229 if (!success) { 230 // scan failure handling 231 Toast.makeText(this, "Scan Failure", Toast.LENGTH_SHORT).show(); 232 } 233 } 234 235 236 private void scanSuccess() { 237 results=wifi.getScanResults(); 238 size=results.size(); 239 //Toast.makeText(this, "Scanning.... " + size, Toast.LENGTH_SHORT).show(); 240 for (ScanResult result : results) { 241 //arraylist.add(result.SSID); 242 //adapter.notifyDataSetChanged(); 243 if (result.SSID.equals("INO_ESP8266")){ 244 Toast.makeText(this, "Trovato ", Toast.LENGTH_SHORT).show(); 245 setSsidAndPassword(getApplicationContext(),"INO_ESP8266","12345678",wifi); 246 break; 247 } 248 } 249 //getApplicationContext().unregisterReceiver(wifiScanReceiver); 250 //lv.setAdapter(adapter); 251 } 252 253 254 public boolean setSsidAndPassword(Context context, String ssid, String ssidPassword, WifiManager wifi) { 255 try { 256 257 WifiConfiguration conf = new WifiConfiguration(); 258 conf.SSID = "\\"" + ssid+ "\\""; 259 //conf.preSharedKey = "\\""+ ssidPassword +"\\""; 260 //conf.preSharedKey = null; 261 conf.allowedKeyManagement.set(WifiConfiguration.KeyMgmt.NONE); 262 int idNet=wifi.addNetwork(conf); 263 if (idNet>=0){ 264 findWifi=true; 265 wifi.disconnect(); 266 wifi.enableNetwork(idNet, true); 267 wifi.reconnect(); 268 } 269 return true; 270 } catch (Exception e) { 271 e.printStackTrace(); 272 return false; 273 } 274 275 } 276 277 278 public void ArdConDis (View view) throws IOException{ 279 if (!connected) { 280 arraylist.clear(); 281 adapter.notifyDataSetChanged(); 282 new connectTask().execute(""); 283 connected=true; 284 } else { 285 286 if (mTcpClient != null) { 287 mTcpClient.stopClient(); 288 textState.setText("Disconnected"); 289 connected=false; 290 } 291 } 292 } 293 294 /* 295 public class connectTask extends AsyncTask<String,Void,TCPClient> { 296 @Override 297 protected TCPClient doInBackground(String... message) { 298 mTcpClient = new TCPClient(); 299 mTcpClient.run(); 300 return null; 301 } 302 } 303 */ 304 305 public class connectTask extends AsyncTask<String,String,TCPClient> { 306 @Override 307 protected TCPClient doInBackground(String... message) { 308 //we create a TCPClient object and 309 mTcpClient = new TCPClient(new TCPClient.OnMessageReceived() { 310 @Override 311 //here the messageReceived method is implemented 312 public void messageReceived(String message) { 313 //this method calls the onProgressUpdate 314 publishProgress(message); 315 } 316 }); 317 mTcpClient.run(); 318 return null; 319 } 320 321 322 @Override 323 protected void onProgressUpdate(String... values) { 324 super.onProgressUpdate(values); 325 String strInput; 326 strInput=values[0]; 327 //in the arrayList we add the messaged received from server 328 arraylist.add(strInput); 329 adapter.notifyDataSetChanged(); 330 if (strInput.contains("connected")){ 331 textState.setText("Connected"); 332 } else { 333 updateLine(strInput); 334 } 335 } 336 } 337 338 public void updateLine(String latlon){ 339 int firsindx=latlon.indexOf(':'); 340 int lastindx=latlon.indexOf(','); 341 float lat = Float.parseFloat(latlon.substring(firsindx+1,lastindx-1)); 342 float lon = Float.parseFloat(latlon.substring(lastindx+1)); 343 LatLng actualLatLon = new LatLng(lat, lon); 344 points.add(actualLatLon); 345 polyline_opt = new PolylineOptions().width(10).color(Color.BLUE); 346 if (points.size()>2) { 347 polyline_opt.addAll(points); 348 polyline = mMap.addPolyline(polyline_opt); 349 } 350 mMap.moveCamera(CameraUpdateFactory.newLatLngZoom(actualLatLon,17.0f)); 351 352 } 353 354 355 public void sendLforward(View view) throws IOException { 356 textCmd.setText("Left forward"); 357 if (mTcpClient != null) { 358 mTcpClient.sendMessage("q"); 359 Toast.makeText(this, "Send q", Toast.LENGTH_SHORT).show(); 360 } 361 } 362 363 public void sendLback(View view) throws IOException{ 364 textCmd.setText("Left back"); 365 if (mTcpClient != null) { 366 mTcpClient.sendMessage("z"); 367 Toast.makeText(this, "Send z", Toast.LENGTH_SHORT).show(); 368 } 369 } 370 371 public void sendRforward(View view) throws IOException{ 372 textCmd.setText("Rigth forward"); 373 if (mTcpClient != null) { 374 mTcpClient.sendMessage("e"); 375 Toast.makeText(this, "Send e", Toast.LENGTH_SHORT).show(); 376 } 377 } 378 379 public void sendRback(View view) throws IOException{ 380 textCmd.setText("Rigth back"); 381 if (mTcpClient != null) { 382 mTcpClient.sendMessage("c"); 383 Toast.makeText(this, "Send c", Toast.LENGTH_SHORT).show(); 384 } 385 } 386 387 public void sendStop(View view) throws IOException{ 388 textCmd.setText("Rigth back"); 389 if (mTcpClient != null) { 390 mTcpClient.sendMessage("s"); 391 Toast.makeText(this, "Send s", Toast.LENGTH_SHORT).show(); 392 } 393 } 394 395 public void sendForw(View view) throws IOException{ 396 textCmd.setText("Forward"); 397 if (mTcpClient != null) { 398 mTcpClient.sendMessage("w"); 399 Toast.makeText(this, "Send w", Toast.LENGTH_SHORT).show(); 400 } 401 } 402 public void sendBack(View view) throws IOException{ 403 textCmd.setText("Back"); 404 if (mTcpClient != null) { 405 mTcpClient.sendMessage("x"); 406 Toast.makeText(this, "Send x", Toast.LENGTH_SHORT).show(); 407 } 408 } 409} 410 411 412 413 414 415 416 417
The "Motor" library
c_cpp
1/* 2 * Motor.cpp 3 * 4*/ 5//home/manu/.arduino15/packages/arduino/hardware/sam/1.6.11/cores/arduino 6#include <Arduino.h> 7#include "Motor.h" 8 9Motor::Motor(int enPin,int APin, int BPin) { 10 en=enPin; 11 A=APin; 12 B=BPin; 13 analogWrite(en,0); 14} 15 16//_________________________________ATTUAZIONE MOTORE_________________________________ 17void Motor::forward(int D){ 18 analogWrite(en,D); 19 digitalWrite(A,LOW); 20 digitalWrite(B,HIGH); 21} 22 23void Motor::back(int D){ 24 analogWrite(en,D); 25 digitalWrite(A,HIGH); 26 digitalWrite(B,LOW); 27} 28 29 30void Motor::stopMot(){ 31 analogWrite(en,0); 32} 33
"TCPClient" class
java
1package com.example.myapplication; 2 3import android.provider.ContactsContract; 4import android.util.Log; 5 6import java.io.BufferedReader; 7import java.io.BufferedWriter; 8import java.io.DataInputStream; 9import java.io.DataOutputStream; 10import java.io.IOException; 11import java.io.InputStreamReader; 12import java.io.OutputStreamWriter; 13import java.io.PrintWriter; 14import java.net.InetAddress; 15import java.net.InetSocketAddress; 16import java.net.Socket; 17import java.net.SocketImpl; 18 19import static java.io.DataInputStream.readUTF; 20 21public class TCPClient { 22 23 public static final String SERVER_IP = "192.168.4.1"; //"192.168.4.1"; 24 public static final int SERVER_PORT = 333; 25 public Socket socket; 26 // while this is true, the client will continue running 27 private boolean mRun = false; 28 // sends message received notifications 29 private OnMessageReceived mMessageListener; 30 private DataOutputStream DataOut; 31 private DataInputStream DataIn; 32 private String msg; 33 byte[] buf; 34 private String cmd=""; 35 private boolean sending=false; 36 /** 37 * Constructor of the class. OnMessagedReceived listens for the messages received from server 38 */ 39 public TCPClient(OnMessageReceived listener) { 40 mMessageListener = listener; 41 } 42 /** 43 * Sends the message entered by client to the server 44 * 45 * @param message text entered by client 46 */ 47 48 49 public void sendMessage(String message) throws IOException { 50 cmd=message; 51 } 52 /* 53 public void sendMessage(final String message) { 54 Runnable runnable = new Runnable() { 55 @Override 56 public void run() { 57 if (DataOut != null && msg==null) { 58 try { 59 Log.i("Debug", "Send command"); 60 DataOut.write(message.getBytes(),0,message.length()); 61 DataOut.flush(); 62 //DataOut.close(); 63 } catch (IOException e) { 64 e.printStackTrace(); 65 } 66 } 67 } 68 }; 69 Thread thread = new Thread(runnable); 70 thread.start(); 71 } 72 */ 73 /** 74 * Close the connection and release the members 75 */ 76 public void stopClient() throws IOException { 77 Log.i("Debug", "Stop Client"); 78 // send mesage that we are closing the connection 79 //sendMessage(Constants.CLOSED_CONNECTION + "Kazy"); 80 mRun = false; 81 if (DataOut != null && socket!=null) { 82 DataOut.flush(); 83 DataOut.close(); 84 } 85 if (DataIn != null && socket!=null) { 86 DataIn.close(); 87 } 88 socket.close(); 89 mMessageListener = null; 90 DataIn=null; 91 DataOut = null; 92 msg = null; 93 cmd=""; 94 //socket=null; 95 } 96 97 public void run() { 98 int nb; 99 mRun = true; 100 try { 101 //here you must put your computer's IP address. 102 InetAddress serverAddr = InetAddress.getByName(SERVER_IP); 103 Log.i("Debug", "Connecting..."); 104 // use to send the command to server 105 //create a socket to make the connection with the server 106 //socket = new Socket(serverAddr,SERVER_PORT); 107 //if (socket==null) { 108 socket = new Socket(); 109 socket.connect(new InetSocketAddress(SERVER_IP, SERVER_PORT), 1000 * 60); 110 //} 111 try { 112 DataOut = new DataOutputStream(socket.getOutputStream()); 113 //receives the message which the server sends back 114 //mBufferIn = new BufferedReader(new InputStreamReader(socket.getInputStream())); 115 DataIn = new DataInputStream(socket.getInputStream()); 116 Log.i("Debug", "Connecting OK"); 117 buf= new byte[1024]; 118 Log.i("Debug", "Inside try catch"); 119 //in this while the client listens for the messages sent by the server 120 while (mRun) { 121 if (DataOut != null && cmd != "") { 122 DataOut.write(cmd.getBytes(), 0, cmd.length()); 123 DataOut.flush(); 124 sending=true; 125 //cmd = ""; 126 Log.i("Debug", "Send cmd: " + cmd); 127 } 128 if (!socket.isClosed()) { 129 nb = DataIn.read(buf); 130 if (nb != -1) { 131 msg = new String(buf, 0, nb); 132 if (sending && msg.contains("ok")){ 133 sending=false; 134 cmd=""; 135 } else if (!msg.contains("ok")){ 136 mMessageListener.messageReceived(msg); 137 } 138 Log.i("Debug", "Recived : " + msg); 139 msg = null; 140 } 141 } 142 } 143 //Log.i("Debug", "Received Message:"); 144 } catch (Exception e) { 145 Log.e("Debug", "Send Error", e); 146 }finally { 147 //the socket must be closed. It is not possible to reconnect to this socket 148 // after it is closed, which means a new socket instance has to be created. 149 /* 150 DataOut.flush(); 151 DataOut.close(); 152 DataIn.close(); 153 socket.close(); 154 */ 155 } 156 } catch (Exception e) { 157 Log.e("Debug", "Connecting Error", e); 158 } 159 } 160 161 //Declare the interface. The method messageReceived(String message) will must be implemented in the MyActivity 162 //class at on asynckTask doInBackground 163 164 public interface OnMessageReceived { 165 public void messageReceived(String message); 166 } 167 168}
The "wifi" lib
c_cpp
1/* 2 * WiFiESP8266.cpp 3 * 4*/ 5#include <Arduino.h> 6#include <string> 7#include <stdio.h> 8//#include <iostream> 9#include "WiFiESP8266.h" 10using namespace std; 11 12// char*=std::string& 13WiFiESP8266::WiFiESP8266(String Network,String Password,String Channel,String KeyType) { 14 Net=Network; 15 Pas=Password; 16 Cha=Channel; 17 KeyTy=KeyType; 18 buffer=""; 19 connected=false; 20} 21 22void WiFiESP8266::init(){ 23 //Serial1.begin (115200); 24 //restart ESP8266 25 Serial1.print ("AT+RST\ "); 26 delay(10); 27} 28 29void WiFiESP8266::SetSoftAPmode(){ 30 String Com; 31 //Serial.println("Input followin information"); 32 Serial.print ("Network: "); 33 //Network=ReadString(); 34 Serial.println (Net); 35 Serial.print ("Password: "); 36 //Password=ReadString(); 37 Serial.println (Pas); 38 Serial.print ("Channel: "); 39 //Channel=ReadString(); 40 Serial.println (Cha); 41 Serial.print ("Key Type: "); 42 //KeyType=ReadString(); 43 Serial.println (KeyTy); 44 //Wi-Fi mode station-softAP (STA-SAP) 45 Serial1.print ("AT+CWMODE=3\ "); 46 delay(10); 47 // Set configuration of SAP mode 48 Com ="AT+CWSAP=\\""; 49 Com +=Net; 50 Com +="\\",\\""; 51 Com +=Pas; 52 Com +="\\","; 53 Com +=Cha; 54 Com +=","; 55 Com +=KeyTy; 56 Com +="\ "; 57 Serial1.print(Com); 58 delay(10); 59 //Serial1.print("AT+RST\ "); 60} 61 62void WiFiESP8266::CreateServer(){ 63 Serial.println("Create server: "); 64 // enable multi connection 65 Serial1.print("AT+CIPMUX=1\ "); 66 delay(10); 67 //delay(25); 68 // CIPSERVER=mode,port 69 // mode=1: create server; 70 // mode=0: delete serever; 71 // port: number of port (333 defoult) 72 Serial1.print("AT+CIPSERVER=1,333\ "); 73 delay(10); 74 // set timeout time in a range (0-7200 [second]) 75 Serial1.print("AT+CIPSTO=120\ "); 76 delay(10); 77} 78 79void WiFiESP8266::GetIP_ClientPC(){ 80 Serial.print("IP rover: "); 81 Serial1.print("AT+CIPSTATUS\ "); 82 delay(10); 83 Serial.println(""); 84 Serial.print("IP connesso: "); 85 Serial1.print("AT+CWLIF\ "); 86 delay(10); 87} 88/* 89void ESP8266::WiFi_SendData(){ 90 if (connected){ 91 Serial.println("Data to send:"); 92 if(Serial.available()>0){ 93 data=Serial.readString(); 94 Serial.println(data); 95 SendData(data); 96 } 97 } 98} 99 100void ESP8266::SendData(String dat){ 101 String Com; 102 bool sendper=true; 103 Com="AT+CIPSEND=0,"; 104 Com +=String(dat.length()); 105 Com += "\ "; 106 //Serial1.print("AT+CIPSEND=0,"); 107 //Serial1.print(dat.length()); 108 //Serial1.print("\ "); 109 Serial1.print(Com); 110 while (sendper){ 111 if (Serial1.find ('>')){ 112 Serial1.print(dat); 113 Serial1.print("\ "); 114 //Serial.print (" > "); 115 //Serial.print(dat); 116 sendper=false; 117 } 118 } 119}*/ 120void WiFiESP8266::SendDataRequest(String dat){ 121 String Com; 122 Com="AT+CIPSEND=0,"; 123 Com +=String(dat.length()); 124 Com += "\ "; 125 Serial1.print(Com); 126 Com=dat; 127 Com+="\ "; 128 if ( Serial1.find('>') ) { 129 Serial1.print(Com); 130 } 131} 132 133void WiFiESP8266::TestSerialWiFi(){ 134 while (Serial1.available () > 0){ 135 buffer=Serial1.readStringUntil('\r'); 136 //Serial.print(buffer); 137 if (buffer=="Link"){ 138 //Serial.println(""); 139 //Serial.println("Connesso"); 140 connected=true; 141 } 142 } 143} 144 145void WiFiESP8266::CloseTCPconnection(){ 146 Serial.println("Close:"); 147 Serial1.print("AT+CIPCLOSE\ "); 148 delay(10); 149} 150
MainActivity.java
java
1package com.example.myapplication; 2 3 4import android.Manifest; 5import 6 android.content.BroadcastReceiver; 7import android.content.Context; 8import 9 android.content.Intent; 10import android.content.IntentFilter; 11import android.content.pm.PackageManager; 12import 13 android.graphics.Color; 14import android.net.wifi.ScanResult; 15import android.net.wifi.WifiConfiguration; 16import 17 android.net.wifi.WifiManager; 18import android.os.AsyncTask; 19import android.support.v4.app.ActivityCompat; 20import 21 android.support.v4.app.FragmentActivity; 22import android.support.v4.content.ContextCompat; 23import 24 android.support.v7.app.AppCompatActivity; 25import android.os.Bundle; 26import 27 android.util.Log; 28import android.view.MotionEvent; 29import android.view.View; 30import 31 android.widget.ArrayAdapter; 32import android.widget.Button; 33import android.widget.ListView; 34import 35 android.widget.TextView; 36import android.widget.Toast; 37 38import com.google.android.gms.maps.CameraUpdateFactory; 39import 40 com.google.android.gms.maps.GoogleMap; 41import com.google.android.gms.maps.MapFragment; 42import 43 com.google.android.gms.maps.OnMapReadyCallback; 44import com.google.android.gms.maps.model.LatLng; 45import 46 com.google.android.gms.maps.model.MarkerOptions; 47import com.google.android.gms.maps.model.Polyline; 48import 49 com.google.android.gms.maps.model.PolylineOptions; 50 51import java.io.BufferedWriter; 52import 53 java.io.IOException; 54import java.io.OutputStreamWriter; 55import java.io.PrintWriter; 56import 57 java.net.InetAddress; 58import java.net.InetSocketAddress; 59import java.net.Socket; 60import 61 java.net.UnknownHostException; 62import java.util.ArrayList; 63import java.util.List; 64 65//public 66 class MainActivity extends AppCompatActivity { 67public class MainActivity extends 68 FragmentActivity implements OnMapReadyCallback { 69 final String AccessWifi 70 = Manifest.permission.ACCESS_WIFI_STATE; 71 final String ChangeWifi = Manifest.permission.CHANGE_WIFI_STATE; 72 73 final String CoarseLoc = Manifest.permission.ACCESS_COARSE_LOCATION; 74 final 75 String FineLoc = Manifest.permission.ACCESS_FINE_LOCATION; 76 final String ChangeNet 77 = Manifest.permission.CHANGE_NETWORK_STATE; 78 final String AccessNet = Manifest.permission.ACCESS_NETWORK_STATE; 79 80 final String Internet = Manifest.permission.INTERNET; 81 public static final 82 int ID_PERM=1; 83 84 WifiManager wifi; 85 ListView lv; 86 int size 87 = 0; 88 List<ScanResult> results; 89 ArrayList<String> arraylist = new ArrayList<>(); 90 91 ArrayAdapter adapter; 92 public boolean findWifi=true; 93 public boolean 94 connected=false; 95 //private static final int SERVERPORT = 333; 96 //private 97 static final String SERVER_IP = "192.168.4.1"; 98 public TCPClient mTcpClient; 99 100 101 private GoogleMap mMap; 102 private Polyline polyline; 103 private PolylineOptions 104 polyline_opt; 105 private List<LatLng> points; 106 TextView textState; 107 108 TextView textCmd; 109 Button butLstop; 110 Button butRstop; 111 112 /* 113 114 @Override 115 public void onRequestPermissionsResult(int requestCode, String 116 permissions[], int[] grantResults) { 117 switch (requestCode) { 118 case 119 ID_PERM: { 120 if (grantResults.length > 0 && grantResults[0] == 121 PackageManager.PERMISSION_GRANTED) { 122 // permission concessa: 123 eseguiamo il codice 124 125 } else { 126 // permission 127 negata: provvediamo in qualche maniera 128 } 129 return; 130 131 } 132 } 133 } 134 */ 135 136 @Override 137 protected 138 void onCreate(Bundle savedInstanceState) { 139 super.onCreate(savedInstanceState); 140 141 setContentView(R.layout.activity_main); 142 // Permessi 143 144 int 145 permiStateAWifi = ContextCompat.checkSelfPermission(this, AccessWifi); 146 int 147 permiStateCWifi = ContextCompat.checkSelfPermission(this, ChangeWifi); 148 int 149 permiStateCLoc = ContextCompat.checkSelfPermission(this, CoarseLoc); 150 int 151 permiStateFLoc = ContextCompat.checkSelfPermission(this, FineLoc); 152 int 153 permiStateCNet = ContextCompat.checkSelfPermission(this, ChangeNet); 154 int 155 permiStateANet = ContextCompat.checkSelfPermission(this, AccessNet); 156 int 157 permiStateInt = ContextCompat.checkSelfPermission(this, Internet); 158 159 if 160 (permiStateAWifi != PackageManager.PERMISSION_GRANTED && permiStateCWifi != PackageManager.PERMISSION_GRANTED 161 && 162 permiStateCLoc != PackageManager.PERMISSION_GRANTED && permiStateFLoc 163 != PackageManager.PERMISSION_GRANTED 164 && permiStateCNet != PackageManager.PERMISSION_GRANTED 165 && permiStateInt != PackageManager.PERMISSION_GRANTED 166 && permiStateANet 167 != PackageManager.PERMISSION_GRANTED) { 168 ActivityCompat.requestPermissions(this, 169 new String[]{AccessWifi, ChangeWifi, CoarseLoc, FineLoc, ChangeNet,AccessNet, Internet},ID_PERM); 170 171 } 172 173 /**/ 174 wifi = (WifiManager) getApplicationContext().getSystemService(Context.WIFI_SERVICE); 175 176 if (wifi.isWifiEnabled() == false) 177 { 178 Toast.makeText(getApplicationContext(), 179 "wifi is disabled..making it enabled", Toast.LENGTH_LONG).show(); 180 wifi.setWifiEnabled(true); 181 182 } 183 IntentFilter intentFilter = new IntentFilter(); 184 intentFilter.addAction(wifi.SCAN_RESULTS_AVAILABLE_ACTION); 185 186 getApplicationContext().registerReceiver(wifiScanReceiver, intentFilter); 187 188 189 //scanWifiNetworks(); 190 lv = (ListView)findViewById(R.id.list); 191 192 adapter = new ArrayAdapter<String>(this,android.R.layout.simple_list_item_1,arraylist); 193 194 lv.setAdapter(adapter); 195 196 MapFragment mapFragment = (MapFragment) 197 getFragmentManager().findFragmentById(R.id.map); 198 mapFragment.getMapAsync(this); 199 200 points= new ArrayList<>(); 201 textState= findViewById(R.id.textView2); 202 203 textCmd= findViewById(R.id.textView3); 204 butLstop=findViewById(R.id.button10); 205 206 butRstop=findViewById(R.id.button11); 207 208 209 butLstop.setOnTouchListener(new 210 View.OnTouchListener() { 211 @Override 212 public boolean 213 onTouch(View v, MotionEvent event) { 214 if(event.getAction() == 215 MotionEvent.ACTION_DOWN) { 216 textCmd.setText("L STOP"); 217 218 if (mTcpClient != null) { 219 try { 220 221 mTcpClient.sendMessage("a"); 222 } 223 catch (IOException e) { 224 e.printStackTrace(); 225 226 } 227 } 228 } else if 229 (event.getAction() == MotionEvent.ACTION_UP) { 230 if (textCmd.getText()=="L 231 STOP" && mTcpClient != null) { 232 try { 233 mTcpClient.sendMessage("w"); 234 235 textCmd.setText("Forward"); 236 } 237 catch (IOException e) { 238 e.printStackTrace(); 239 240 } 241 } 242 } 243 244 245 return true; 246 } 247 }); 248 249 butRstop.setOnTouchListener(new 250 View.OnTouchListener() { 251 @Override 252 public boolean 253 onTouch(View v, MotionEvent event) { 254 if(event.getAction() == 255 MotionEvent.ACTION_DOWN) { 256 textCmd.setText("R STOP"); 257 258 if (mTcpClient != null) { 259 try { 260 261 mTcpClient.sendMessage("d"); 262 } 263 catch (IOException e) { 264 e.printStackTrace(); 265 266 } 267 } 268 } else if 269 (event.getAction() == MotionEvent.ACTION_UP) { 270 if (textCmd.getText()=="R 271 STOP" && mTcpClient != null) { 272 try { 273 mTcpClient.sendMessage("w"); 274 275 textCmd.setText("Forward"); 276 } 277 catch (IOException e) { 278 e.printStackTrace(); 279 280 } 281 } 282 } 283 284 285 return true; 286 } 287 }); 288 } 289 290 @Override 291 292 public void onMapReady(GoogleMap googleMap) { 293 mMap = googleMap; 294 295 //polyline_opt = new PolylineOptions().width(5).color(Color.BLUE); 296 //polyline 297 = mMap.addPolyline(polyline_opt); 298 } 299 /* 300 public void addToMap(View 301 view){ 302 Polyline line = mMap.addPolyline(new PolylineOptions() 303 .add(new 304 LatLng(41, 9), new LatLng(42, 9)) 305 .width(5) 306 .color(Color.RED)); 307 308 309 } 310 */ 311 BroadcastReceiver wifiScanReceiver = new BroadcastReceiver() 312 { 313 @Override 314 public void onReceive(Context c, Intent intent) 315 { 316 boolean success = intent.getBooleanExtra(wifi.EXTRA_RESULTS_UPDATED, 317 false); 318 if (success && !findWifi) { 319 scanSuccess(); 320 321 } 322 } 323 }; 324 325 326 public void WifiCon (View view){ 327 328 findWifi=false; 329 arraylist.clear(); 330 boolean success 331 = wifi.startScan(); 332 if (!success) { 333 // scan failure handling 334 335 Toast.makeText(this, "Scan Failure", Toast.LENGTH_SHORT).show(); 336 337 } 338 } 339 340 341 private void scanSuccess() { 342 results=wifi.getScanResults(); 343 344 size=results.size(); 345 //Toast.makeText(this, "Scanning.... " 346 + size, Toast.LENGTH_SHORT).show(); 347 for (ScanResult result : results) 348 { 349 //arraylist.add(result.SSID); 350 //adapter.notifyDataSetChanged(); 351 352 if (result.SSID.equals("INO_ESP8266")){ 353 Toast.makeText(this, 354 "Trovato ", Toast.LENGTH_SHORT).show(); 355 setSsidAndPassword(getApplicationContext(),"INO_ESP8266","12345678",wifi); 356 357 break; 358 } 359 } 360 //getApplicationContext().unregisterReceiver(wifiScanReceiver); 361 362 //lv.setAdapter(adapter); 363 } 364 365 366 public boolean setSsidAndPassword(Context 367 context, String ssid, String ssidPassword, WifiManager wifi) { 368 try { 369 370 371 WifiConfiguration conf = new WifiConfiguration(); 372 conf.SSID 373 = "\\"" + ssid+ "\\""; 374 //conf.preSharedKey = "\\""+ ssidPassword 375 +"\\""; 376 //conf.preSharedKey = null; 377 conf.allowedKeyManagement.set(WifiConfiguration.KeyMgmt.NONE); 378 379 int idNet=wifi.addNetwork(conf); 380 if (idNet>=0){ 381 findWifi=true; 382 383 wifi.disconnect(); 384 wifi.enableNetwork(idNet, 385 true); 386 wifi.reconnect(); 387 } 388 return 389 true; 390 } catch (Exception e) { 391 e.printStackTrace(); 392 393 return false; 394 } 395 396 } 397 398 399 public void ArdConDis 400 (View view) throws IOException{ 401 if (!connected) { 402 arraylist.clear(); 403 404 adapter.notifyDataSetChanged(); 405 new connectTask().execute(""); 406 407 connected=true; 408 } else { 409 410 if (mTcpClient 411 != null) { 412 mTcpClient.stopClient(); 413 textState.setText("Disconnected"); 414 415 connected=false; 416 } 417 } 418 } 419 420 421 /* 422 public class connectTask extends AsyncTask<String,Void,TCPClient> 423 { 424 @Override 425 protected TCPClient doInBackground(String... message) 426 { 427 mTcpClient = new TCPClient(); 428 mTcpClient.run(); 429 430 return null; 431 } 432 } 433 */ 434 435 public class 436 connectTask extends AsyncTask<String,String,TCPClient> { 437 @Override 438 439 protected TCPClient doInBackground(String... message) { 440 //we 441 create a TCPClient object and 442 mTcpClient = new TCPClient(new TCPClient.OnMessageReceived() 443 { 444 @Override 445 //here the messageReceived method 446 is implemented 447 public void messageReceived(String message) { 448 449 //this method calls the onProgressUpdate 450 publishProgress(message); 451 452 } 453 }); 454 mTcpClient.run(); 455 return 456 null; 457 } 458 459 460 @Override 461 protected void onProgressUpdate(String... 462 values) { 463 super.onProgressUpdate(values); 464 String strInput; 465 466 strInput=values[0]; 467 //in the arrayList we add the messaged 468 received from server 469 arraylist.add(strInput); 470 adapter.notifyDataSetChanged(); 471 472 if (strInput.contains("connected")){ 473 textState.setText("Connected"); 474 475 } else { 476 updateLine(strInput); 477 } 478 479 } 480 } 481 482 public void updateLine(String latlon){ 483 int 484 firsindx=latlon.indexOf(':'); 485 int lastindx=latlon.indexOf(','); 486 float 487 lat = Float.parseFloat(latlon.substring(firsindx+1,lastindx-1)); 488 float 489 lon = Float.parseFloat(latlon.substring(lastindx+1)); 490 LatLng actualLatLon 491 = new LatLng(lat, lon); 492 points.add(actualLatLon); 493 polyline_opt 494 = new PolylineOptions().width(10).color(Color.BLUE); 495 if (points.size()>2) 496 { 497 polyline_opt.addAll(points); 498 polyline = mMap.addPolyline(polyline_opt); 499 500 } 501 mMap.moveCamera(CameraUpdateFactory.newLatLngZoom(actualLatLon,17.0f)); 502 503 504 } 505 506 507 public void sendLforward(View view) throws IOException { 508 509 textCmd.setText("Left forward"); 510 if (mTcpClient != null) { 511 512 mTcpClient.sendMessage("q"); 513 Toast.makeText(this, "Send 514 q", Toast.LENGTH_SHORT).show(); 515 } 516 } 517 518 public void sendLback(View 519 view) throws IOException{ 520 textCmd.setText("Left back"); 521 if 522 (mTcpClient != null) { 523 mTcpClient.sendMessage("z"); 524 Toast.makeText(this, 525 "Send z", Toast.LENGTH_SHORT).show(); 526 } 527 } 528 529 public 530 void sendRforward(View view) throws IOException{ 531 textCmd.setText("Rigth 532 forward"); 533 if (mTcpClient != null) { 534 mTcpClient.sendMessage("e"); 535 536 Toast.makeText(this, "Send e", Toast.LENGTH_SHORT).show(); 537 } 538 539 } 540 541 public void sendRback(View view) throws IOException{ 542 textCmd.setText("Rigth 543 back"); 544 if (mTcpClient != null) { 545 mTcpClient.sendMessage("c"); 546 547 Toast.makeText(this, "Send c", Toast.LENGTH_SHORT).show(); 548 } 549 550 } 551 552 public void sendStop(View view) throws IOException{ 553 textCmd.setText("Rigth 554 back"); 555 if (mTcpClient != null) { 556 mTcpClient.sendMessage("s"); 557 558 Toast.makeText(this, "Send s", Toast.LENGTH_SHORT).show(); 559 } 560 561 } 562 563 public void sendForw(View view) throws IOException{ 564 textCmd.setText("Forward"); 565 566 if (mTcpClient != null) { 567 mTcpClient.sendMessage("w"); 568 569 Toast.makeText(this, "Send w", Toast.LENGTH_SHORT).show(); 570 } 571 572 } 573 public void sendBack(View view) throws IOException{ 574 textCmd.setText("Back"); 575 576 if (mTcpClient != null) { 577 mTcpClient.sendMessage("x"); 578 579 Toast.makeText(this, "Send x", Toast.LENGTH_SHORT).show(); 580 } 581 582 } 583} 584 585 586 587 588 589 590 591
The "wifi" lib
c_cpp
1/* 2 * WiFiESP8266.cpp 3 * 4*/ 5#include <Arduino.h> 6#include 7 <string> 8#include <stdio.h> 9//#include <iostream> 10#include "WiFiESP8266.h" 11using 12 namespace std; 13 14// char*=std::string& 15WiFiESP8266::WiFiESP8266(String Network,String 16 Password,String Channel,String KeyType) { 17 Net=Network; 18 Pas=Password; 19 Cha=Channel; 20 KeyTy=KeyType; 21 buffer=""; 22 connected=false; 23} 24 25void 26 WiFiESP8266::init(){ 27 //Serial1.begin (115200); 28 //restart ESP8266 29 Serial1.print 30 ("AT+RST\ "); 31 delay(10); 32} 33 34void WiFiESP8266::SetSoftAPmode(){ 35 36 String Com; 37 //Serial.println("Input followin information"); 38 Serial.print 39 ("Network: "); 40 //Network=ReadString(); 41 Serial.println (Net); 42 Serial.print 43 ("Password: "); 44 //Password=ReadString(); 45 Serial.println (Pas); 46 Serial.print 47 ("Channel: "); 48 //Channel=ReadString(); 49 Serial.println (Cha); 50 Serial.print 51 ("Key Type: "); 52 //KeyType=ReadString(); 53 Serial.println (KeyTy); 54 55 //Wi-Fi mode station-softAP (STA-SAP) 56 Serial1.print ("AT+CWMODE=3\ "); 57 58 delay(10); 59 // Set configuration of SAP mode 60 Com ="AT+CWSAP=\\""; 61 62 Com +=Net; 63 Com +="\\",\\""; 64 Com +=Pas; 65 Com +="\\","; 66 67 Com +=Cha; 68 Com +=","; 69 Com +=KeyTy; 70 Com +="\ "; 71 Serial1.print(Com); 72 73 delay(10); 74 //Serial1.print("AT+RST\ "); 75} 76 77void WiFiESP8266::CreateServer(){ 78 79 Serial.println("Create server: "); 80 // enable multi connection 81 Serial1.print("AT+CIPMUX=1\ "); 82 83 delay(10); 84 //delay(25); 85 // CIPSERVER=mode,port 86 // mode=1: create 87 server; 88 // mode=0: delete serever; 89 // port: number of port (333 90 defoult) 91 Serial1.print("AT+CIPSERVER=1,333\ "); 92 delay(10); 93 // 94 set timeout time in a range (0-7200 [second]) 95 Serial1.print("AT+CIPSTO=120\ "); 96 97 delay(10); 98} 99 100void WiFiESP8266::GetIP_ClientPC(){ 101 Serial.print("IP 102 rover: "); 103 Serial1.print("AT+CIPSTATUS\ "); 104 delay(10); 105 Serial.println(""); 106 107 Serial.print("IP connesso: "); 108 Serial1.print("AT+CWLIF\ "); 109 delay(10); 110} 111/* 112void 113 ESP8266::WiFi_SendData(){ 114 if (connected){ 115 Serial.println("Data to send:"); 116 117 if(Serial.available()>0){ 118 data=Serial.readString(); 119 Serial.println(data); 120 121 SendData(data); 122 } 123 } 124} 125 126void ESP8266::SendData(String 127 dat){ 128 String Com; 129 bool sendper=true; 130 Com="AT+CIPSEND=0,"; 131 Com 132 +=String(dat.length()); 133 Com += "\ "; 134 //Serial1.print("AT+CIPSEND=0,"); 135 136 //Serial1.print(dat.length()); 137 //Serial1.print("\ "); 138 Serial1.print(Com); 139 140 while (sendper){ 141 if (Serial1.find ('>')){ 142 Serial1.print(dat); 143 144 Serial1.print("\ "); 145 //Serial.print (" > "); 146 //Serial.print(dat); 147 148 sendper=false; 149 } 150 } 151}*/ 152void WiFiESP8266::SendDataRequest(String 153 dat){ 154 String Com; 155 Com="AT+CIPSEND=0,"; 156 Com +=String(dat.length()); 157 158 Com += "\ "; 159 Serial1.print(Com); 160 Com=dat; 161 Com+="\ "; 162 163 if ( Serial1.find('>') ) { 164 Serial1.print(Com); 165 } 166} 167 168void 169 WiFiESP8266::TestSerialWiFi(){ 170 while (Serial1.available () > 0){ 171 buffer=Serial1.readStringUntil('\ '); 172 173 //Serial.print(buffer); 174 if (buffer=="Link"){ 175 //Serial.println(""); 176 177 //Serial.println("Connesso"); 178 connected=true; 179 } 180 181 } 182} 183 184void WiFiESP8266::CloseTCPconnection(){ 185 Serial.println("Close:"); 186 187 Serial1.print("AT+CIPCLOSE\ "); 188 delay(10); 189} 190
The "Motor" library
c_cpp
1/* 2 * Motor.cpp 3 * 4*/ 5//home/manu/.arduino15/packages/arduino/hardware/sam/1.6.11/cores/arduino 6#include 7 <Arduino.h> 8#include "Motor.h" 9 10Motor::Motor(int enPin,int APin, int 11 BPin) { 12 en=enPin; 13 A=APin; 14 B=BPin; 15 analogWrite(en,0); 16} 17 18//_________________________________ATTUAZIONE 19 MOTORE_________________________________ 20void Motor::forward(int D){ 21 analogWrite(en,D); 22 digitalWrite(A,LOW); 23 digitalWrite(B,HIGH); 24} 25 26void 27 Motor::back(int D){ 28 analogWrite(en,D); 29 digitalWrite(A,HIGH); 30 digitalWrite(B,LOW); 31} 32 33 34void 35 Motor::stopMot(){ 36 analogWrite(en,0); 37} 38
Comments
Only logged in users can leave comments