diff options
author | NeodarZ <neodarz@neodarz-K53SV.com> | 2015-04-29 23:20:14 +0200 |
---|---|---|
committer | NeodarZ <neodarz@neodarz-K53SV.com> | 2015-04-29 23:20:14 +0200 |
commit | 9222bfc8a944a616996e404cb3dfbd29532bd56a (patch) | |
tree | 9c35225ee94a56fc7cb35cf1b1d2922b7b2f38a4 /pilotage_moteur_v2 | |
parent | 3c0afb53872c09e8cb2c1e5afb6d6a5184aab0fe (diff) | |
download | Robot-Cable-9222bfc8a944a616996e404cb3dfbd29532bd56a.tar.xz Robot-Cable-9222bfc8a944a616996e404cb3dfbd29532bd56a.zip |
Rajout des programme de commande des treuils (Processing) et ceux du fonctionnement des treuils (Arduino)
Diffstat (limited to 'pilotage_moteur_v2')
-rw-r--r-- | pilotage_moteur_v2/pilotage_moteur_v2.ino | 140 |
1 files changed, 140 insertions, 0 deletions
diff --git a/pilotage_moteur_v2/pilotage_moteur_v2.ino b/pilotage_moteur_v2/pilotage_moteur_v2.ino new file mode 100644 index 0000000..2910422 --- /dev/null +++ b/pilotage_moteur_v2/pilotage_moteur_v2.ino @@ -0,0 +1,140 @@ + + +String chaine_nbr = ""; // valeur numérique +String chaine_cmd = ""; // valeur commande + +int delaylegnth = 4; //durée du delai. + +void setup() +{ + //establish motor direction toggle pins + pinMode(12, OUTPUT); //CH A -- HIGH = forwards and LOW = backwards??? + pinMode(13, OUTPUT); //CH B -- HIGH = forwards and LOW = backwards??? + + //establish motor brake pins //etablir les pin du frein du moteur + pinMode(9, OUTPUT); //brake (disable) CH A + pinMode(8, OUTPUT); //brake (disable) CH B + + Serial.begin(9600); +} + +void loop() +{ + while (Serial.available() > 0) // si buffer liaison serie non vide // quand on reçoit data + { + int inChar = Serial.read(); //lecture des octets rentrants + if (isDigit(inChar)) + { + // convert the incoming byte to a char and add it to the string: //convertir les octets rentrant en nombre et les ajoute a la chaine de charactere. + chaine_nbr += (char)inChar; + } + //if (!isDigit(inChar)&&(inChar != 0x0D)&&(inChar != 0x0A)) // si octet PAS nbr ET octet PAS 0x0D (cr) ET octet PAS 0x0A (nl) + if (!isDigit(inChar)&&(inChar != 0x0D)&&(inChar != 0x0A)) + { + chaine_cmd += (char)inChar; // valeur commande + } + // if you get a newline, print the string, + // then the string's value: + if (inChar == '\r') + { + Serial.print("Nom commande : "); + Serial.print(chaine_cmd); + Serial.print(" Valeur nombre : "); + Serial.println(chaine_nbr.toInt()); // valeur après conversion en entier + + + if (chaine_cmd=="cmdH") //commande pour avancer + { + for (int cpt=0; cpt<chaine_nbr.toInt(); cpt++) + { + actionA(); //effectuer A + Serial.println("actionA 4pas"); + } + } + if (chaine_cmd=="cmdT") //commande pour reculer + { + for (int cpt=0; cpt<chaine_nbr.toInt(); cpt++) + { + actionB(); //effectuer B + Serial.println("actionB 4pas"); + } + } + + // effacement des chaines nbr et cmd + chaine_nbr = ""; + chaine_cmd = ""; + } // fin si fin de ligne + + } // fin while +} // fin loop + + +///////////////////////////////// + +void actionA() +{ + digitalWrite(9, LOW); //ENABLE CH A + digitalWrite(8, HIGH); //DISABLE CH B + digitalWrite(12, HIGH); //Sets direction of CH A + analogWrite(3, 128); //Moves CH A /Entre 0 et 255 + + delay(delaylegnth); + + digitalWrite(9, HIGH); //DISABLE CH A + digitalWrite(8, LOW); //ENABLE CH B + digitalWrite(13, LOW); //Sets direction of CH B + analogWrite(11, 128); //Moves CH B /Entre 0 et 255 + + delay(delaylegnth); + + digitalWrite(9, LOW); //ENABLE CH A + digitalWrite(8, HIGH); //DISABLE CH B + digitalWrite(12, LOW); //Sets direction of CH A + analogWrite(3, 128); //Moves CH A /Entre 0 et 255 + + delay(delaylegnth); + + digitalWrite(9, HIGH); //DISABLE CH A + digitalWrite(8, LOW); //ENABLE CH B + digitalWrite(13, HIGH); //Sets direction of CH B + analogWrite(11, 128); //Moves CH B /Entre 0 et 255 + + delay(delaylegnth); +} + +void actionB() +{ + + + digitalWrite(9, LOW); //ENABLE CH A + digitalWrite(8, HIGH); //DISABLE CH B + digitalWrite(12, LOW); //Sets direction of CH A + analogWrite(3, 128); //Moves CH A /Entre 0 et 255 + + delay(delaylegnth); + + digitalWrite(9, HIGH); //DISABLE CH A + digitalWrite(8, LOW); //ENABLE CH B + digitalWrite(13, LOW); //Sets direction of CH B + analogWrite(11, 128); //Moves CH B /Entre 0 et 255 + + delay(delaylegnth); + + digitalWrite(9, LOW); //ENABLE CH A + digitalWrite(8, HIGH); //DISABLE CH B + digitalWrite(12, HIGH); //Sets direction of CH A + analogWrite(3, 128); //Moves CH A /Entre 0 et 255 + + delay(delaylegnth); + + digitalWrite(9, HIGH); //DISABLE CH A + digitalWrite(8, LOW); //ENABLE CH B + digitalWrite(13, HIGH); //Sets direction of CH B + analogWrite(11, 128); //Moves CH B /coefficient Entre 0 et 255 de le tension envoyée. + + delay(delaylegnth); +} + + + +
|