Table des matières

Commutateur triphasé à six états

1. Introduction

Ce document décrit le fonctionnement d'un commutateur permettant d'alimenter trois bobines, en montage étoile ou triangle, avec 6 états de tension différents. Ce type de commutateur est utilisé pour la commande des moteurs nommés moteurs à courant continu sans balais (Brushless direct current motors, BLDC). Il s'agit de moteurs synchrones à stator triphasé (dont le rotor est constitué d'aimants permanents) mais dont la commande consiste à appliquer des tensions constantes par intervalle aux bornes des bobines, ce qui fait que leur mode de fonctionnement est proche de celui du moteur à courant continu. Il s'agit en quelque sorte d'un moteur à courant continu dont la commutation mécanique (par les balais) est remplacée par une commutation électronique. Cette commutation est en effet pilotée par la position du rotor, de manière similaire à la commutation effectuée par les balais. Une dénomination plus rigoureuse des moteurs DC sans balais est : moteur synchrone auto-piloté, en raison de la commutation pilotée par le rotor. Remarquons que le fait que la source d'énergie de ces moteurs délivre une tension constante n'est pas une bonne raison de les nommer moteurs à courant continu sans balais car beaucoup de moteurs fonctionnent aujourd'hui avec une source à tension constante, la tension alternative étant générée par l'électronique de commande. Il est par ailleurs possible de commander un moteur à courant continu sans balais avec des tensions sinusoïdales (avec auto-pilotage) mais dans ce cas sa dénomination n'a plus de sens.

Dans ce document, nous décrivons cette commutation à 6 états et son implémentation avec un pont de transistors MOSFET piloté par un arduino MEGA. Le problème de l'auto-pilotage par le rotor n'est pas traité.

2. Commutation à 6 états et 2 courants

2.a. Montage des bobines en étoile et champ magnétique tournant

Les trois bobinages d'un stator triphasé peuvent être montées en triangle ou en étoile. Nous considérons le cas du montage en étoile, qui permet d'alimenter simultanément deux bobines. Les schémas suivants représentent trois bobines dont les axes sont disposés à 120 degrés les uns des autres, ce qui correspond effectivement à la disposition des bobines dans le stator triphasé le plus simple. Les trois bobines ont une borne reliée au point neutre (N). Les autres bornes sont notées A,B,C. La commutation à 6 états et à deux courants consiste à appliquer une tension entre seulement deux bornes parmi A,B,C, l'autre étant laissée à l'état non connecté (potentiel flottant). Pendant un état de commutation, le courant ne passe que dans deux bobines (via le point neutre).

Pour modéliser la génération du champ tournant, nous supposons qu'aucun rotor n'est présent. La direction du champ magnétique qui résulte de ce courant se déduit d'une construction géométrique simple consistant à sommer les champ magnétiques produits par les trois bobines au centre du dispositif. La figure suivante représente l'état du système lorsqu'on applique une tension positive de la borne A par rapport à la borne B, la borne C étant laissée non connectée.

3bobines-1-fig.svgFigure pleine page

La flèche rouge représente le sens du courant électrique. Les flèches bleues représentent les champs magnétiques créés par chacune des deux bobines parcourues par un courant et leur somme. Cette configuration produit au centre du dispositif un champ magnétique B faisant un angle de 150 degrés par rapport à l'axe (Ox). Remarquons que ce modèle de détermination du champ tournant, bien que permettant de décrire correctement la séquence de commutation et la fréquence de rotation du champ, ne permet pas de connaître précisément le champ glissant de l'entrefer dans le cas de la présence d'un rotor cylindrique en matériau ferromagnétique doux.

L'état suivant est obtenu en appliquant une tension positive à la borne A par rapport à la borne C, la borne B passant à l'état libre (potentiel flottant).

3bobines-2-fig.svgFigure pleine page

Dans le raisonnement qui suit, nous supposons que le temps d'établissement du courant dans les deux bobines auquelles une tension est appliquée est négligeable devant la durée d'un état de commutation.

Le champ magnétique dans cette configuration fait un angle de 210 degrés par rapport à l'axe (Ox). Il a donc tourné de 60 degrés par rapport à la configuration précédente. La suite des états doit permettre de faire tourner le champ toujours dans le même sens, par saut de 60 degrés. Le passage d'un état au suivant consiste à garder une borne à son potentiel, à déconnecter l'autre et à appliquer à la troisième le potentiel contraire de la première. Notons AB l'état dans lequel la borne A est à un potentiel plus élevé que la borne B, la borne C étant à un potentiel flottant. Dans cet état, le courant circule (après un régime transitoire) de la borne A vers la borne B (nous ignorons la force contre-électromotrice dans les bobines). Pour obtenir une rotation du champ dans le sens trigonométrique (sens horaire inversé), la séquence des états est :

AB,AC,BC,BA,CA,CB cycle-fig.svgFigure pleine page

Le cycle complet est constitué de 6 états, ce qui fait bien une rotation de 6x60 = 360 degrés du champ magnétique. Le cycle est divisé en 6 secteurs de 60 degrés (valeur de la phase mais aussi angle du champ magnétique). La règle de commutation est la suivante : chaque borne reste à un potentiel positif pendant deux secteurs consécutifs (soit 120 degrés) puis passe à l'état non connecté pendant un secteur avant de passer à un potentiel nul pendant deux secteurs. La figure suivante montre l'évolution au cours du temps des potentiels des trois bornes :

sequence-fig.svgFigure pleine page

Si l'on considère par exemple le 4e état, on VB-VA=E, ce qui conduit à un courant positif circulant de B vers A, et la borne C est non connectée. Si l'on veut faire tourner le champ magnétique dans le sens horaire, il suffit d'inverser deux bornes dans la séquence, par exemple les bornes B et C :

AC,AB,CB,CA,BA,BC

Remarque importante : le modèle de champ tournant utilisé ici, consistant à considérer la somme des trois vecteurs de champ magnétique générés par les trois bobines au centre du dispositif, ne peut donner la forme exacte du champ glissant produit au niveau de l'entrefer entre le stator et le rotor.

Dans le cas du stator d'un moteur synchrone à stator bipolaire, le champ magnétique dans l'entrefer a ses deux pôles dans une direction à peu près constante pendant un sixième de période, alors que dans une machine synchrone à commande sinusoïdale, les deux pôles tournent de manière continue. Dans un moteur à courant continu (avec balais), le champ magnétique créé par le stator est effectivent de direction fixe. Pour cette raison, le fonctionnement du moteur DC sans balai pendant un secteur de 60 degrés est similaire à celui du moteur à courant continu. On doit donc s'attendre à ce que la vitesse de rotation à charge mécanique nulle soit proportionnelle à la tension E. La commutation doit être pilotée par le rotor, de manière similaire à la commutation effectuée par les balais dans un moteur à courant continu.

Le modèle présenté ci-dessus conduit à un champ tournant par saut de 60 degrés car le temps d'établissement du courant dans les bobines est supposé très faible devant la durée d'un état. Pour une bobine d'auto-inductance L et de résistance r, si une tension E est appliquée à ses bornes, le temps qu'il faut pour que le courant atteigne E/r est de l'ordre de L/r. Si ce temps est de l'ordre de grandeur de la période de commutation, le champ tourne en réalité de manière continue. Notons aussi que, dans un moteur, le courant dépend de la force contre-électromotrice et que celle-ci augmente avec la vitesse du moteur, donc avec la fréquence de commutation. Le calcul correct du courant dans le stator nécessite donc la prise en compte de cette f.é.m. donc la prise en compte du mouvement du rotor.

Pour chacune des six états de commutation, une des bobines n'est pas alimentée (le courant qui la traverse est nul). Il est donc possible de faire une mesure de force électromotrice aux bornes de cette bobine, ce qui permet d'obtenir une information sur la position du rotor. Les commandes de moteur BLDC sans capteur réalisent un auto-pilotage reposant sur le passage de la f.é.m. de la bobine libre par zéro.

En annexe, nous présentons un autre schéma de commutation où le courant passe à tout instant dans les trois bobines.

2.b. Montage en triangle

Lorsque les trois bobines sont montées en triangle, le courant ne passe que dans une bobine à la fois. Voici la configuration AB :

3bobines-triangle-fig.svgFigure pleine page

La séquence permettant d'obtenir un champ tournant dans le sens trigonométrique (par saut de 60 degrés) est la même que pour le montage en étoile :

AB,AC,BC,BA,CA,CB cycle-triangle-fig.svgFigure pleine page

Dans le montage en triangle, la tension est appliquée à une seule bobine alors qu'elle est appliquée à deux bobines en série dans le montage en étoile. La différence la plus importante de ces deux montages est sans doute dans la direction du champ : dans le montage en triangle, le champ magnétique est dans l'axe des bobines alors qu'il est incliné de 30 degrés dans le cas du montage en étoile.

2.c. Principe du pont de transistors

La commutation est obtenue grace à un pont de 6 transistors, similaire à celui qui est utilisé pour réaliser un onduleur triphasé. Dans le schéma simplifié ci-dessous, chaque transistor est représenté par un interrupteur en parallèle avec une diode (diode source-drain d'un transistor MOSFET ou diode de roue libre ajoutée) :

pont3phases-fig.svgFigure pleine page

Notons 1 l'état d'un interrupteur fermé et 0 son état ouvert. Chaque bras de pont (constitué d'un transistor haut et d'un transistor bas) est soit dans l'état 10 (transistor haut fermé), soit dans l'état 01 (transistor bas fermé), soit dans l'état 00. L'état 10 permet de placer la borne de phase correspondante au potentiel Vs (tension de la source), l'état 01 permet de la placer au potentiel nul, l'état 00 en potentiel flottant (borne déconnectée). L'état AB est obtenu avec l'état suivant des trois bras : 10,01,00. La séquence de commutation est :

10,01,00 10,00,01 00,10,01 01,10,00 01,00,10 00,01,10

La tension E effective appliquée est ajustée par modulation de largeur d'impulsion (MLI). Sur chaque secteur, on effectue une alternance de la tension appliquée (entre deux phases) entre 0 et Vs à une fréquence de découpage assez élevée (typiquement de 10 à 100 kHz). Cette alternance concerne bien sûr la borne qui se trouve au potentiel le plus élevé (l'autre restant à la masse). Par exemple pour le premier secteur (état AB), on effecte l'alternance 10,01,00 avec 01,01,00 avec un rapport cyclique qui permet d'ajuster la valeur de E (la tension moyenne) entre 0 et Vs. En réalité, le moyennage se fait sur le courant dans la bobine et non pas sur la tension, mais E est la tension effective, c'est-à-dire la tension constante qui donnerait le même courant que le courant moyen résultant du découpage. Il faut évidemment que la fréquence de découpage soit assez élevée pour que les ondulations du courant soient très faibles.

Dans un moteur à courant continu sans balais (ou moteur synchrone auto-piloté), l'alternance des 6 états est pilotée par le rotor, c'est-à-dire qu'à chaque secteur de 60 degrés où se trouve le rotor correspond un état de commutation bien précis, celui qui maximise le couple pour ce secteur. La vitesse de rotation est déterminée par E, donc par le rapport cyclique du signal MLI. Dans ce document, nous n'étudions pas l'auto-pilotage : la séquence des 6 états sera simplement pilotée par le logiciel, à une cadence déterminée. Remarquons cependant qu'un moteur synchrone ne peut pas démarrer si la commutation est effectuée sans aucune référence à la position du rotor. L'auto-pilotage est donc indispensable pour démarrer le moteur et aussi pour assurer un fonctionnement stable en régime permanent. Seul un moteur fonctionnant à vitesse constante peut se passer de l'auto-pilotage, à condition d'être associé à un dispositif de démarrage. Les moteurs synchrones des véhicules électriques sont évidemment auto-pilotés.

2.d. Programme Arduino

Le pont de commutation comporte 6 transistors MOSFET qui doivent être pilotés indépendamment. On doit donc utiliser 3 Timers, chacun pilotant un bras de deux transistors. Le programme donné ci-dessous fonctionne avec l'Arduino MEGA. Il utilise les Timers 16 bits 1,3 et 4. Pour chaque Timer, les sorties A et B pilotent les deux transistors. Voici à quelles sorties de la carte des sorties des trois Timers sont reliées, comme l'indique la table de correspondance :

  • Timer 1 : OC1A (D11), OC1B (D12), OC1C (D13).
  • Timer 3 : OC3A (D5), OC3B (D2), OC3B (D3).
  • Timer 4 : OC4A (D6), OC4B (D7), OC4C (D8).

Les entrées qui pourront être utilisées pour les interruptions matérielles sont les entrées 18,19,20 et 21.

Le fonctionnement d'un Timer pour la génération des deux signaux est montré sur la figure suivante :

timer-fig.svgFigure pleine page

Le compteur (registre TCNT1) est incrémenté à une cadence égale à la fréquence d'horloge (16 MHz) divisée par 1, 8, 64, 256 ou 1024 (diviseur d'horloge). Il est incrémenté jusqu'à la valeur contenue dans le registre ICR1 puis décrémenté jusqu'à zéro. Les sorties OC1A et OC1B sont générées à partir des seuils définis dans respectivement OCR1A (Output Compare Register) et OCR1B. La sortie OC1A est configurée avec le mode : clear OC1A on compare when up counting, la sortie OC1B avec le mode : set OC1B on compare match when up counting. Cela permet de générer deux signaux inverses pour piloter les deux transistors d'un bras du pont. Supposons que OC1A pilote le transistor supérieur du bras de la phase A et OC1B le transistor inférieur. L'état 10 de ce bras est obtenu par OC1A = 1 et OC1B = 0 alors que l'état 01 est obtenu par OC1A = 0 et OC1B = 1. L'état 00 est obtenu avec OCR1A = 0 et OCR1B = ICR1 + 1. Le rapport cyclique est le rapport OCR1A/ICR1.

Chaque secteur de 60 degrés (un sixième de période) est défini par un état des sorties A,B,C du pont (ne pas confondre ces lettres avec celles des sorties d'un Timer). Par exemple l'état AB est obtenu en appliquant un signal MLI pour commander les deux transistors du bras A (alternance d'états 01 et 10) alors que le bras B reste dans l'état 01 et le bras C dans l'état 00.

Dans un moteur dont la position du rotor est contrôlée par des capteurs, le passage d'un secteur à l'autre est déclenché par une interruption matérielle en prevenance de ces capteurs. Pour notre test, nous déclenchons ce passage dans la boucle loop. Pour un moteur qui tourne à une vitesse maximale de 6000 tours par minute, la fréquence de rotation maximale est de 100 Hz et il faut donc changer d'état à la cadence maximale de 600 Hz (si le rotor est bipolaire, mais deux fois plus s'il est quadrupolaire). La fréquence de découpage (porteuse de signal MLI) dépend des bobines du stator mais elle doit être au minimum de 10 kHz.

generateurPWM-3Phases-6Etats.ino
// bras de pont phase A
#define INA_1 11 // transistor haut
#define INA_2 12 // transistor bas
// bras de pont phase B
#define INB_1 5 
#define INB_2 2 
// bras de pont phase C
#define INC_1 6 
#define INC_2 7 

// états d'un bras de pont
#define HIGH_0_LOW_1 0 // sortie à la masse (état 01)
#define HIGH_1_LOW_0 1 // sortie en PWM (état 10)
#define HIGH_0_LOW_0 2 // sortie non connectée (état 00)

uint8_t sequence_A[6] = {1,1,2,0,0,2};
uint8_t sequence_B[6] = {0,2,1,1,2,0};
uint8_t sequence_C[6] = {2,0,0,2,1,1};

uint8_t is = 0;


uint16_t icr;
uint16_t ocra,ocrb;
uint16_t temps_mort = 0;
uint16_t diviseur[6] = {0,1,8,64,256,1024};

void config_timers(float period, float rapport) {
  // period : période du PWM en microsecondes
  cli();
  TCCR1A = (1 << COM1A1) | (1 << COM1B1) | (1 << COM1B0);
  TCCR1B = (1 << WGM13);
  TCCR3A = (1 << COM1A1) | (1 << COM1B1) | (1 << COM1B0);
  TCCR3B = (1 << WGM13);
  TCCR4A = (1 << COM1A1) | (1 << COM1B1) | (1 << COM1B0);
  TCCR4B = (1 << WGM13);

  icr = (F_CPU/1000000*period/2);
    int d = 1;
    while ((icr>0xFFFF)&&(d<5)) {
        d++;
        icr = (F_CPU/1000000*period/2/diviseur[d]);
    } 
  TCCR1B |= d;
  TCCR3B |= d;
  TCCR4B |= d;
  ocra = icr*rapport-temps_mort;
  ocrb = icr*rapport+temps_mort;
  TCNT1 = 0;
  TCNT3 = 0;
  TCNT4 = 0;
  ICR1 = icr;
  ICR3 = icr;
  ICR4 = icr;
  OCR1A = ocra;
  OCR1B = ocrb;
  OCR3A = ocra;
  OCR3B = ocrb;
  OCR4A = ocra;
  OCR4B = ocrb;
  sei();
}

void etat_bras_A(uint8_t etat) {
  switch (etat) {
    case HIGH_0_LOW_1:
      OCR1A = 0;
      OCR1B = 0;
      break;
    case HIGH_1_LOW_0:
      OCR1A = ocra;
      OCR1B = ocrb;
      break;
    case HIGH_0_LOW_0:
      OCR1A = 0;
      OCR1B = icr+1;
      break;
  }
}

void etat_bras_B(uint8_t etat) {
  switch (etat) {
    case HIGH_0_LOW_1:
      OCR3A = 0;
      OCR3B = 0;
      break;
    case HIGH_1_LOW_0:
      OCR3A = ocra;
      OCR3B = ocrb;
      break;
    case HIGH_0_LOW_0:
      OCR3A = 0;
      OCR3B = icr+1;
      break;
  }
}

void etat_bras_C(uint8_t etat) {
  switch (etat) {
    case HIGH_0_LOW_1:
      OCR4A = 0;
      OCR4B = 0;
      break;
    case HIGH_1_LOW_0:
      OCR4A = ocra;
      OCR4B = ocrb;
      break;
    case HIGH_0_LOW_0:
      OCR4A = 0;
      OCR4B = icr+1;
      break;
  }
}

void setup() {
  pinMode(INA_1,OUTPUT);
  digitalWrite(INA_1,LOW);
  pinMode(INA_2,OUTPUT);
  digitalWrite(INA_2,LOW);
  pinMode(INB_1,OUTPUT);
  digitalWrite(INB_1,LOW);
  pinMode(INB_2,OUTPUT);
  digitalWrite(INB_2,LOW);
  pinMode(INC_1,OUTPUT);
  digitalWrite(INC_1,LOW);
  pinMode(INC_2,OUTPUT);
  digitalWrite(INC_2,LOW);
  
  config_timers(100,0.3);
}

void loop() {
  delay(10);
  etat_bras_A(sequence_A[is]);
  etat_bras_B(sequence_B[is]);
  etat_bras_C(sequence_C[is]);
  is += 1;
  if (is==6) is=0;
}

                   

Voici les tensions des sorties D11 et D12, qui commandent le bras de pont A (la fréquence de découpage est seulement de 1 kHz pour permettre la visibilité du signal MLI) :

import numpy as np
from matplotlib.pyplot import *

[t,u_high, u_low] = np.loadtxt('test-1.txt',unpack=True,skiprows=1)
t -= t.min()
figure(figsize=(20,6))
plot(t,u_high,label='HIGH')
plot(t,u_low,label='LOW')
xlabel('t (s)',fontsize=16)
ylabel('Volts',fontsize=16)
legend(loc='upper right')
                   
fig1fig1.pdf

On voit sur cet oscillographe la succession des trois états du bras de pont : alternance HIGH=1,LOW=0 avec HIGH=0,LOW=1 pendant 120 degrés (partie MLI), HIGH=0,LOW=0 pendant 60 degrés (état non connecté de la sortie), HIGH=0,LOW=1 pendant 120 degrés (sortie à la masse).

Voici une vue détaillée de la partie MLI, pour une fréquence de 10 kHz:

[t,u_high, u_low] = np.loadtxt('test-2.txt',unpack=True,skiprows=1)
t -= t.min()
figure(figsize=(20,6))
plot(t,u_high,label='HIGH')
plot(t,u_low,label='LOW')
xlabel('t (s)',fontsize=16)
ylabel('Volts',fontsize=16)
legend(loc='upper right')
                    
fig2fig2.pdf

Ces signaux de commande des deux transistors d'un bras de pont ont un inconvénient : la réponse d'un transistor n'étant pas instantanée, il peut y avoir un moment bref où les deux transistors sont passants en même temps, ce qui implique un courant allant directement de la borne plus de la source à la masse via les deux transistors. Ce court-circuit doit être évité car il cause des pertes d'énergie. Pour cela, il faut introduire un temps mort entre le changement de HIGH et celui de LOW. Il suffit d'abaisser légèrement le rapport cyclique du signal qui commande le transistor du haut et d'augmenter légèrement celui du signal qui commande le transitor du bas. La variable globale temps_mort définit la moitié du temps mort en unité de période d'horloge (avec le facteur de division). Voici les signaux pour une fréquence de découpage de 10 kHz et temps_mort=10 :

[t,u_high, u_low] = np.loadtxt('test-3.txt',unpack=True,skiprows=1)
t -= t.min()
figure(figsize=(20,6)) 
plot(t,u_high,label='HIGH')
plot(t,u_low,label='LOW')
xlabel('t (s)',fontsize=16)
ylabel('Volts',fontsize=16)
legend(loc='upper right')
                    
fig3fig3.pdf

Lorsqu'un transistor passe à l'état passant (la tension de commande passe de 0 à 5 V), l'autre transistor a déjà reçu le front descendant (commandant le passage à l'état bloquant) depuis un certain temps, égal ici à 20 fois la période d'horloge. Ce temps mort sera à ajuster en fonction du temps de réponse des transistors.

2.e. Convertisseur MOSFET

Le convertisseur est constitué de 6 transistors MOSFET.

onduleur3phasesMOSFET.svgFigure pleine page

Chaque bras de pont, constitué de deux transistors, est piloté par un circuit intégré IR2113 (voir Transistor MOSFET de puissance). Ce pilote de MOSFET a la particularité de permettre un pilotage séparé du transistor haut et du transistor bas, ce qui est indispensable pour réaliser le convertisseur. Trois alimentations sont nécessaires : une alimentation 5 V pour le circuit IR2113, une alimentation 15 V pour la polarisation des grilles des transistors et l'alimentation de puissance pour les bobines du moteur (jusqu'à 500 V mais limitée par la tension maximale des condensateurs C1 et C14). Les trois sorties (OUTA, OUTB, OUTC) doivent être reliées aux bornes A,B,C des trois bobines montées en étoile (ou bien en triangle), comme précisé plus haut. Sur chacune de ces sorties, nous avons ajouté un pont diviseur (10k et 33k) donnant une gain de 0,23. Une tension de sortie de 20 V par rapport à la masse sera ainsi ramenée à 4,6 V. Trois résistances de 33k montées en étoile permettent d'obtenir un point neutre virtuel (NVRT). Les trois tensions de OUTA, OUTB et OUTC sont alternatives par rapport à ce point neutre : il s'agit d'une réplique des trois tensions aux bornes des trois bobines du stator. Les trois comparateurs (LM393), alimentés sous 5V, permettent de déterminer le signe de ces trois tensions. On peut ainsi savoir le sens de la tension aux bornes de chaque bobine. Ces comparateurs permettrons de faire un auto-pilotage par détection du passage par zéro de la force contre-électromotrice dans la bobine non alimentée (auto-pilotage sans capteur).

3. Commutation à 6 états et 3 courants

3.a. Définition

Dans ce schéma de commutation à 6 états, on applique un potentiel positif sur une ou deux bornes de phase (A,B, ou C) et un potentiel nul sur les autres. Aucune phase n'est à un potentiel libre. Voici la séquence :

cycle3courants-fig.svgFigure pleine page

La notation A+B-C- signifie qu'une tension positive est appliquée sur les bornes A+ et que les borne B et C sont à la masse. Dans cet état, la bobine A est en série avec l'association en parallèle des bobines B et C. En conséquence, le courant est deux fois plus grand dans la bobine A que dans les deux autres donc le champ magnétique qu'elle génère est aussi deux fois plus grand. La somme des champs (non représentée sur la figure) est dans la direction et le sens du champ le plus fort.

Cette séquence de commutation donne un champ tournant par saut de 60 degrés. Aucune bobine n'est laissée libre donc ce schéma ne convient que si l'auto-pilotage est fait au moyen de capteurs. Par ailleurs, ce mode de commutation produit dans l'entrefer (entre le stator et le rotor) un champ glissant dont les pôles nord et sud n'ont pas la même intensité que les pôles sud. Cet inconvénient ne se voit pas sur le modèle de champ tournant considéré ici mais apparaît si on fait un calcul par éléments finis du champ statorique dans l'entrefer. On peut le comprendre si l'on remarque qu'une des phases est parcourue par un courant deux fois plus grand que les deux autres. Le schéma à 2 courants exposé précédemment (2 bobines alimentées simultanément) est préférable car il donne bien des pôles magnétiques sud et nord de même intensité. Le seul intérêt de ce schéma de commutation à 3 courants réside dans la possibilité de le réaliser avec un pont de transistors dont chaque bras possède une unique commande (qui pilote les deux transistors), ce qui est le cas des ponts en H courramment vendus pour piloter les moteurs à courant continu.

Voici la séquence des tensions :

sequence-3courants-fig.svgFigure pleine page

Chaque bras de pont du convertisseur est soit dans l'état 10 soit dans l'état 01 (les deux transistors sont toujours en états opposés). Il est donc possible de réaliser la commande avec deux ponts en H (4 bras de ponts) dont chaque bras est commandé par un seul signal, comme c'est le cas sur la plupart des ponts vendus pour alimenter les moteurs à courant continu (par exemple le L298).

3.b. Programme Arduino

Lorsque deux bornes doivent être à un potentiel haut (par exemple les bornes A et C dans l'état A+B-C+), il faut appliquer exactement le même signal MLI pour commander les bras de pont reliés aux bornes A et C. En comparaison, la commutation à deux courants (deux phases alimentées simultanément) ne nécessite qu'un seul signal MLI. On doit donc finalement générer 3 signaux MLI identiques, ce qui est faisable avec un Timer, et annuler le signal lorsque la phase correspondante est à la masse.

Le programme ci-dessous génère les signaux avec les trois sorties du Timer 1 (OC1A, OC1B, OC1C). On programme le même signal sur ces trois sorties, avec un rapport cyclique proportionnel à la tension moyenne que l'on veut appliquer aux bobines. Ce rapport cyclique est défini par la valeur attribuée aux registres OCR1A, OCR1B et OCR1C. On la stocke dans une variable ocr. Pour faire passer le bras piloté par OC1A à l'état 0, il suffit de placer zéro dans le registre OCR1A puis de placer à nouveau la valeur de ocr lorsque le bras passe à l'état 1.

generateurPWM-3Phases-6Etats-3courants.ino
#define INA 11
#define INB 12
#define INC 13
#define ENA1 8 // ENABLE pont X
#define ENA2 9  // ENABLE pont Y


uint8_t is = 1;
uint16_t icr;
uint16_t ocr;
uint16_t diviseur[6] = {0,1,8,64,256,1024};

void config_timers(float period, float rapport) {
  // period : période du PWM en microsecondes
  cli();
  TCCR1A = (1 << COM1A1) | (1 << COM1B1) | (1 << COM1C1);
  TCCR1B = (1 << WGM13);
  icr = (F_CPU/1000000*period/2);
    int d = 1;
    while ((icr>0xFFFF)&&(d<5)) {
        d++;
        icr = (F_CPU/1000000*period/2/diviseur[d]);
    } 
  TCCR1B |= d;
  ocr = icr*rapport;
  TCNT1 = 0;
  ICR1 = icr;
  // initialisation à l'état 0
  OCR1A = ocr;
  OCR1B = 0;
  OCR1C = 0;
  sei();

}

void etat_pont(uint8_t etat) {
  // changement de l'état à partir de l'état précédent
  switch(etat) {
    case 0:
      OCR1B = 0;
      break;
    case 1:
      OCR1C = ocr;
      break;
    case 2:
      OCR1A = 0;
      break;
    case 3:
      OCR1B = ocr;
      break;
    case 4:
      OCR1C = 0;
      break;
    case 5:
      OCR1A = ocr;
      break;
  }
}

void setup() {
  pinMode(INA,OUTPUT);
  digitalWrite(INA,LOW);
  pinMode(INB,OUTPUT);
  digitalWrite(INB,LOW);
  pinMode(INC,OUTPUT);
  digitalWrite(INC,LOW);
  pinMode(ENA1,OUTPUT);
  digitalWrite(ENA1,HIGH);
  pinMode(ENA2,OUTPUT);
  digitalWrite(ENA2,HIGH);
  is = 1;
  config_timers(100,0.4);

}

void loop() {
  delay(10);
  etat_pont(is);
  is += 1;
  if (is==6) is=0;
}

         

3.c. Convertisseur

Le convertisseur peut être réalisé avec deux ponts de transistors en H, pourvu que les deux bras de chaque pont soient pilotables séparément, ce qui est rare dans les cartes vendues pour l'alimentation des moteurs à courant continu. Le circuit intégré L298 (voir Pilotage d'un pont L298) convient pour réaliser le convertisseur. Il comporte deux ponts de transistors à jonction bipolaire. Ces performances en vitesse de commutation et en courant maximal peuvent être insuffisantes pour des bobines de stator de faible impédance (à moins d'ajouter des bobines externes au moteur). Nous utilisons plutôt le circuit suivant, réalisé avec deux ponts MOSFET intégrés (L6203) :

onduleur3phasesL6203.svgFigure pleine page

Contrairement au convertisseur décrit plus haut (6 transistors MOSFET discrets), celui-ci ne nécessite qu'une seule alimentation, qui sert à la fois pour la partie logique, pour la commande des grilles et pour fournir la puissance aux bobines. En contrepartie, cette alimentation doit avoir une valeur minimale d'environ 12 V : il est donc impossible d'alimenter les bobines avec une tension inférieure à 12 V, mais la tension effective est de toute façon plus basse car elle est obtenue par MLI.

Creative Commons LicenseTextes et figures sont mis à disposition sous contrat Creative Commons.