Didel

Xbot: utiliser le PFM et les interruptions

Avec ce chapitre, on apprend à gérer plusieurs tâches par interruption. Cette approche n'est pas celle d'Arduino, avec ses grosses librairies en C++, mais elle n'est pas incompatible. Elle nous permettra d'ajouter facilement les capteurs les plus courants.

Le PFM est trop peu connu, il est aussi facile à utiliser que le PWM et a un l'avantage de permettre des vitesses aussi lentes que l'on veut.

Avec le PWM d'Arduino, une interruption appelle régulièrement l'impulsion de commande, de longueur variable. Avec le PFM, il faut créer cette interruption. Il y a deux approches pour les interruptions. Chaque tâche peut créer son interruption, et il faut définir des priorités en cas de simultanéité (téléphone et sonnette d'entrée).

Avec la programmation synchrone, une seule interruption balaye les sources d'interruption possibles. Toutes les 100 microsecondes par exemple, on regarde si les moustaches sont pressées, s'il faut activer le moteur A, le moteur B, si l'echo du SR05 est revenu. L'avantage est que tout se déroule dans l'ordre, sans collision.

1. Test du principe PFM

On envoie au moteurs une impulsion de 1 à 2ms, suffisante pour décoller les frottements. Il fait un ou deux tours, mais avec le réducteur, on voit à peine le mouvement . Répétons cette impulsion toute les 4 ms, cela forme une onde carrée, et le moteur reçoit 50% de puissance. Si les impulsions se suivent, on a du 100%. S'il en manque 1 sur 10, du 90%. L'algorithme est expliqué ici. Le programme de test le plus simple accélère le moteur toute les 10 cycles de 2ms. La vitesse passe de 1 à 100 en ~5 secondes.

// TestPfmSimple.ino| On accélère et stoppe
#include <Arduino.h>
#define RecD 4
#define AvD 5
#define AvG 6
#define RecG 7
#define Avance() PORTD |= 0b01100000; PORTD &= 0b01101111
#define Stop() PORTD &= ~0b11110000
void setup() {
DDRD |= 0b11110000 ;
DDRD &= 0b11110011 ;
}
#define MaxPfm 100
byte pfm=0, pfmCnt;
void loop() {
for (byte i=0; i<10; i++) {
pfmCnt += pfm;
if (pfmCnt > MaxPfm) {pfmCnt -= MaxPfm; Avance();}
else {Stop();}
delay (2);
}
pfm++;
if (pfm>MaxPfm) {Stop(); while(1);}
}


On remarque que la vitesse a 100 valeurs et pas 256. Ceci permet de coder les vitesses négatives en 8 bits. On va donc utiliser des vitesses de -100 à +100. Les valeurs supérieures seront saturées, mais il faut bien comprendre le codage des nombres négatifs sur 8 bits. De 0 à 127 c'est positif. Une vitesse de 120 sera saturée à 100. Une vitesse de 140 est vue comme une valeur négative en complément à 256 et vaut -116, donc saturée à -110. On déclare les vitesses signées avec le type char ou uint_8

Testons la fonction pfm bidirectionnelle. Ses paramètres sont globaux. Dans le programme principal, on donne la valeur des vitesses. La fonction DoPfm(); est appelée toutes les 2ms pour décider si c'est le moment d'activer ou désactiver les moteurs. Le programme de test simule la routine d'interruption et doit être recompilé si on change la valeur.

// TestPfmBidir.ino|
// Variables globales
char pfmG, pfmD; // -100 .. 100

#include "XbotPfm.h"

void setup() {
  SetupXbotPfm();
}

void loop () {
  pfmG=2; pfmD=-10;
  DoPfm ();
  delay (2);
}


// XbotPfm.h
#include <Arduino.h>
#define bRecD 4 // HIGH LOW
#define bAvD 5 // pwm
#define bAvG 6 // pwm
#define bRecG 7
#define AvG bitSet (PORTD,bAvG); bitClear(PORTD,bRecG)
#define RecG bitClear(PORTD,bAvG); bitSet (PORTD,bRecG)
#define StopG bitClear(PORTD,bAvG); bitClear(PORTD,bRecG)
#define AvD bitSet (PORTD,bAvD); bitClear(PORTD,bRecD)
#define RecD bitClear(PORTD,bAvD); bitSet (PORTD,bRecD)
#define StopD bitClear(PORTD,bAvD); bitClear(PORTD,bRecD)
void SetupXbotPfm() {
  DDRD |= 0b11110000 ;
  DDRD &= 0b11110011 ;
}
#define MaxPfm 100
volatile byte pfcG, pfcD;
void DoPfm () {
  char tempG,tempD;
  if (pfmD > MaxPfm) pfmD=MaxPfm; // saturer
  if (pfmD < -MaxPfm) pfmD= -MaxPfm;
  
  if (pfmD >=0) {
    if ((pfcD+=pfmD)>MaxPfm){pfcD-=MaxPfm;AvD;}
    else { StopD; }
  }
  if (pfmD <0) {
    tempD= -pfmD; // ou pfd= ABS(pfd)
    if ((pfcD+=tempD)>MaxPfm){pfcD-=MaxPfm;RecD;}
    else { StopD; }
  }
  if (pfmG > MaxPfm) pfmG=MaxPfm; // saturer
  if (pfmG < -MaxPfm) pfmG= -MaxPfm;>   if (pfmG >=0) {
  if ((pfcG+=pfmG)>MaxPfm){pfcG-=MaxPfm;AvG;}
  else { StopG; }
  }
  if (pfmG <0) {
    tempG= -pfmG; // ou pfg= ABS(pfg)
    if ((pfcG+=tempG)>MaxPfm){pfcG-=MaxPfm;RecG;}
    else { StopG; }
  }
}

Interruptions timer 2

Les interruptions et le Timer2 sont expliqués ici, comme on va les utiliser. Cette doc montre comment clignoter; on va simplement un peu plus vite avec les impulsions moteur.

On va définir une période de 58 us en prévision d'autres tâches d'interruption. Avec des compteurs, on décide d'intervenir toutes les 2ms pour le PFM. On pourra ajouter beaucoup d'autres actions, à condition que chaque action no dure que quelques microsecondes. On voit que la fonction DoPfm n'exécute, à cause de .if, que 20 à 30 instructions C. A 16 Mhz, cela prend ~10 microsecondes.

Si le PFM est géré par interruptions, le programme principal est libre d'utiliser des fonctions bloquantes, delay() ou pulesIn() par exemple. On voit que pour tester l'aller-retour, le programme n'a que des modifications mineures par rapport au programme PWM du chapitre précédent. Au lieu d'appeler la fonctions PwmDG() , on modifie les variables pfmG et pfmD

// AllerRetPfm.ino aller-retour vitesse variable
// accelere en 2.5s
char pfmG, pfmD; // -MaxPfm .. 0 .. MaxPfm

#include "XbotPfm.h"
#include "Inter.h"
void setup() {
  SetupXbotPfm();
  SetupInter();
}
char vit;
#define DelEvol 5
void loop() {
  for (vit=0; vit<100; vit++) {
  pfmG=vit; pfmD =vit;
  delay (DelEvol);
  }
  for (vit=100; vit>-100; vit--) {
    pfmG=vit; pfmD =vit;
    delay (DelEvol);
  }
  for (vit=-100; vit<=0; vit++){
    pfmG=vit; pfmD =vit;
    delay (DelEvol);
  }
}

// Inter.h Timer2

volatile byte cnt1,cnt2;
ISR (TIMER2_OVF_vect) {
  TCNT2 = 141; // 58 us calibre avec corr
  // on appellera ici le Uson SR05
  if (cnt1++ > 40) { // toutes les 40x58= 2.5ms
    cnt1=0; DoPfm();
  }
  if (cnt2++ > 250) { // toutes les 250x58= 20ms
    cnt2=0; // tâches lentes futures
  }
}

void SetupInter() { // initialisation
  TCCR2A = 0; //default
  TCCR2B = 0b00000010; // clk/8
  TIMSK2 = 0b00000001; // TOIE2
  sei();
}

Conclusion

La structure pour continuer est maintenant en place. On peut enchaîner dans le programme principal des tâches avec des délais, des affichages, des assignations de variables gérées par interruption. On peut appeler par interruption des routines s'exécutant en peu d'instructions, basées sur des machines d'état.

La documentation de Libx se développe sous Github , voir aussi le catalogue des appels LibX Vos contributions et commentaires sont bienvenus.

Les documents pédagogiques suivant utilisent le concepts des fichiers inclus:

Lecture de capteur de distance SR05 et affichage sur Oled  

Lecture de capteur de distance IR et affichage sur Oled  

Des documents plus anciens ont parfois un style ou des notations qui doivent être revues.

 

jdn 170817