Moteurs

La propulsion de l’AlphaBot est de type différentielle : deux moteurs indépendants propulsent et dirigent le robot.

 

 

Principe du contrôle des moteurs

Chaque moteur est piloté par un circuit dédié :

Ce circuit comprend :

Voici les correspondances entre les ports de communications du Raspberry et les interfaces de commande du pilote moteur :

Moteur gauche Moteur droit
nom de l’interface ENA ENB
Arduino UNO D5 D6
Raspberry Pi
GPIO6 GPIO26

 

  • un pont en H (L298P) pour modifier le sens de rotation

Voici les correspondances entre les ports de communications du Raspberry ou de l’Arduino , ainsi que les états qu’ils doivent prendre (LOW ou HIGH) pour obtenir le comportement moteur attendu :

Arrêt
(moteur libre)
Avant Arrière Arrêt
(moteur freiné)
IN+ IN- IN+ IN- IN+ IN-
LOW LOW HIGH LOW LOW HIGH pas possible !

 

Moteur gauche Moteur droit
IN+ IN- IN+ IN-
nom de l’interface IN1 IN2 IN3 IN4
Arduino UNO A0 A1 A2 A3
Raspberry Pi GPIO12 GPIO13 GPIO20 GPIO21

 

 


Programmation avec Arduino

Bibliothèque

Pour utiliser plus simplement le détecteur de ligne, il faut installer la bibliothèque  AlphaBot.

Elle procure aux programmes une classe AlphaBot représentant le traqueur. Ainsi on peut créer un objet (appelé par exemple bot) avec la ligne suivante, placé en début de programme (avant la fonction setup) :

AlphaBot bot = AlphaBot();

Gestion des mouvements

Deux méthodes de la classe AlphaBot sont intéressantes :

  • la méthode .MotorRun, qui attend deux arguments de type int (Lspeed et Rspeed) représentant la vitesse angulaire des roues Gauche et Droite.
    Lspeed et Rspeed doivent être compris entre -255 et 255
  • la méthode .Brake, qui permet d’arrêter les deux moteurs.

 

Le petit programme ci-dessous montre comment les utiliser :

#include "AlphaBot.h"

AlphaBot bot = AlphaBot();

void setup() {
}

void loop() { 
  delay(1000);  
  bot.MotorRun(-250,-250);
  delay(1000);
  bot.Brake();
}

 

 

 


Programmation en Python

Initialisation

Pour gérer les ports du Raspberry, il faut importer la bibliothèque Python RPi.GPIO :

import RPi.GPIO as GPIO

Remarque : le nom derrière le as permet dans la suite du programme d’utiliser le module sous le nom GPIO au lieu de RPi.GPIO, c’est plus court !

Il faut ensuite choisir le mode d’adressage, il en existe plusieurs, retenons simplement le mode BCM :

GPIO.setmode(GPIO.BCM)
#GPIO.setmode(GPIO.BOARD) # autre mode d'adressage

 

On peut obtenir des infos (adressage, mode, état, …) sur les ports en tapant gpio readall dans un Terminal Linux :

 

Configuration des ports

Un port ne peut avoir qu’un seul mode à la fois : entrée (GPIO.IN) ou sortie (GPIO.OUT).

Il faut configurer chaque port avant son utilisation :

GPIO.setup(CH, GPIO.IN)  # broche CH est une entrée numérique
GPIO.setup(CH, GPIO.OUT) # broche CH est une sortie numérique

GPIO.setup(CH, GPIO.OUT, initial = GPIO.HIGH)# broche CH est une sortie initialement à l’état haut

Exemple : pour configurer le port 12 en mode sortie avec l’état initial BAS :

GPIO.setup(12, GPIO.OUT, initial = GPIO.LOW)

Selon le circuit que l’on y connecte, il faut parfois utiliser les résistances de pull-up ou de pull-down internes au RPi, pour les ports configurés en mode entrée :

GPIO.setup(CH, GPIO.IN, pull_up_down=GPIO.PUD_UP)
GPIO.setup(CH, GPIO.IN, pull_up_down=GPIO.PUD_DOWN)

Lecture d’un port d’entrée

etat = GPIO.input(CH)

Écriture sur un port de sortie

GPIO.output(CH, GPIO.LOW)
GPIO.output(CH, GPIO.HIGH)

Signal PWM

Les ports du RPi sont capables de générer des signaux PWM.

p = GPIO.PWM(CH, frequence)             # fréquence en Hz
p.start(rapport_cyclique)               # rapport_cyclique entre 0 et 100

p.ChangeFrequency(nouvelle_frequence)   
p.ChangeDutyCycle(nouveau_rapport_cyclique)
p.stop()


Exercice : mouvements
Écrire en Python les fonctions suivantes, qui permettront de contrôler les mouvements du robot :

Modules Python utiles : time, thread, ...

  • Contrôle des moteurs indépendamment :

rot_moteur(moteur, vitesse)

moteur : str ('G' ou 'D')

vitesse : int (-100 à 100)

avance en continu :

avancer_cont(vitesse, rayon = None)

vitesse : int (-100 à 100)

rayon : float (en mètre), None = rayon infini

arrêt :

stopper()

avance pendant un temps donné (sans interruption du programme !) :

avancer_duree(vitesse, duree, rayon = None)

duree : float (secondes)

 

Correction
# -*- coding:utf-8 -*-

import RPi.GPIO as GPIO
import time

GPIO.setmode(GPIO.BCM)

# Ports de contrôle des moteurs
ENA = 6
IN1 = 12
IN2 = 13

ENB = 26
IN3 = 20
IN4 = 21

GPIO.setup(ENA, GPIO.OUT)
GPIO.setup(IN1, GPIO.OUT)
GPIO.setup(IN2, GPIO.OUT)
GPIO.setup(ENB, GPIO.OUT)
GPIO.setup(IN3, GPIO.OUT)
GPIO.setup(IN4, GPIO.OUT)
PWMA = GPIO.PWM(ENA, 500)
PWMB = GPIO.PWM(ENB, 500)


# Dimensions du robot
R = 0.066 # rayon des roues en mètres
B = 0.132 # voie du robot en mètres


# Variables d'état des moteurs
motD, motG = 0, 0  # mémorisent les vitesses des moteurs (valeurs algébriques)
# Pour passer les valeurs globales à un autre programme,
# il faut utiliser une fonction !
def get_vitesse(moteur):
	if moteur == 'G':
		return motG
	else:
		return motD



########################################################################
# Contrôle des moteurs
########################################################################
def rot_moteur(moteur, vitesse):
	""" Met en rotation le moteur ('G' pour moteur Gauche et 'D' pour moteur Droit)
		à la vitesse donnée (-100 à 100)
		   vitesse < 0 : sens arrière
		   vitesse > 0 : sens avant
		   vitesse == 0 : arrêt
	"""
	global motD, motG
	if moteur == 'G':
		pwm = PWMA
		h1 = IN1
		h2 = IN2
		motG = vitesse
		vitesse = -vitesse # inversion car les moteurs sont en opposition
	else:
		pwm = PWMB 
		h1 = IN3
		h2 = IN4
		motD = vitesse
	
	if vitesse > 0 :
		GPIO.output(h1, GPIO.LOW)
		GPIO.output(h2, GPIO.HIGH)
	elif vitesse < 0:
		GPIO.output(h1, GPIO.HIGH)
		GPIO.output(h2, GPIO.LOW)
	else:
		pwm.stop()
		return
		
	pwm.start(abs(vitesse))
	
	
########################################################################
# Calcul des mouvements
########################################################################
def vitesse_robot(wD, wG, r = R, b = B):
	""" Calcule en fonction des vitesses angulaires [rad/s] des 2 roues (wD et wG) :
		 * la vitesse [m/s] du centre du robot
		 * et le rayon [m] de la trajectoire du centre du robot
			None : ligne droite
	"""
	if wD == wG:	# Ligne droite
		return wG*r, None
	return 0.5*(wD+wG)*r, b/2*(wD+wG)/(wD-wG)


def vitesses_roues(vit, ray, r = R, b = B):
	""" Calcule les vitesses angulaires [rad/s] des 2 roues en fonction :
		 * de la vitesse [m/s] du centre du robot
		 * du rayon [m] de la trajectoire du centre du robot
			None : ligne droite
			0    : rotation sur place (vers la droite)
	"""
	if ray is None:			# Ligne droite
		wG = vit/r
		wD = wG
		
	elif ray == b/2: 		# virage sur la roue Droite
		wG = 0
		wD = 2*vit/r
		
	elif ray == -b/2: 		# virage sur la roue Gauche
		wG = 2*vit/r
		wD = 0
		
	elif ray == 0: 			# rotation sur place
		wG = vit/r
		wD = -wG
	
	else:
		d = (ray-b/2)/(ray+b/2)
		wG = 2*vit/(1+1/d)/r
		wD = 2*vit/(1+d)/r

	return wD, wG
	
	
########################################################################
# Contrôle du robot
########################################################################
def stopper():
	""" Arrêt du robot
	"""
	rot_moteur('G', 0)
	rot_moteur('D', 0)


def avancer_cont(vitesse, rayon):
	""" Avance du robot en continue
		réalisant un virage de rayon donné [m]
			None : rayon infini = ligne droite
			0    : rotation sur place
		à une vitesse donnée en %
	"""
	# Calcul des vitesse angulaires (vitesse arbitrairement fixée à 1.0)
	wD, wG = vitesses_roues(1.0, rayon)
	# Normalisation pour obtenir une valeur absolue égale à <vitesse>
	wmax = max(abs(wD), abs(wG))
	if wmax != 0:
		wD, wG = wD*vitesse/wmax, wG*vitesse/wmax
		
	rot_moteur('G', wG)
	rot_moteur('D', wD)


########################################################################
# Procédures de test du module
########################################################################
if __name__ == "__main__":
	#rot_moteur('G', 100)
	#time.sleep(1)
	#rot_moteur('D', 100)
	#time.sleep(1)
	#rot_moteur('D', -50)
	#time.sleep(1)
	#rot_moteur('D', 0)
	#rot_moteur('G', 0)
	
	time.sleep(10)
	avancer_cont(80, None)
	time.sleep(1)
	avancer_cont(40, 0)
	time.sleep(1)
	avancer_cont(100, 0.5)
	time.sleep(5)
	
	GPIO.cleanup()

 

Module AlphaBot

Un module Python « maison », nommé AlphaBot.py, permet un accès rapide aux principales fonctions de pilotage des moteurs :

class AlphaBot(builtins.object)
 |  AlphaBot(in1=12, in2=13, ena=6, in3=20, in4=21, enb=26)
 |
 |  __init__(self, in1=12, in2=13, ena=6, in3=20, in4=21, enb=26)
 |      Initialize self.  See help(type(self)) for accurate signature.
 |
 |  backward(self)
 |      Action sur le pont en H :
 |      Les deux moteurs dans le sens ARRIERE
 |
 |  forward(self)
 |      Action sur le pont en H :
 |      Les deux moteurs dans le sens AVANT
 |
 |  left(self)
 |      Action sur le pont en H :
 |      Moteur Gauche dans le sens AVANT
 |      Moteur Droit dans le sens ARRIERE
 |
 |  right(self)
 |      Action sur le pont en H :
 |      Moteur Gauche dans le sens ARRIERE
 |      Moteur Droit dans le sens AVANT
 |
 |  setMotor(self, left, right)
 |
 |  setPWMA(self, value)
 |      Change le rapport cyclique moteur Gauche
 |      0 <= value <= 100
 |
 |  setPWMB(self, value)
 |      Change le rapport cyclique moteur Droit
 |      0 <= value <= 100
 |
 |  stop(self)
 |      Action sur le pont en H :
 |      Les deux moteurs ARRETES

Téléchargement : AlphaBot

Utilisation

with AlphaBot() as Ab:
    Ab.stop()

 

 

 

 

Vous aimerez aussi...

Laisser un commentaire

Votre adresse e-mail ne sera pas publiée. Les champs obligatoires sont indiqués avec *