/*
Transmission par liaison série de la commande d'un chassis de robot
Matériel : pont en H http://www.instructables.com/id/Arduino-Modules-L298N-Dual-H-Bridge-Motor-Controll/
           Capteur ultra son HC-SR04  https://itechnofrance.wordpress.com/2013/03/12/utilisation-du-module-ultrason-hc-sr04-avec-larduino/
           emetteur bluetooth HC-06 http://tiptopboards.free.fr/arduino_forum/viewtopic.php?f=2&t=57
Programmation pour un Leonardo : Serial1 communique avec le smartphone, Serial ne sert qu'à degugger
Sur un Arduino Uno on peut supprimer tous les Serial et remplacer les Serial1 par Serial.
Transmission du smartphone : Marche;Droite;Gauche;\n
Réponse de l'Arduino : 1T;Volt;Microsecondes;durée;k\n

Marche : 0->Arrêt, 1->Avant, 2->Arrière, 6->impulsion avant Gauche, 7-> impulsion arrière Gauche
         8->impulsion avant Droite, 9-> impulsion arrière Droite
Droite : puissance du moteur à droite de 0 à 255
Gauche : puissance du moteur à gauche de 0 à 255

Volt : tension de la pile mesurée à l'aide d'un diviseur de tension de 2*10k sur Vin vers A0 (0 à 1023 pour 10 V)
Microsecondes : durée mesurée par le capteur à ultrason HC-SR04 avec un timeout de 30ms
durée : nombre de ms entre la réception de 2 instructions du smartphone (environ 200ms)
k : nombre d'instructions reçues sans interruption supérieure à 600 ms

 http://appinventor.mit.edu/explore/
 Créer un compte puis Projects\Import project (.aia)from my computeur...
 */

const int Da=3,Db=5,Ga=11,Gb=9;   // Cablage du pont en H 
const int Trig1=8,Echo1=7;        // Cablage du HC-SR04
const int impulsion=150;          // Durée de l'impulsion en ms pour virage
int Marche, Droite, Gauche;
float cm;


unsigned long t=0;              // durée entre 2 instructions du smartphone
unsigned int dt;              // Mesure en Microseconds de la distance par le capteur US
int i,j,k;
float V;                      // Tension pile en Volt
boolean Obstacle;            // Vrai si obstacle à moins de 35 cm 

void setup()
{
  pinMode(Da, OUTPUT); 
  pinMode(Db, OUTPUT);
  pinMode(Ga, OUTPUT); 
  pinMode(Gb, OUTPUT); 
  pinMode(Trig1,OUTPUT);
  pinMode(Echo1,INPUT);
  Serial.begin(9600);
  Serial1.begin(9600);
  delay(2000);
  Serial.println("Format de transmission retenu : Marche;Droite;Gauche; exemple : 1;150;150; +LF (code ascii 10)");
}

void loop()
{
  if (Reception()) {
    //while (millis()-t<200) ;
    k++;
    Serial1.print("1T ;");
    Serial1.print(analogRead(A0));
    Serial1.print(";");
    Serial1.print(dt);
    Serial1.print(";");
    Serial1.print(millis()-t);
    Serial1.print(";");
    Serial1.println(k);
    t=millis();

    Obstacle=!Ultrason(&dt,&cm);        // Mesure de la disctance en cm et en Microsecondes (dt)
    
    V=10.0*analogRead(A0)/1024.0;
    Serial.print(k);Serial.print("\t");


    if (Marche==1) {
      if (Obstacle) {QuartTour();Marche=0;}
      else {
        analogWrite(Db,0); 
        analogWrite(Gb,0);
        analogWrite(Da,Droite); 
        analogWrite(Ga,Gauche);
        Serial.print("Avant \t Droite = ");
      }
    }

    if (Marche==0) {
      analogWrite(Da,0); 
      analogWrite(Ga,0);
      analogWrite(Db,0); 
      analogWrite(Gb,0);
      Serial.print("Arret \t Droite = ");
    }

    if (Marche==2) {
      analogWrite(Da,0); 
      analogWrite(Ga,0);
      analogWrite(Db,Droite); 
      analogWrite(Gb,Gauche);
      Serial.print("Arriere \t Droite = ");
    }
    
    if (Marche==6) {        // Virage à Gauche avant
      analogWrite(Db,0); 
      analogWrite(Gb,0);
      analogWrite(Da,200); 
      analogWrite(Ga,0);
      delay(impulsion);
      analogWrite(Da,Droite); 
      analogWrite(Ga,Gauche);
      Serial.print("Virage AvG \t Droite = ");
    }
    
    if (Marche==7) {        // Virage à Gauche arrière
      analogWrite(Da,0); 
      analogWrite(Ga,0);
      analogWrite(Db,200); 
      analogWrite(Gb,0);
      delay(impulsion);
      analogWrite(Da,Droite); 
      analogWrite(Ga,Gauche);
      Serial.print("Virage ArG \t Droite = ");
    }
      if (Marche==8) {        // Virage à Droite avant
      analogWrite(Db,0); 
      analogWrite(Gb,0);
      analogWrite(Da,0); 
      analogWrite(Ga,200);
      delay(impulsion);
      analogWrite(Da,Droite); 
      analogWrite(Ga,Gauche);
      Serial.print("Virage AvD \t Droite = ");
    } 
    if (Marche==9) {        // Virage à Droite arrière
      analogWrite(Da,0); 
      analogWrite(Ga,0);
      analogWrite(Db,0); 
      analogWrite(Gb,200);
      delay(impulsion);
      analogWrite(Da,Droite); 
      analogWrite(Ga,Gauche);
      Serial.print("Virage ArD \t Droite = ");
    }    
    
    Serial.print(Droite);
    Serial.print("\t Gauche =");
    Serial.print(Gauche);

    Serial.print("\t Pile = ");
    Serial.print(V);
    Serial.print(" V");
    Serial.print("\t Distance = ");
    Serial.print(cm);
    Serial.println(" cm");
    i=0;


  }

  if (millis()-t >600) {                // Perte de transmission > 600 ms

    k=0;
    t=millis();
    analogWrite(Da,0);                 // Arrêt des moteurs
    analogWrite(Ga,0);
    analogWrite(Db,0); 
    analogWrite(Gb,0);
    if (!(i%10)){
      Serial.print("Pas de reception depuis ");
      Serial.print(0.5*i);
      Serial.println(" s");
    }
    i++;
  }
}


boolean Reception()                          // Exemple de transmission : "1;100;250; +LF"
{
  if (!Serial1.available()) return false; // Si aucun caractère disponible dans le buffer fin du sous programme
     
     Marche=Serial1.parseInt(); // Marche = 1 reste ds le buffer :";100;250; +LF" 
     Droite=Serial1.parseInt();  // Droite = 100 reste ds le buffer :";250; +LF"
     Gauche=Serial1.parseInt();  // Gauche = 250 reste ds le buffer :"; +LF"
     delay(15);             // Attendre la fin de transmission
     while (Serial1.available()) Serial1.read();  // Vider le buffer Serial s'il reste des caractères...   
     return true;
  }

boolean Ultrason(unsigned int *t,float *centi) {    // Pour s'entraîner à utiliser un pointeur : http://forum.arduino.cc/index.php?topic=101780.0
  digitalWrite(Trig1,HIGH);
  delayMicroseconds(50);
  digitalWrite(Trig1,LOW);
  *t = pulseIn(Echo1,HIGH,30000);
  if (!*t) *t=30000;
  *centi = 170.0**t/10000; 
  if (*centi > 35) return true;
  delayMicroseconds(30000-*t);                  // Quelque soit la distance la durée de cette fonction est de 30 ms
  return false;
}

void QuartTour(){
      analogWrite(Da,0); 
      analogWrite(Ga,0);
      analogWrite(Db,0); 
      analogWrite(Gb,200);
      delay(500);
      analogWrite(Db,0); 
      analogWrite(Gb,0);}