[PATCH 1/2] Code cleaning Added schematics

Signed-off-by: Gnieark <gnieark@free.fr>
master
Frédéric BISSON 5 years ago committed by Gnieark
parent 7f6c2c2118
commit a57a5b85d7

File diff suppressed because one or more lines are too long

After

Width:  |  Height:  |  Size: 476 KiB

@ -1,135 +1,246 @@
// lineFollowerBot.ino
// Programme basique permettant à un robot de suivre une ligne dessinée au sol.
//
// Un projet du hackerspace Ventres Mous.
// =============================================================================
//
// IDENTIFICATION DES BROCHES DE LARDUINO UTILISÉES PAR LE PROJET
//
// =============================================================================
// Chaque broche de lArduino est identifiée par un numéro. Afin de faciliter
// la lecture du code, on leur donne des noms parlants.
// Broches sur lesquelles les moteurs sont connectés.
// Ce sont des broches de sortie numériques.
#define MOTEUR_GAUCHE 2
#define MOTEUR_DROITE 3
// Broches sur lesquelles les capteurs sont connectés.
// Ce sont des broches de lecture analogique.
#define CAPTEUR_GAUCHE A0
#define CAPTEUR_DROITE A1
// Broches sur lesquelles les leds de suivi détalonnage sont connectées.
// Ce sont des broches de sortie numériques.
#define ETALONNAGE_LED_GAUCHE 4
#define ETALONNAGE_LED_DROITE 5
// Broche sur laquelle le bouton détalonnage est connecté.
// Cest une broche de lecture numérique.
#define ETALONNAGE_BOUTON 12
// Les 2 états possible du bouton détalonnage : pressé et relevé.
#define BOUTON_PRESSE 1
#define BOUTON_RELEVE 0
// Variables utilisées pour définir les seuils de détection des capteurs. Les
// seuils sont réglés à 200 par défaut.
int seuil_gauche = 200;
int seuil_droite = 200;
// =============================================================================
//
// INITIALISATION DES BROCHES DE LARDUINO
//
// =============================================================================
// Cette fonction est exécutée une seule fois lors de lallumage de lArduino.
// Son rôle consiste à configurer lArduino pour un usage précis, dans le cas
// présent pour un robot suiveur de ligne.
void setup() {
// Configure les broches des moteurs en sortie numérique.
pinMode(MOTEUR_GAUCHE, OUTPUT);
pinMode(MOTEUR_DROITE, OUTPUT);
// Configure les broches des leds de suivi détalonnage en sortie numérique.
pinMode(ETALONNAGE_LED_GAUCHE, OUTPUT);
pinMode(ETALONNAGE_LED_DROITE, OUTPUT);
// Configure la broche du bouton détalonnage en entrée numérique.
pinMode(ETALONNAGE_BOUTON, INPUT);
// Les broches analogiques des capteurs sont obligatoirement en mode lecture
// analogique. Il ny a donc pas de réglage à faire sur ces broches.
}
int ledDebugDroite = 5;
int ledDebugGauche = 4;
// =============================================================================
//
// GESTION DU BOUTON DÉTALONNAGE
//
// =============================================================================
int moteurGauche = 2;
int moteurDroite = 3;
// Attend jusquà ce que le bouton détalonnage soit enfoncé ou relaché.
// Le paramètre etat peut prendre 2 valeurs : BOUTON_PRESSE et BOUTON_RELEVE.
void continuer_si(int etat) {
while(digitalRead(ETALONNAGE_BOUTON) != etat) delay(1);
}
// =============================================================================
//
// GESTION DES LEDS DÉTALONNAGE
//
// =============================================================================
// Fait clignoter les leds détalonnage pour indiquer à lutilisateur que
// létalonnage est terminé.
void clignoter() {
// Fait clignoter 5 fois les leds. Clignoter consiste à allumer puis éteindre.
for(int b = 0; b < 5; b++) {
// Allume les leds détalonnage (les broches sont réglées à 5 volts).
digitalWrite(ETALONNAGE_LED_GAUCHE, HIGH);
digitalWrite(ETALONNAGE_LED_DROITE, HIGH);
// Attend 0,2 secondes.
delay(200);
// Éteint les leds détalonnage (les broches sont réglées à 0 volt).
digitalWrite(ETALONNAGE_LED_GAUCHE, LOW);
digitalWrite(ETALONNAGE_LED_DROITE, LOW);
// Attend 0,2 secondes.
delay(200);
}
}
int capteurGauche = A0;
int capteurDroite = A1;
// Éteint les deux leds détalonnage.
void eteindre() {
// Éteint les 2 leds de débogage en mettant leurs broches à 0 volt.
digitalWrite(ETALONNAGE_LED_GAUCHE, LOW);
digitalWrite(ETALONNAGE_LED_DROITE, LOW);
}
int pinButton = 12;
// =============================================================================
//
// ÉTALONNAGE DES CAPTEURS DU ROBOT
//
// =============================================================================
// Étalonne les capteurs pour établir la différence entre la ligne et le sol.
void etalonnage() {
// Variables qui vont recevoir les valeurs minimales et maximales des capteurs
// gauche et droite. Lunité importe peu.
int min_gauche;
int min_droite;
int max_gauche;
int max_droite;
// Arrête les 2 moteurs, le robot ne bouge plus.
moteur_arret();
// Létalonnage est déclenché quand lutilisateur appuie sur le bouton
// détalonnage. On attend que le bouton soit relaché pour étalonner.
continuer_si(BOUTON_RELEVE);
// Lit létat des deux capteurs.
min_gauche = analogRead(CAPTEUR_GAUCHE);
min_droite = analogRead(CAPTEUR_DROITE);
// Éteint les deux leds détalonnage.
eteindre();
// Attend que lutilisateur clique sur le bouton (clic = appui + relache).
continuer_si(BOUTON_PRESSE);
continuer_si(BOUTON_RELEVE);
// Lit létat des deux capteurs.
max_gauche = analogRead(CAPTEUR_GAUCHE);
max_droite = analogRead(CAPTEUR_DROITE);
// Le seuil correspond à la valeur située entre les valeurs minimales et
// maximales que le capteur retourne.
seuil_gauche = (min_gauche + max_gauche) / 2;
seuil_droite = (min_droite + max_droite) / 2;
clignoter();
}
int seuil = 200;
int seuilGauche = 200;
int seuilDroite = 200;
// =============================================================================
//
// GESTION DES DEUX MOTEURS
//
// =============================================================================
void setup()
{
// Arrête les deux moteurs. Le robot ne bouge plus.
void moteur_arret() {
digitalWrite(MOTEUR_GAUCHE, LOW);
digitalWrite(MOTEUR_DROITE, LOW);
}
pinMode(ledDebugDroite, OUTPUT);
pinMode(ledDebugGauche, OUTPUT);
pinMode(moteurGauche, OUTPUT);
pinMode(moteurDroite, OUTPUT);
pinMode(pinButton, INPUT);
// Fait tourner le robot à droite.
void moteur_droite() {
// Pour tourner à droite, on bloque le côté droit et on fait avancer le côté
// gauche.
digitalWrite(MOTEUR_GAUCHE,HIGH);
digitalWrite(MOTEUR_DROITE,LOW);
}
void setSeuil()
{
stop();
//on attend que le bouton soit relaché
int a=1;
while( a==1){
a = digitalRead(pinButton);
delay(1);
}
int minGauche;
int minDroite;
minGauche = analogRead(capteurGauche);
minDroite = analogRead(capteurDroite);
// Fait tourner le robot à gauche.
void moteur_gauche() {
// Pour tourner à gauche, on bloque le côté gauche et on fait avancer le côté
// droit.
digitalWrite(MOTEUR_GAUCHE, LOW);
digitalWrite(MOTEUR_DROITE, HIGH);
}
digitalWrite(ledDebugDroite,LOW);
digitalWrite(ledDebugGauche,LOW);
// Fait tourner les deux moteurs. Le robot avance.
void moteur_avance() {
digitalWrite(MOTEUR_GAUCHE, HIGH);
digitalWrite(MOTEUR_DROITE, HIGH);
}
while (a ==0){
delay(1);
a = digitalRead(pinButton);
}
//Nouvel appui sur le bouton
while(a==1){
delay(1);
a = digitalRead(pinButton);
// =============================================================================
//
// BOUCLE PRINCIPALE
//
// =============================================================================
// La fonction loop est appelée en boucle par lArduino.
void loop() {
// Variables qui vont recevoir les valeurs des capteurs.
int valeur_gauche;
int valeur_droite;
// Si le bouton détalonnage est pressé, on lance létalonnage.
if(digitalRead(ETALONNAGE_BOUTON) == 1) etalonnage();
// Lit létat des deux capteurs.
valeur_gauche = analogRead(CAPTEUR_GAUCHE);
valeur_droite = analogRead(CAPTEUR_DROITE);
// Fait avancer le robot si les deux capteurs identifient le sol.
if((valeur_gauche < seuil_gauche) && (valeur_droite < seuil_droite)) {
moteur_avance();
return;
}
int maxGauche;
int maxDroite;
maxGauche = analogRead(capteurGauche);
maxDroite = analogRead(capteurDroite);
seuilGauche = (minGauche + maxGauche) / 2;
seuilDroite = (minDroite + maxDroite) / 2;
for(int b = 0; b < 5; b++){
digitalWrite(ledDebugDroite,HIGH);
digitalWrite(ledDebugGauche,HIGH);
delay(200);
digitalWrite(ledDebugDroite,LOW);
digitalWrite(ledDebugGauche,LOW);
delay(200);
}
// Tourne à droite si le capteur de gauche identifie le sol et le capteur de
// droite identifie la ligne.
if((valeur_gauche < seuil_gauche) && (valeur_droite > seuil_droite)) {
moteur_droite();
}
void stop(){
digitalWrite(moteurGauche,LOW);
digitalWrite(moteurDroite,LOW);
}
void tourneDroite(){
digitalWrite(moteurGauche,HIGH);
digitalWrite(moteurDroite,LOW);
}
void tourneGauche(){
digitalWrite(moteurGauche,LOW);
digitalWrite(moteurDroite,HIGH);
}
void avance(){
digitalWrite(moteurGauche,HIGH);
digitalWrite(moteurDroite,HIGH);
}
void loop()
{
int a;
a = digitalRead(pinButton);
if(a == 1){
//le buton a été appuyé
setSeuil();
// Attend que le capteur de droite identifie le sol.
while(analogRead(CAPTEUR_DROITE) > seuil_droite) delay(1);
return;
}
int valGauche;
int valDroite;
valGauche = analogRead(capteurGauche);
valDroite = analogRead(capteurDroite);
if(valGauche < seuil)
digitalWrite(ledDebugGauche,HIGH);
else
digitalWrite(ledDebugGauche,LOW);
if(valDroite < seuil)
digitalWrite(ledDebugDroite,HIGH);
else
digitalWrite(ledDebugDroite,LOW);
if((valGauche < seuilGauche) && (valDroite < seuilDroite))
avance();
if((valGauche < seuilGauche) && (valDroite > seuilDroite)){
tourneDroite();
while(valDroite > seuilDroite){
valDroite = analogRead(capteurDroite);
delay(1);
}
// Tourne à gauche si le capteur de gauche identifie la ligne et le capteur de
// droite identifie le sol.
if((valeur_gauche > seuil_gauche) && (valeur_droite < seuil_droite)) {
moteur_gauche();
// Attend que le capteur de gauche identifie le sol.
while(analogRead(CAPTEUR_GAUCHE) > seuil_gauche) delay(1);
return;
}
if((valGauche > seuilGauche) && (valDroite < seuilDroite)){
tourneGauche();
while(valGauche > seuilGauche){
valGauche = analogRead(capteurGauche);
delay(1);
}
// Arrête le robot si les deux capteurs identifient chacun le sol. Cela veut
// dire que le robot a perdu la ligne, il est plus prudent de larrêter.
if((valeur_gauche > seuil_gauche) && (valeur_droite > seuil_droite)) {
moteur_arret();
return;
}
if((valGauche > seuilGauche) && (valDroite > seuilDroite))
stop();
}

Loading…
Cancel
Save