Difference between revisions of "Projets:Perso:2013:Module de localisation"
(→Interruption sur CAN) |
(→Les signaux analogiques) |
||
Line 526: | Line 526: | ||
:: // L’ID du message est standard, sur 11 bits. | :: // L’ID du message est standard, sur 11 bits. | ||
=== Les signaux analogiques === | === Les signaux analogiques === | ||
+ | Les microcontrôleurs sont des composants logiques, c’est-à-dire que toutes les données qu’ils traitent sont des données logiques (« 0 » / « 1 ») dont le niveau électrique dépendant de la technologie (0/5V ou 0/3.3V). Il n’est donc, à priori, pas possible de commander un équipement avec un signal analogique variant entre 0 et 5V par exemple, ou de disposer d’une entrée codant sont information sur son niveau électrique.<br /> | ||
+ | Pour palier à cela, il existe deux fonctions complémentaires : <br /> | ||
+ | * ADC : Analogic to Digital Converter, ou convertisseur analogique / numérique. Le fonctionnement détaillé d’un ADC ne sera pas abordé ici, seule sa mise en œuvre sera traitée. | ||
+ | * PWM : Pulse Width Modulation, ou modulation par amplitude d’un signal carré. De même, seule la mise en œuvre avec un Chip sera abordée ici. | ||
+ | ==== Convertisseurs Analogiques / Numériques ==== | ||
+ | Le module ADC va convertir un signal analogique, de niveau 0 à 3.3V ou 5V, en une donnée numérique de type flottant ou entier, signé ou non ('''AD1CON1\FORM<1:0>'''). Le principe est de réaliser un échantillonnage du signal à une fréquence plus ou moins haute, puis de convertir ce signal de manière régulière ou évènementielle ('''AD1CON1\SSRC<2:0>''').<br /> | ||
+ | Ce module utilisera obligatoirement les PIN du chip ayant une capacité de conversion analogique en numérique, à savoir sur le GP/MC802 les ports A0-1, B0-3 et B12-15. Il est en outre possible de choisir les références, positives et négatives, utilisées pour l’échantillonnage du signal ('''AD1CON2\VCFG<2:0>''').<br /> | ||
+ | :: // Format des données converties : 0 = Entier non signé | ||
+ | : AD1CON1bits.FORM = 0; | ||
+ | :: // Source de l’horloge de conversion. J’utilise ici GP Timer 3 : à chaque échéance du timer, une conversion intervient | ||
+ | : AD1CON1bits.SSRC = 2; | ||
+ | :: // Contrôle de l’échantillonnage : 1 => un nouvel échantillonnage démarre automatiquement après la dernière conversion | ||
+ | : AD1CON1bits.ASAM = 1; | ||
+ | :: // Opération en mode 10 Bits. La donnée est convertie sur 10 Bits. Il est possible d’opérer sur 12 également | ||
+ | : AD1CON1bits.AD12B = 0; | ||
+ | :: // Scan des entrées sélectionnées pour CH0+ lors de l’échantillonnage A | ||
+ | : AD1CON2bits.CSCNA = 1; | ||
+ | :: // Conversion du canal CH0 uniquement | ||
+ | : AD1CON2bits.CHPS = 0; | ||
+ | :: // Horloge de conversion dérivée de l’horloge système (réglable) | ||
+ | : AD1CON3bits.ADRC = 0; | ||
+ | :: // Durée de conversion : (n + 1) fois le temps d’opération du chip Tcy, ici 63 => Tad = 0,025ns * (63+1) = 1,6µs | ||
+ | : AD1CON3bits.ADCS = 63; | ||
+ | :: // Nombre de canaux utilisés pour le scan : ici NUM_CHS2SCAN = 1 | ||
+ | : AD1CON2bits.SMPI = (NUM_CHS2SCAN-1); | ||
+ | :: //AD1CSSH/AD1CSSL: A/D Input Scan Selection Register | ||
+ | :: //AD1CSSH = 0x0000; | ||
+ | : AD1CSSLbits.CSS0=1; | ||
+ | :: // Enable AN4 for channel scan | ||
+ | :: //AD1PCFGH/AD1PCFGL: Port Configuration Register | ||
+ | : AD1PCFGL=0xFFFF; | ||
+ | :: // AD1PCFGH=0xFFFF; | ||
+ | : AD1PCFGLbits.PCFG0 = 0; | ||
+ | :: // AN4 as Analog Input | ||
+ | : IFS0bits.AD1IF = 0; | ||
+ | :: // Clear the A/D interrupt flag bit | ||
+ | : IEC0bits.AD1IE = 1; | ||
+ | :: // Enable A/D interrupt | ||
+ | : AD1CON1bits.ADON = 0; | ||
+ | :: // Turn on the A/D converter |
Revision as of 21:37, 11 March 2014
Contents
Système de balisage infrarouge
Cette page présente mes travaux actuels sur la fabrication d'un système de balisage infrarouge pour mobile.
Le système contient les fonctions suivantes :
- Emission infrarouge de 4 balises autonomes,
- Réception infrarouge sur une tourelle,
- Contrôle d'un moteur pas à pas d'entrainement de la tourelle.
En plus de la fonction de triangulation associée au balisage, le système intègre en permanence deux entrées codeuses, assurant ainsi l'odométrie du mobile. Les données d'odométrie sont ensuite intégrées aux données de balisage en permanence par l'intermédiaire d'un filtre de Kalman.
Un troisième volet de ce projet est le calcul en permanence d'une "void area", basée sur un réseau de capteurs ultrason déployés sur le mobile.
Dans un second temps, un autre projet viendra compléter celui-ci avec la réalisation d'un système de contrôle commande des moteurs (en DC, stepper DC puis en BLDC) avec un calcul de trajectoire basé sur les splines de Catmull-Rom.
Localisation par balisage infrarouge
Le principe de balisage infrarouge consiste à utiliser des balises émettant un signal infrarouge que va détecter un plot central, déployé sur une structure mobile roulante par exemple. Le concept est développé dans le cadre de la coupe de France de robotique, et permet de disposer facilement d’une information de localisation sur la table de 3x2m. >>Table + balisage<<
Le but est d’obtenir la meilleur estimation de x et y afin d’avoir la position du robot sur la table, ainsi que son orientation. Le principe appliqué est celui de la triangulation, basée sur une mesure d’angle (il existe le même principe avec les distances, tout n’étant au final qu’une application des équations de trigonométrie). Le choix du balisage infrarouge est lié au faible coût de la mise en œuvre (une centaine d’euros tout compris) et à la relativement grande précision du système. Il sera couplé, dans la suite de ce document, à un dispositif d’odométrie et un dispositif de sonars permettant d’affiner la position courante du robot et de créer une « void area » autour du robot indiquant les zones accessibles ou non au robot. >>Table + odométrie<<
Microcontrôleur DsPIC
Cette section est dédiée à l'utilisation des microcontrôleurs DsPic de chez Microchip. Ces chips sont majoritairement utilisés dans le système présenté ici. Il est donc nécessaire de poser un certain nombre de bases sur leur utilisation, en particulier leur mise en oeuvre et les drivers disponibles.
Configuration générale
Les DsPic sont de petits microcontrôleurs 16 bits très puissants que l'on peut utiliser pour tout ou presque :
- Contrôle de moteur par PWM,
- Conversion analogique numérique 16 bits (ADC),
- Acquisition de signaux numériques (Input Capture)
- Communication CAN (natif), i2c (natif), UART (natif), SPI (natif), etc.
- Une foultitude de timers,
- etc.
Il existe plusieurs familles de DsPIC : 30F, 32, 33F, 33E. Seuls les 33F sont détaillés ici.
Dans une même famille, tous les microcontrôleurs utilisent les drivers de la même façon, avec le même code, sous réserve qu'ils disposent du driver. En effet, dans la famille des 33F il va exister pléthore de chips différents, la différence se situant au niveau du nombre de drivers, d'E/S, de timers, de place mémoire, etc.
Dans la suite, les explications seront apportées sur un DsPIC33FJ128MC802 ou un DsPIC33FJ64GP802, dont la principale différence est un PWM pour le premier.
La programmation peut se faire en C ou en assembleur. Les exemples proposés sont en C, je reviendrais par la suite sur la manière de les programmer.
Schéma de câblage
Tous les microcontrôleurs de la famille des DsPIC33FJ sont câblés pareils : >> Schéma de câblage chip <<
Le connecteur J1 est utilisé pour la programmation du DsPic, en utilisant un ICD2 ou un Pickit 3.
- !MCLR
- +Vcc
- GND
- PGEC1
- PGED1
Les ports suivants sont nécessairement câblés pour pouvoir utiliser le chip, conformément à la figure précédente :
- !MCLR : La patte sert à la fois à la programmation et à la mise en marche du Chip : !MCLR = 0/NC - Chip inactif, !MCLR = VDD : Chip actif.
- PGEDi/PGECi : broches de programmation, elles peuvent aussi avoir d'autres application lors de l'usage du chip. Il y a plusieurs mappages des PGEC/D possibles, j'utilise ici le premier.
- VSS/AVSS : ground, 0 logique. La broche "A-" est normalement la branche utilisée pour faire passer de la puissance dans le chip, mais en règle général il vaut mieux tout avoir sur la même source et utiliser ensuite des composant fait pour pour les aspects puissance.
- OSC1 / OSC2 : entrées du quartz. Voir le chapitre horloge pour le détail d'utilisation.
- VDD/AVDD : 3,3V (+/- 10%)
- VCAP : Cette entrée doit être reliée à la masse par un condo de 10µF, l'idéal étant un tantale polarisé (CMS ou non d'ailleurs). Sans ce condo, le chip ne marchera pas et ne pourra même pas être programmé.
Horloge
Les DsPIC peuvent être cadencés assez haut, mais ils utilisent pour cela une PLL interne (Phase Lock Loop). Le principe de la PLL est détaillé sur internet, nous ne verrons ici que l'application. Trois types d'horloges sont utilisées :
- Quartz,
- Oscillateur,
- Horloge interne.
De manière générale, il est déconseillé d'utiliser des horloges trop rapides. En effet, les signaux "carrés" sont plus mauvais à ces fréquences. Une bonne pratique est de dédier un quartz de fréquence raisonnable (8 ou 10 MHz) à chaque chip, et d'en augmenter la fréquence par une PLL.
Utilisation d'un quartz
Les quartz sont des cristaux passifs que le microcontrôleur utilise pour générer une horloge. Le quartz est relié aux broches OSC1 et OSC2 du microcontrôleur. Les quartz utilisables sont de deux types, en fonction de leur vitesse d'horloge :
- XT : quartz jusqu'à 10 MHz,
- HS : quartz de 10 MHz à 40 MHz.
Chaque broche OSC1 et OSC2 est également relié à la masse (GND), par l'intermédiaire d'un condo de 15 µF. A noter que ça marche aussi sans le condo, mais ils sont recommandés dans la doc du chip.
Dans : MPLAB : Configure\configuration bits...
- Oscillator mode : Primary oscillator (XT, HS, EC) w/ PLL
- Internal External switch over mode : Start up device with FRC, then automatically switch to bla bla bla...
- Primary oscillator source : HS Oscillator mode (pour cause de quartz utilisé à 10 MHz)
Nota : les quartz étant passifs, ils sont dédiés à un seul chip et unique chip, on ne peut pas utiliser un quartz pour plusieurs chips.
Utilisation d'un oscillateur
ADU
Utilisation de l'horloge interne
ADU
Configuration de l'horloge
Ci-dessous un bout de code permettant de paramétrer la PLL au démarrage du chip :
- void oscConfig(void){
- PLLFBD=30; // M=32
- CLKDIVbits.PLLPOST=0; // N1=2
- CLKDIVbits.PLLPRE=0; // N2=2
- OSCTUN=0; // Tune FRC oscillator, if FRC is used
- RCONbits.SWDTEN=0; // Disable Watch Dog Timer
- __builtin_write_OSCCONH(0x03); // Initiate Clock Switch to Primary Oscillator with PLL (NOSC=0b011)
- __builtin_write_OSCCONL(0x01); // Start clock switching
- while (OSCCONbits.COSC != 0b011); // Wait for Clock switch to occur
- while(OSCCONbits.LOCK!=1) {}; // Wait for PLL to lock
- }
Ce code est prévu pour un quartz de 10 MHz, permettant de passer la fréquence de cycle du microcontrôleur à 40 MHz (une opération toutes les 1 / [40.E6], soit 25 ns).
Configuration des ports d'entrées / sorties
La configuration des ports d’E/S est réalisée de base par les trois registres suivants :
- AD1PCFGL' : Ports analogiques, à positionner à [0xffff] pour les désactiver,
- _TRISBx / _TRISAx : Direction de la broche RBx / RAx :
- 1 : broche en entrée,
- 0 : broche en sortie.
- _RBx / _RAx : Etat de la broche :
- 1 : broche à VDD (+3,3V),
- 0 : broche à VSS (GND).
Nota : Lorsque l’on passe plusieurs broches à l’état logique 1 l’une à la suite de l’autre, notamment avec des très hautes fréquences, il est possible que le condensateur qui sert à modifier l’état de la broche ne puisse pas suivre et alimenter toutes les broches. Dans ce cas, il faut séparer les opérations de changement d’état de plusieurs cycles (au moins deux ou trois) pour permettre au condo de recharger.
En plus des manipulations standards, il existe deux autres opérations associées à l’utilisation des drivers : redirection des ports d’entrée ou de sortie : _RPxR (output) et RPINRx (input).
- _RPxR : les _RPxR sont des registres associés à **ADU**
- RPINRx : la plupart des drivers ont leurs entrées redirigeables vers l’une ou l’autre des broches RPx du chip. Pour chaque driver, il faut trouver le bon RPINRx et indiquer dans ce registre le numéro de la broche à laquelle associer l’entrée.
Pour chaque driver, les redirections de port seront précisées au cas par cas.
Les timers
Les timers sont probablement les fonctions les plus utiles d’un microcontrôleur. Ils permettent de réaliser des opérations avec une fréquence particulière, avec des actions spécifiques à chaque révolution du timer. Le principe est qu’un registre va être incrémenté régulièrement, proportionnellement à la fréquence Fcy, jusqu’à une certaine valeur. Lorsque cette valeur est atteinte, une interruption est déclenchée qui permet de réaliser l’action voulue à la révolution du timer.
Les DsPIC disposent de plus ou moins de timer selon les séries, celui utilisé ici dispose de 5 timers.
Certains timers sont utilisés par des fonctions (comme les timers 2 et 3 avec l’Input Capture, définit plus loin), ou peuvent être combinés pour former des timers 32 bits (de révolution très largement supérieure). Les applications présentées ici utiliseront plusieurs de ces fonctions, mais sans être exhaustif.
Principe
Les timers fonctionnent selon le principe ci-dessous : <<Schéma Timer à ajouter>>
Paramétrage du timer
Le code ci-dessous permet de paramétrer un timer pour avoir une interruption cadencée à la fréquence voulue :
- void init_timer1(void)
- {
- _T1IE=0; // interruption timer
- _T1IF=0; // flag d’interruption remis à zéro
- T1CON=0x0020;
- /* configuration du registre de controle :
- Le bit de poids fort <Bit_15> commande le démarrage du timer,
- Les bits <5-4> permettent de ralentir la vitesse du timer, en divisant la fréquence de mise à jour du timer par une valeur spécifique (ce que l’on appelle un prescaler. Ainsi, au lieu d’être incrémenté à chaque coup d’horloge (Fcy), le compteur du timer est incrémenté tous les 8, 64 ou 256 coups :
- <5-4> = 0 ; // A chaque coup d’horloge
- <5-4> = 1 ; // tous les 8 coups
- <5-4> = 2 ; // tous les 64 coups
- <5-4> = 3 ; // tous les 256 coups */
- PR1= <<valeur>>;
- // Lorsque le compteur du timer atteint cette valeur, une interruption est générée et le timer remis à 0
- T1CONbits.TON=1; // démarrage du timer
- }
Pour faciliter la manipulation du timer, on définit en général la donnée suivante :
- #define timer1 IEC0bits.T1IE
Avec 1 pour le timer 1, 2 pour le timer 2 et ainsi de suite. Cela permet au microcontrôleur de générer les interruptions, ce qu’il ne fait pas sinon.
Nota 1 : même si les interruptions sont désactivées, le timer fonctionne si T1CONbits.TON=1. Nota 2 : vérifier que le registre IEC0 contient bien le bit du timer associé. En particulier, pour les timer 4 et 5 il faut chercher sur le registre IEC1 :
- #define timer4 IEC1bits.T4IE
A titre informatif, le tableau ci-dessous donne quelques réglages de base pour générer des interruptions aux périodes indiquées, sur la base de réglage de la PLL et du quartz utilisé :
Config 1 | Config 2 | Config 3 | Config 4 | |
---|---|---|---|---|
Horloge |
10 MHz |
10 MHz |
10 MHz |
10 MHz |
M |
38 |
30 |
0 |
10 |
N1 |
0 |
0 |
0 |
0 |
N2 |
0 |
0 |
0 |
0 |
FCAN |
50 MHz |
40 MHz |
5 MHz |
15 MHz |
Période |
20 ns |
25 ns |
200 ns |
66 ns |
Interruption timer
Une interruption timer est définie dans la routine suivante :
- void __attribute__((interrupt, no_auto_psv)) _T1Interrupt (void)
- {
- TMR1=0; // remise à 0 du compteur
- Ajouter le code ici
- IFS0bits.T1IF=0; // remise à 0 du drapeau d’interruption du timer
- }
Nota 1 : le code ne doit pas être trop long, sinon son exécution peut masquer la survenue d’autres interruptions (voir priorité des interruptions), Nota 2 : TMR4 et TMR5 sont sur IFS1.
Cas d'utilisations des timers
Les timers sont utilisés dans les applications qui suivent dans plusieurs cas :
- Génération de la commande d’un servomoteur (pulse d’une milliseconde sur une période de 20ms),
- Génération d’un signal pour LED infrarouge conforme protocole IRDa,
- Commande d’un moteur pas à pas avec une carte de commande,
- Etc.
Ces différents cas seront détaillés dans la description complète des fonctions, au niveau des applications elles-mêmes.
Input Capture et interruptions externes
Il existe deux fonctions assez similaires qui réagissent à un changement d’état d’une entrée du microcontrôleur en générant une interruption. Ces fonctions sont :
- Input Capture, permettant via un couplage aux timer de mesurer précisément le temps écoulé entre deux changements d’état,
- Interruptions externes : principalement utilisées pour du comptage d’occurrence de changement d’état.
Paramétrage de l'Input Capture
La fonction d’Input Capture (IC) est très utile pour la mesure précise d’une période entre deux changements d’états d’une entrée, sur le même front ou sur des fronts différents. Il est également possible d’utiliser, comme pour les timers, un prescaler générant une interruption au bout de la 4eme, 16eme, etc. survenue du changement d’état attendu.
- void init_input_capture(void)
- {
- IC1CON = 0x0001;
- IC7CON = 0x0001;
- RPINR7 = 0x000B;
- RPINR10 = 0x000A;
- _IC1IF = 0;
- _IC1IE = 1;
- _IC7IF = 0;
- _IC7IE = 1;
- }
Le registre ICxCON permet le paramétrage du module d’input capture. Dans notre cas, seuls les paramètres suivants sont intéressants :
- Bit 7 – ICTMR : lorsque l’interruption survient, le contenu d’un timer est recopié dans un registre associé à l’input capture. Si ICTMR = 1, c’est le contenu du timer 2 (ie TMR2) qui est recopié dans le registre, sinon c’est le contenu du timer 3 (ie TMR3),
- Bit <6 – 5> - ICI<1:0> : décale la génération de l’interruption de 1 à 4 survenue de l’évènement scruté. Par exemple, si ce paramètre vaut 3, et que l’IC est programmée pour détecter tous les fronts montants sur une broche, l’interruption sera générée au troisième front montant et non à chaque fois,
- Bit <2 - 0> - ICM<2:0> : précise l’évènement scruté. Un paramètre à 0 désactive l’IC. Un paramètre à 1 génèrera une interruption à chaque front montant ou descendant. Dans ce mode le décalage de l’ICI<1:0> ne fonctionne pas. Un paramètre à 2 ou plus entrainera une interruption, après décalage de ICI<1:0>, sur chaque front montant, chaque front descendant, tous les 4, 16 front montants, etc. se reporter au datasheet du composant.
Dans le paramétrage de l’exemple, l’IC va générer une interruption à chaque front montant ou descendant.
Il faut ensuite associer à chaque IC une broche, et on utilise pour ça le registre RPINR vu précédemment. Dans l’exemple, le RPINRx de l’IC1 est RPINR7 octet de poids faible, auquel on a associé la valeur 11 (0xB). Ainsi, l’entrée de l’IC1 est la broche RP11 (ie RB11).
Enfin, de la même manière que pour les timers, il est nécessaire d’activer les interruptions sur l’IC :
- _IC1IE = 1;
Après s’être assuré au préalable que l’interruption n’est pas en cours, sans quoi le code ne sera jamais appelé :
- _IC1IF = 0;
Interruption Input Capture
Une interruption d’input capture est définie dans la routine suivante :
- void __attribute__((interrupt, no_auto_psv)) _IC1Interrupt(void)
- {
- Value = IC1BUF;
- // Ajouter TMR3 = 0 ou TMR2 = 0 si il est nécessaire de recommencer à compter depuis 0 (et ainsi éviter les rollovers)
- _IC1IF = 0;
- Value = IC1BUF;
- }
La valeur du timer 2 ou 3 (selon réglage) est copiée dans le registre ICxBUF, mais pas remise à 0. Si besoin, il est possible de la remettre à 0 en utilisant directement les registres de comptage TMRx. Noter qu’il est possible, pour by-passer une limitation du chip, d’utiliser le TMR d’un autre timer, sous réserve que celui-ci soit remis à 0 juste après et qu’aucun autre soft ne s’en serve.
Paramétrage de l'interruption externe
Les interruptions externes sont en réalité une extension des fonctions d’entrée / sortie, mais avec la génération d’une interruption à chaque front montant. Si la fonction ressemble beaucoup à l’IC, elle est cependant limitée sans possibilité de prescaler. A noter enfin qu’il ne vaut mieux pas utiliser l’INT0 qui est très haute dans la liste des priorité d’interruption, et qui peut donc rapidement poser problème pour l’exécution du code.
- void init_interrupts(void)
- {
- RPINR0 = 0x0900; // RPINR0 => octet de poids fort pour le choix de la broche associée à l’interruption 1 (INT1), donc ici sur la broche RP9 (RB9)
- _INT1EP = 0;
- _INT1IF = 0; // vérification que l’interruption n’est pas en cours
- _INT1IE = 1; // Activation de l’interruption
- }
Le bit _INT1EP contrôle le sens de génération de l’interruption :
- 1 – interruption sur le front descendant,
- 0 – interruption sur le front montant.
Interruption externe
Une interruption externe est définie dans la routine suivante :
- void __attribute__((interrupt,no_auto_psv))_INT1Interrupt(void)
- {
- code
- _INT1IF = 0;
- }
Les communications
Les DsPIC33FJ possèdent plusieurs modes de communication gérés automatiquement par le chip, qu’il ne reste qu’à paramétrer :
- I2C,
- UART,
- ECAN.
Dans le projet décrit par la suite, seule I2C et ECAN seront utilisés, l’I2C en maitre et l’ECAN en émission / réception. Les drivers de communication sont définis dans des fichiers indépendants :
- ecan.c / ecan.h, disponibles sur le site : ****
- i2c_Func.c / i2c.h, disponibles sur le site : ****
Les fichiers ne sont pas disponibles ici car ils appartiennent à leurs créateurs (qui n’est pas moi, simple utilisateur), et donc restent disponibles sous leur contrôle uniquement.
Utilisation de l'I2C
Dans les applications du projet, le chip est utilisé comme maitre I2C pour lire des télémètres à ultrason.
Il est possible d’utiliser l’i2C pour la communication globale avec le chip, par exemple pour la transmission d’info avec le blackfin. Cependant, il faut penser que l’I2C n’est pas fait pour la communication à distance (de l’ordre du mètre et plus), en particulier dans un environnement CEM sévère (par exemple avec de puissants moteurs brushless à proximité).
C’est pourquoi dans les applications du projet, les communications internes seront réalisées en ECAN (plus robuste), et l’I2C limité à l’interface avec les composants qui ne comprennent que ça (typiquement les sonars à ultrason).
Câblage de l'I2C
Le principe de l’i2c est qu’il est possible d’utiliser des composants sur plusieurs niveaux de tension, par exemple entre les DsPIC33F (en 3,3V) et les capteurs à ultrason (en 5V).
Pour cela, on utilise sur chaque ligne des résistances de pull-up, portant la tension de la ligne à la tension nécessaire pour que tout le monde comprenne (c’est un bus, donc il peut y avoir plusieurs composants). Tous les sda (serial data) sont à relier ensemble, tous les scl (serial clock) aussi.
<<Ajouter figure>>
Paramétrage de l'I2C
La fonction I2C est initialisée facilement (en mode maitre) à partir de la fonction donnée dans le fichier i2c_Func.c : InitI2C().
Cette fonction peut cependant être (légèrement) modifiée :
- I2C1BRG : ce registre permet de modifier la fréquence de communication de l’I2C. L’I2C fonctionne principalement en 140 KHz et 400 KHz. A noter, puisque c’est le maître qui donne l’horloge, il est normalement possible de mettre la valeur que l’on souhaite dans la limite des 400 KHz max.
Il n’y a pas de redirection (à ma connaissance) sur les broches de l’I2C, il faut nécessairement utiliser les broches RB8 / RB9 ou RB5 / RB6 (I2C complémentaire, utilisable en modifiant les bits de configuration (Configure\ Configuration Bits… \ ALTI2C (Alternate I2C Pins)).
Interruption sur l'I2C
En mode maitre, c’est le chip qui décide d’initier la communication au moment opportun. Les esclaves peuvent également initier la communication, mais cette fonction ne sera pas étudiée ici.
Il existe deux fonctions pour la communication I2C :
- Write : écrit un certain nombre de données dans le chip à l’adresse indiquée. La définition des données écrites pour les deux composants doit faire l’objet d’une ICD .
- Read : Un premier cycle d’écriture va positionner l’esclave en lecture (en général, l’envoi de l’adresse du composant esclave « +1 », par exemple 0xE2 : adresse de l’esclave en écriture, 0xE3 : adresse de l’esclave en lecture), puis un redémarrage permet à l’esclave de transmettre ses données.
La fonction standard d’écriture du fichier i2c_Func.c est utilisable en l’état (rien trouvé à redire).
On l’appelle ainsi :
- LDByteWriteI2C(0xE2, 0, 0x51);
Avec :
- 0xE2 : adresse de l’esclave,
- 0 : adresse de démarrage pour l’écriture des données,
- 0x51 : la (les) valeur(s) à écrire.
Pour la fonction de lecture, j’ai modifié légèrement la fonction donnée dans le fichier.
On l’appelle ainsi :
- LDByteReadI2C(0xE2, 0x02, i2c_buffer_out_1, 4);
Avec :
- 0xE2 : adresse de l’esclave,
- 0 x02: adresse de démarrage de la lecture des données,
- I2c_buffer_out_1 : une structure de type [unsigned char i2c_buffer_out_1[20]] permettant de récupérer les données en lecture,
- 4 : le nombre de bits à lire.
La fonction est modifiée comme suit :
- unsigned int LDByteReadI2C(unsigned char ControlByte, unsigned char Address, unsigned char *Data, unsigned char Length)
- {
- IdleI2C();
- //wait for bus Idle
- StartI2C();
- //Generate Start Condition
- WriteI2C(ControlByte);
- //Write Control Byte
- IdleI2C();
- //wait for bus Idle
- WriteI2C(Address);
- //Write start address
- IdleI2C();
- //wait for bus Idle
- RestartI2C();
- //Generate restart condition
- WriteI2C(ControlByte | 0x01);
- //Write control byte for read
- IdleI2C();
- //wait for bus Idle
- getsI2C(Data, Length);
- //read Length number of bytes
- NotAckI2C();
- //Send Not Ack
- StopI2C();
- //Generate Stop
- IdleI2C();
}
De plus, avant de démarrer une communication, il faut forcer les esclaves à revenir en idle mode. Ajouter les deux lignes suivantes dans le Main :
- StartI2C();
- StopI2C();
En règle générale ça marche…
Utilisation du CAN
Le bus CAN est plus robuste à la CEM que l’I2C, il est donc plus judicieux de l’utiliser au lieu de l’i2c pour toutes les communications sur lesquelles on a le choix.
Le protocole CAN est standardisé, le plus simple est de choisir des composants qui le possèdent en natif. Dans le projet présenté, les deux composants sont natifs CAN :
- Blackfin : le module noyau can.ko doit être inséré au système d’exploitation, il peut ensuite être utilisé (voir ***)
- DsPIC33F : il faut choisir dans la gamme des composants qui ont de l’ECAN en natif. C’est le cas notamment des composants 64MC802.
Avant toute chose, il y a deux choses à savoir sur le CAN indépendamment de sa programmation :
- Il est impératif d’utiliser un driver matériel indépendant (convertissant le can+/can- en CAN_H / CAN_L), par exemple des MCP2551 de chez microchip,
- Il est impératif d’avoir au moins deux composants lorsque l’on utilise un réseau CAN. En effet, un seul composant a besoin qu’on lui réponde pour compléter son cycle de transmission de données.
Sans ces deux précautions, il est impossible de faire marcher un module CAN.
Câblage de l'ECAN
Comme expliqué précédemment, il n’est pas possible de câbler deux composants par leurs can+ / can- directement. Il faut les câbler par leurs CAN_H / CAN_L après ajout d’un driver matériel et surtout d’un composant en face. Le schéma ci-dessous précise le montage, tous les CAN_H sont à relier ensemble, les CAN_L ensemble également.
<<Ajouter l'image>>
Attention, le MCP2551 se plug en 5V uniquement.
Paramétrage du module CAN
Dans un réseau CAN, les composants échangent des données sous la forme de trames de 8 octets. Le principe est sensiblement différent de l’i2c, dans lequel on adresse un composant puis une adresse de données dans le composant, avant de lire ou d’écrire à cette adresse. Dans le CAN, on adresse des données.
Le principe est que chaque « type » d’information a sa propre adresse. En effet, un composant va transmettre une information avec une adresse indiquant à la fois le type et l’origine de l’information.
Par exemple, un détecteur va transmettre régulièrement ses données sur le réseau CAN avec une référence (le terme est plus explicite qu’adresse) propre à la fois au composant et au type de données qu’il transmet. Ensuite, tous les composants du réseau qui doivent lire ces données sont paramétrées pour filtrer les données échangées sur le réseau et lire précisément celle-ci.
Le réseau va traiter les cas de collision automatiquement (par un jeu magique de comparaison des bits dans les références, on va dire que c’est sans objet dans l’application courante).
Comme pour l’i2c, il est possible d’utiliser le code tout fait développé par microchip et contenu dans les fichiers ***. L’initialisation se fait par les fonctions :
- initECAN();
- initDMAECAN();
Il faut nécessairement utiliser la DMA dans l’exemple. On peut faire sans mais je n’ai pas creusé plus loin.
Pour l’initialisation de l’ECAN (ECAN pour extended CAN, possibilité d’utiliser des références sur 29 bits au lieu de 11 pour avoir plus de messages) il faut paramétrer les filtres et masques qui permettent de limiter les données lues. Dans l’exemple, je n’utilise que les adresses standards (sur 11 bits).
Les lignes à modifier sont :
- C1RXM0SID=CAN_FILTERMASK2REG_SID(0x15E) : On applique un masque permettant de lire tous les bits de 350 à 360 (0x15E *** ADU).
- C1RXF0SID=CAN_FILTERMASK2REG_SID(0x0x15E) : adu.
De même, il est possible de modifier la vitesse de transmission via la valeur BRP_VAL définit dans le ecan.h :
- #define BRP_VAL ((FCAN/(2*NTQ*BITRATE))-1)
Avec :
- #define FCAN 40000000
- // Fréquence de cycle, Fcy en réalité.
- #define BITRATE 125000
- // vitesse de communication
- #define NTQ 20
- // 20 Time Quanta in a Bit Time (ne pas changer)
C’est le paramètre BITRATE qui modifie la vitesse de communication sur le réseau CAN. Hélas, la valeur de 125 kHz n’est pas choisie au hasard, elle a été codée en dur dans le module linux can.ko. Donc il faut nécessairement utiliser cette valeur.
Les ports de communication utilisés sont les broches RB2 et RB3. Pour l’association de ces broches au driver CAN, on utilise deux registres de redirection :
- _TRISB2 = 0;
- // Broche RB2 en sortie
- _RP2R = 0x10;
- // C1TX = RB2, allocation de la broche RB2 à la fonction TxCAN
- _TRISB3 = 1;
- // Broche RB3 en entrée
- RPINR26 = 0x03;
- // C1RX = RB3, allocation de la broche RB3 à la fonction RxCAN
Interruption sur CAN
La fonction suivante est directement issue de l’application note *** :
- void __attribute__((interrupt,no_auto_psv))_C1Interrupt(void)
- {
- /* check to see if the interrupt is caused by receive */
- if(C1INTFbits.RBIF)
- {
- /* check to see if buffer 1 is full */
- if(C1RXFUL1bits.RXFUL1)
- {
- /* set the buffer full flag and the buffer received flag */
- canRxMessage.buffer_status=CAN_BUF_FULL;
- canRxMessage.buffer=1;
- }
- /* check to see if buffer 2 is full */
- else if(C1RXFUL1bits.RXFUL2)
- {
- /* set the buffer full flag and the buffer received flag */
- canRxMessage.buffer_status=CAN_BUF_FULL;
- canRxMessage.buffer=2;
- }
- /* check to see if buffer 3 is full */
- else if(C1RXFUL1bits.RXFUL3)
- {
- /* set the buffer full flag and the buffer received flag */
- canRxMessage.buffer_status=CAN_BUF_FULL;
- canRxMessage.buffer=3;
- }
- else;
- /* clear flag */
- C1INTFbits.RBIF = 0;
- }
- else if(C1INTFbits.TBIF)
- {
- /* clear flag */
- C1INTFbits.TBIF = 0;
- }
- else if(C1INTFbits.ERRIF)
- {
- C1INTFbits.ERRIF = 0;
- C1TR01CONbits.TXREQ0=0;
- }
- /* clear interrupt flag */
- IFS2bits.C1IF=0;
- }
La routine d’interruption est composée de trois parties :
- La première [C1INTFbits.RBIF] est liée à une interruption suite à la réception de données. Dans ce cas, l’un des trois buffers de réception est rempli et le flag de réception levé [canRxMessage.buffer_status > 0]. On récupère les données via la fonction rxECAN(&canRxMessage) dans le corps de la fonction main.
- La seconde [C1INTFbits.TBIF] est liée à la transmission de données. L’interruption est levée dès lors qu’une transmission c’est bien passé. Ne sert à rien dans l’application, mais y ajouter une LED qui clignote permet de savoir rapidement que le réseau CAN est opérationnel.
- La dernière n’est pas active par défaut, elle permet le traitement des erreurs [C1INTFbits.ERRIF].
Pour activer la génération des interruptions, il faut ajouter les lignes suivantes dans le corps de la fonction main :
- /* Enable ECAN1 Interrupt */
- IEC2bits.C1IE=1;
- /* enable Transmit interrupt */
- C1INTEbits.TBIE=1;
- /* Enable Receive interrupt */
- C1INTEbits.RBIE=1;
- /* Activer les interruptions sur erreur */
- C1INTEbits.ERRIE = 1;
La récupération des données à traiter se fait par la fonction :
- rxECAN(&canRxMessage);
La structure canRxMessage est également définie dans l’application note ***, reprise ci-dessous :
- /* message structure in RAM */
- typedef struct{
- /* keep track of the buffer status */
- unsigned char buffer_status;
- /* RTR message or data message */
- unsigned char message_type;
- /* frame type extended or standard */
- unsigned char frame_type;
- /* buffer being used to send and receive messages */
- unsigned char buffer;
- /* 29 bit id max of 0x1FFF FFFF
- * 11 bit id max of 0x7FF */
- unsigned long id;
- unsigned char data[8];
- unsigned char data_length;
- }mID;
La création de la structure est réalisée comme suit :
- mID canTxMessage;
- mID canRxMessage;
Avec une structure pour la transmission de message et l’autre pour la réception.
Pour la transmission, il faut utiliser la fonction suivante :
- sendECAN(&canTxMessage);
La structure canTxMessage est instanciée directement dans le code.
Enfin, les deux paramètres message_type et frame_type sont initialisés avec les constantes suivantes dans l’exemple :
- canTxMessage.message_type=CAN_MSG_DATA;
- // Le message est un message de données simple
- canTxMessage.frame_type=CAN_FRAME_STD;
- // L’ID du message est standard, sur 11 bits.
Les signaux analogiques
Les microcontrôleurs sont des composants logiques, c’est-à-dire que toutes les données qu’ils traitent sont des données logiques (« 0 » / « 1 ») dont le niveau électrique dépendant de la technologie (0/5V ou 0/3.3V). Il n’est donc, à priori, pas possible de commander un équipement avec un signal analogique variant entre 0 et 5V par exemple, ou de disposer d’une entrée codant sont information sur son niveau électrique.
Pour palier à cela, il existe deux fonctions complémentaires :
- ADC : Analogic to Digital Converter, ou convertisseur analogique / numérique. Le fonctionnement détaillé d’un ADC ne sera pas abordé ici, seule sa mise en œuvre sera traitée.
- PWM : Pulse Width Modulation, ou modulation par amplitude d’un signal carré. De même, seule la mise en œuvre avec un Chip sera abordée ici.
Convertisseurs Analogiques / Numériques
Le module ADC va convertir un signal analogique, de niveau 0 à 3.3V ou 5V, en une donnée numérique de type flottant ou entier, signé ou non (AD1CON1\FORM<1:0>). Le principe est de réaliser un échantillonnage du signal à une fréquence plus ou moins haute, puis de convertir ce signal de manière régulière ou évènementielle (AD1CON1\SSRC<2:0>).
Ce module utilisera obligatoirement les PIN du chip ayant une capacité de conversion analogique en numérique, à savoir sur le GP/MC802 les ports A0-1, B0-3 et B12-15. Il est en outre possible de choisir les références, positives et négatives, utilisées pour l’échantillonnage du signal (AD1CON2\VCFG<2:0>).
- // Format des données converties : 0 = Entier non signé
- AD1CON1bits.FORM = 0;
- // Source de l’horloge de conversion. J’utilise ici GP Timer 3 : à chaque échéance du timer, une conversion intervient
- AD1CON1bits.SSRC = 2;
- // Contrôle de l’échantillonnage : 1 => un nouvel échantillonnage démarre automatiquement après la dernière conversion
- AD1CON1bits.ASAM = 1;
- // Opération en mode 10 Bits. La donnée est convertie sur 10 Bits. Il est possible d’opérer sur 12 également
- AD1CON1bits.AD12B = 0;
- // Scan des entrées sélectionnées pour CH0+ lors de l’échantillonnage A
- AD1CON2bits.CSCNA = 1;
- // Conversion du canal CH0 uniquement
- AD1CON2bits.CHPS = 0;
- // Horloge de conversion dérivée de l’horloge système (réglable)
- AD1CON3bits.ADRC = 0;
- // Durée de conversion : (n + 1) fois le temps d’opération du chip Tcy, ici 63 => Tad = 0,025ns * (63+1) = 1,6µs
- AD1CON3bits.ADCS = 63;
- // Nombre de canaux utilisés pour le scan : ici NUM_CHS2SCAN = 1
- AD1CON2bits.SMPI = (NUM_CHS2SCAN-1);
- //AD1CSSH/AD1CSSL: A/D Input Scan Selection Register
- //AD1CSSH = 0x0000;
- AD1CSSLbits.CSS0=1;
- // Enable AN4 for channel scan
- //AD1PCFGH/AD1PCFGL: Port Configuration Register
- AD1PCFGL=0xFFFF;
- // AD1PCFGH=0xFFFF;
- AD1PCFGLbits.PCFG0 = 0;
- // AN4 as Analog Input
- IFS0bits.AD1IF = 0;
- // Clear the A/D interrupt flag bit
- IEC0bits.AD1IE = 1;
- // Enable A/D interrupt
- AD1CON1bits.ADON = 0;
- // Turn on the A/D converter