Club robotique de Sophia-Antipolis

Accueil > POBOTpedia > Electronique > Montages électroniques > Modifier la fréquence d’un PWM

Modifier la fréquence d’un PWM

dimanche 2 janvier 2011, par Julien H.

Un signal PWM est défini par son rapport cyclique (le temps au niveau haut par rapport à la période totale) mais aussi par sa fréquence.

C’est cette fréquence qui nous intéresse aujourd’hui : il faut l’adapter à l’usage qu’on va faire, de quelques centaines de Hertz à plusieurs kHz.

Pour un usage courant en électronique ludique, 500 ou 1000 Hz sont suffisant pour modifier l’intensité d’une led, notamment pour obtenir des couleurs variées sur un éclairage RGB, ou pour commander un dispositif externe en faisant varier une tension.

Mais ces fréquences sont audibles et si un résonateur est connecté au signal PWM, vous devriez être rapidement gêné. C’est ce qui se passe en robotique quand le PWM est utilisé pour piloter un moteur : on utilise le PWM pour modifier la vitesse à travers un composant de puissance qui démarre et arrête les moteurs.

Ce problème est notamment important avec le robot à chenilles RP5 qu’utilise le club pour ses ateliers. Cet article va utiliser cet exemple pour vous montrer comment faire disparaitre le bruit.

Attention, Henri nous a présenté lors d’un atelier les inconvénients qu’il peut y avoir à modifier la fréquence d’un PWM : avec une fréquence trop faible et si le moteur n’est pas protégé, le courant que laisse passer le PWM va augmenter proportionnellement à l’allongement de la longueur d’onde ce qui peut griller le moteur.

Un PWM à modifier

Dans les montages à base de micro-contrôleur type AVR, on bénéficie de compteurs internes au circuit intégré permettant de réaliser un signal PWM. 

On ne va donc pas présenter ici comment générer un PWM (si vous savez le générer, vous savez modifier sa fréquence), mais comment modifier la fréquence d’un PWM généré par le micro-contrôleur et commandé par une bibliothèque PWM telle qu’on en trouve dans des environnements simplifiés type Arduino.

Cette simplification masque toutes les insctructions d’initialisation nécessaires, et même le nom des fonctions réelles du circuit intégré.

En résumé :

La modification de la fréquence se fait facilement en changeant la valeur du "prescaler" du compteur qui divise l’horloge.

Un PWM sur Arduino

Grâce à l’environnement de programmation simplifié, un PWM s’obtient sur une Arduino classique avec la fonction analogWrite utilisé sur une patte numérique Digital 3, 5, 6, 9, 10 ou 11.

Le code est simple, utilisé ici pour faire varier l’accélération d’un moteur sur le robot :


void loop()
// accélération
for (int i=0 ; i<256 ; i++)
// on "écrit" la vitesse (i) sur la patte 5 de l’Arduino
// connectée à l’enable du driver de moteur
analogWrite(5,i) ;
// le délai détermine la pente de l’accélération (en ms)
delay(100) ;
 ;

Lecture de la datasheet

La datasheet ou doc technique est un fichier de plusieurs dizaines de page présentant les caractéristiques d’un composant. On la trouve tout simplement sur le site du constructeur.

Il faut tout d’abord trouver quelle est la patte du micro-contrôleur AVR utilisée par Arduino comme sortie Digital 5. La lecture du schéma nous indique qu’il s’agit de la patte 5 du port D de l’ATmega328 (attention, cette correspondance directe n’est valable que pour D0 à D7, ensuite on change de port donc de lettre.

Schéma de l’Arduino

Datasheet résumée de l’Arduino

Puis la datasheet de l’AVR ATmega48-88-168-328 etc.. (bref, la famille ATmega8) nous apprend que cette patte 5 du port D sert à la fois d’entrée/sortie à usage générique (GPIO) et d’interruption 21 ou encore de OC0B.

C’est cette dernière fonction qui nous intéresse :
 OC désigne une fonctionnalité d’un timer output compare
 0 désigne le compteur de temps 0.
 B désigne la seconde sortie

Il faut alors faire appel à la version non abrégée de la datasheet (celle-ci fait plus de cinq cent pages) pour connaitre quelles instructions ou registres influent sur ce compteur.

Le document page 90 nous apprend ainsi que le mode PWM du timer 0 utilise bien cette sortie. On est sur la bonne piste.

Attention, si vous utilisez une autre patte de l’Arduino, il faut refaire la recherche. Par exemple la patte 10 d’une Arduino est la patte 16 ou port B2 de l’AVR et son mode PWM est OC1B donc il faut adapter les registres !!

Modification

Le compteur/timer 0 est configuré par deux registres : TCCR0A et TCCR0B. Attention à ne pas faire de raccourci et penser que l’un pilote OC0A et l’autre OC0B, il n’en est rien.

C’est TCCR0B qui nous intéresse : les trois premiers bits CS00 CS01 et CS02 permettent de sélectionner la valeur du diviseur de fréquence (ou prescaler).

Il s’agit en fait de diviser l’horloge du timer : il s’agit de l’horloge des entrées/sorties (ou I/O clock) et pas de l’horloge système qui est à la fréquence du quartz, soit 16 MHz.

L’horloge I/O est déjà 256 fois moins que l’horloge CPU, soit 62500 Hz. C’est cette valeur qu’on va pouvoir diviser, elle constitue donc notre fréquence maximum (sans avoir à modifier le prescaler de l’horloge I/O ou à utiliser une horloge externe).

Il suffit désormais de suivre le tableau de valeurs de ces 3 bits et de coder dans l’initialisation de notre robot une ligne de modification de ce registre TCCR0B. On utilise alors les raccourcis de manipulation en code binaire pour garder un code lisible.

diviseur valeur de bits
pas de division 0 0 1 (=1)
division par 8 0 1 0 (=2)
division par 64 0 1 1 (=3)
division par 256 1 0 0 (=4)
division par 1024 1 0 1 (=5)

Les autres valeurs ne servent pas à modifier le prescaler, mais à arrêter le timer ou à utiliser un quartz externe, ne les utilisez pas.

Le code à insérer dans votre "setup" est donc :


TCCR0B = TCCR0B & 0b11111000 | mode ;

où mode prend la valeur de bits indiquée ci-dessus.

Effet de bord

Vous aurez noté que cette fonction utilise le timer 0. Modifier son diviseur de fréquence va donc aussi altérer les autres modes de ce timer, et en premier lieu la fonction "delay" qu’on utilise pour attendre pendant que le moteur tourne.

Il faut donc multiplier vos valeurs de délai ou les diviser selon que vous vous trouvez au-delà ou en de-ça de la valeur par défaut (diviseur de 64). Ainsi un délai d’une seconde sans diviseur doit s’écrire "delay(1000*64)".

Le résultat

Le code complet est disponible sur le Playground Pobot (repository SVN qui contient tous nos codes sources) sous le nom TestVitesseRP5 du projet complet ZarRP5 (le robot à chenilles de Zartronic).

J’ai enregistré les deux sons :
 avec la valeur par défaut sur une Arduino Uno, soit une fréquence de 976 Hz (et non pas 500 Hz comme le disait à tord la doc officielle qui oubliait de dire que les pattes 5 et 6 ont une fréquence double).

Accélération à 976 Hz

 et sans division, soit 62,5 kHz : on n’entend plus de sifflement.

Accélération à 62,5 kHz

Vos commentaires

  • Le 5 juillet 2015 à 13:05, par charles En réponse à : Modifier la fréquence d’un PWM

    Bonjour,
    merci pour votre qui article semble clair même si je n’ai pas tout compris (je débute).
    Juste une question : si j’applique à la lettre la ligne de code dans le setup, c’est la fonction digitalWrite qui est indirectement modifiée c’est bien ça ? donc cela permet de générer un signal PWM sur un OUTPUT que l’on peut laisser en marche même quand le processor fait autre chose ? (c’était le problème de générer un PWM avec la fonction loop...).
    Cordialement

    Répondre à ce message

  • Le 28 mai 2015 à 21:48, par Lassaad Zerai En réponse à : Modifier la fréquence d’un PWM

    slm :)
    je souhaite faire des PWM à fréquence de 4 Khz(3902 acceptable) pour commander un moteur a courant continu,et mrc d’avance (y)

    • Le 2 juin 2015 à 16:39, par Eric P. En réponse à : Modifier la fréquence d’un PWM

      Un peu léger comme question :D
       "faire" des PWM : avec quoi ? Arduino, PC, SBC,...
       quel est le type de driver de puissance pilotant le moteur ?
      Il faudrait décrire les choses d’une manière un peu plus détaillée et précise si vous voulez des réponses exploitables. On ne peut pas deviner ce que vous cherchez à faire ;)

    Répondre à ce message

  • Le 4 mai 2015 à 13:46, par Tfou57 En réponse à : Modifier la fréquence d’un PWM

    Bonjour,
    Très , très intéressant !
    Félicitations :’-)) pour cette vulgarisation de ce sujet pour le PWM Arduino Uno
    Est-ce que , un de vos lecteurs a réalisé la même modification du pWM avec une Arduino DUE à 84MHz ( processeur Atmel SAM 3X8E ) ?
    Merci d’avance

    Répondre à ce message

  • Le 16 mars 2015 à 00:42, par bakre En réponse à : Modifier la fréquence d’un PWM

    salut tous le monde je veux commander un moteur brushless à l’aide d’un esc par raspberry p1 mais je trouve pas comment générer ce signal pwm car pour ce type d’esc ca demande une programmation de ces esc.
    Merci

    • Le 22 mars 2015 à 10:05, par Eric P. En réponse à : Modifier la fréquence d’un PWM

      Le signal de commande de ces ESC est identique à celui des servos et des ESC pour moteurs classiques.
      La "carte de programmation" vendue par les constructeurs sert à configurer et paramétrer certaines fonctions de l’ESC (soft start, brake,...) mais celui-ci possède déjà une configuration par défaut en sortie d’usine qui permet de l’utiliser directement.

    Répondre à ce message

  • Le 26 mars 2014 à 12:11, par mcacj En réponse à : Modifier la fréquence d’un PWM

    Bonjour, je souhaite faire des PWM a des fréquences de 1khz et 10 khz... Sur un Arduino Mega 2560... Est-ce possible ? Merci d’avance !

    • Le 26 mars 2014 à 17:50, par Julien H. En réponse à : Modifier la fréquence d’un PWM

      Bonjour,
      On peut les faire en pilotant soi-même la ligne de sortie et là la fréquence dépend entièrement du code qui va compter le temps.
      Avec la solution automatique, en modifiant l’horloge, je doute qu’on arrive à une fréquence fixe comme celles-ci.
      C’est pour quel usage ?
      Cordialement,
      Julien.

    Répondre à ce message

  • Le 4 juin 2013 à 08:52, par pierro2803 En réponse à : Modifier la fréquence d’un PWM

    Bonjour,
    Nous travaillons sur un projet GBF sur Arduino Uno, mais nous rencontrons quelques problèmes.
    Nous n’arrivons pas a générer un signal sinusoidal d’une fréquence de 1kHz, on arrive à faire un signal sinusoidal de 5Hz et un signal périodique de 1kHz mais impossible d’associer les deux.
    Nous pensons que le problème viens du PWM et des registres à modifier.

    Si quelqu’un pouvais nous aider et éclairer un peu notre lanterne :)

    Cordialement,
    pierro2803.

    Répondre à ce message

Un message, un commentaire ?

modération a priori

Attention, votre message n’apparaîtra qu’après avoir été relu et approuvé.

Qui êtes-vous ?

Pour afficher votre trombine avec votre message, enregistrez-la d’abord sur gravatar.com (gratuit et indolore) et n’oubliez pas d’indiquer votre adresse e-mail ici.

Ajoutez votre commentaire ici

Ce champ accepte les raccourcis SPIP {{gras}} {italique} -*liste [texte->url] <quote> <code> et le code HTML <q> <del> <ins>. Pour créer des paragraphes, laissez simplement des lignes vides.