Table des matières

Accéléromètre et gyromètre I2C

1. Introduction

Ce document montre la mise en œuvre d'un accéléromètre/gyromètre à liaison série I2C, le MPU6050 (InvenSense). Il s'agit d'un circuit intégré comportant un accéléromètre trois axes et un gyromètre trois axes avec un convertisseur A/N 16 bits. Il possède aussi une unité de traitement du signal pour filtrer les signaux et pour faire des calculs de position et d'orientation (Digital Motion Processor). Les données sont transmises à un microcontrôleur par liaison série I2C. Les plages d'accélérations vont de 2g à 16g, celles des vitesses de rotation de 250 à 2000 degrés par seconde et la fréquence d'échantillonnage peut atteindre 8kHz. Un filtrage passe-bas est généralement appliqué avant de réduire la fréquence d'échantillonnage, ce qui garantit un signal exempt de repliement spectral.

Le MPU6050 est vendu soudé sur une platine de test par DFROBOT.

Nous allons voir comment programmer le MPU6050 depuis un Arduino (UNO, NANO ou MEGA) afin d'effectuer une acquisition échantillonnée des accélérations et des vitesses de rotation, avec une transmission des données à un ordinateur. Nous verrons aussi comment réaliser une platine avec une liaison radio Xbee.

L'accès au MPU6050 depuis l'arduino se fait avec la bibliothèque de fonctions I2Cdevlib/MPU6050. I2Clibdev est une collection d'interfaces entre divers microcontrôleurs et des périphériques I2C. Il est possible de télécharger toute la bibliothèque I2Clibdev. Il suffira de recopier le dossier i2cdevlib-master/Arduino/MPU6050 et le dossier i2cdevlib-master/Arduino/I2Cdev dans le dossier Library de l'IDE Arduino.

Il est important de bien comprendre ce qu'un accéléromètre mesure. Il mesure le champ de pesanteur dans son propre référentiel (référentiel du boitier de l'accéléromètre), plus précisément les composantes de ce champ sur ces trois axes. Les valeurs affichées sont en fait les opposées de ces composantes. Si l'accéléromètre est en mouvement dans le référentiel terrestre, les valeurs affichées comportent l'accélération de l'accéléromètre dans le référentiel terreste retranchée du champ de pesanteur dans ce même référentiel.

2. Programme Arduino

Il y a 4 calibres pour l'accélération (calibre 0 : +/-2g, calibre 1 : +/- 4g, calibre 2 : +/- 8g, calibre 3 : +/- 16g). Par exemple, le calibre 2g donnera la valeur -0x7FFF pour une accélération -2g, 0x7FFF pour une accélération +2g et 0 pour une accélération nulle (en principe car un étalonnage et un réglage du zéro seront nécessaires). Le calibre de l'accéléromètre se configure avec la fonction setFullScaleAccelRange.

Il y a 4 calibres pour le gyromètre (calibre 0 : +/- 250 deg/s, calibre 1 : +/- 500 deg/s, calibre 2 : +/- 1000 deg/s, calibre 3 : +/- 2000 deg/s). Le calibre du gyromètre se configure avec la fonction setFullScaleGyroRange.

Le filtre passe-bas numérique intégré dans le MPU6050 peut être configuré avec différentes bandes passantes :

         |   ACCELEROMETER    |           GYROSCOPE
 DLPF_CFG | Bandwidth | Delay  | Bandwidth | Delay  | Sample Rate
 ---------+-----------+--------+-----------+--------+-------------
 0        | 260Hz     | 0ms    | 256Hz     | 0.98ms | 8kHz
 1        | 184Hz     | 2.0ms  | 188Hz     | 1.9ms  | 1kHz
 2        | 94Hz      | 3.0ms  | 98Hz      | 2.8ms  | 1kHz
 3        | 44Hz      | 4.9ms  | 42Hz      | 4.8ms  | 1kHz
 4        | 21Hz      | 8.5ms  | 20Hz      | 8.3ms  | 1kHz
 5        | 10Hz      | 13.8ms | 10Hz      | 13.4ms | 1kHz
 6        | 5Hz       | 19.0ms | 5Hz       | 18.6ms | 1kHz  		    
    		    

Si l'on souhaite par exemple stocker et traiter les données à une fréquence de 200Hz, on aura intérêt à échantillonner à 1000Hz et à filtrer avec une bande passante de 94Hz, de manière à éviter le repliement des fréquences supérieures à 100Hz. Le prix à payer pour ce filtrage est le léger retard du signal numérique par rapport au signal analogique. Pour 94Hz, ce retard est de 3,0ms. Si l'on souhaite synchroniser ces données avec des images vidéo, ce retard est acceptable pour une cadence d'image jusqu'à 120 img/s. Le filtre passe-bas se configure avec la fonction setDLPFMode.

La fréquence d'échantillonnage de sortie (après filtrage) est obtenue par division de la fréquence indiquée dans le tableau ci-dessus. SMPLRTDIV est un nombre entier 8 bits (de 0 à 255). La fréquence d'échantillonnage est :

fe=f01+SMPLRTDIV(1)

f0 est la fréquence d'échantillonnage de numérisation (avant filtrage), soit f0=8kHz si DLPF_CFG=0 et f0=1kHz si DLPF_CFG=1 à 6. Par exemple pour DLPF_CGF=2 et SMPLRTDIV=3, la fréquence d'échantillonnage de numérisation est 1000Hz, celle de sortie est 250Hz et la fréquence de coupure du filtre est 94Hz. En principe, la fréquence de sortie doit être égale au moins à deux fois la fréquence de coupure du filtre (condition de Nyquist-Shannon).

Le MPU6050 comporte une sortie INT qui passe au niveau 1 lorsqu'un jeu de données (accélérations et vitesses de rotation) est disponible puis revient au niveau bas lorsque ces données sont lues. Cette sortie est utilisée pour déclencher une interruption matérielle sur le microcontrôleur.

Les accélérations et les vitesses angulaires sont stockées dans un tampon comportant BUFSIZE entiers 16 bits (signés). Cette taille doit être divisible par 6 puisqu'il contient 6 composantes.

Les données sont échangées avec le programme Arduino au moyen du protocole écrit dans Échanges de données avec un Arduino. Ces données sont :

Les accélérations et vitesses angulaires transmises au PC sont sous forme brute (nombres entiers 16 bits). On fera la conversion en grandeurs réelles et l'étalonnage dans le script Python.

MPU6050.ino
#include "Arduino.h"
#include "Wire.h"
#include "I2Cdev.h"
#include "MPU6050.h"
// Arduino nano : A4=SDA, A5=SCL, D2=INT
#define GET_DATA 10
#define SET_DATA 11
#define START 12
#define STOP 13
#define BUFSIZE 180 // doit être divisible par 6
MPU6050 mpu;
int16_t ax, ay, az;
int16_t buffer[2][BUFSIZE];
uint16_t indice_buffer;
uint8_t nbuf;
uint8_t data_ready;
uint8_t acquisition;
uint8_t gyro;
uint8_t mpuIntStatus;
uint8_t accel_range=3;
uint8_t gyro_range=3;
uint8_t rate_div=9;
uint8_t dlpf_mode=4;

// transmission des données
#define DATA_0_SIZE BUFSIZE*2 // buffer
#define DATA_1_SIZE 1 // accel_range
#define DATA_2_SIZE 1 // gyro_range
#define DATA_3_SIZE 1 // rate_div
#define DATA_4_SIZE 1 // dlpf_mode
bool data_0_ready = false;
bool data_0_request = false;
uint8_t data_1[DATA_1_SIZE];
uint8_t data_2[DATA_2_SIZE];
uint8_t data_3[DATA_3_SIZE];
uint8_t data_4[DATA_1_SIZE];

                   

La fonction suivante est appelée lorsque la sortie INT passe au niveau haut, par interruption matérielle.

void data_ready_interrupt() {
  data_ready = 1;
}
                   

La fonction suivante est appelée lorsque le PC demande une donnée, ici le contenu du tampon (data 0):

void get_data() {
  char n;
  while (Serial.available()<1) {};
  n = Serial.read();
  if (n==0) data_0_request = true;
}   
                   

La fonction suivante envoie au PC le contenu du tampon. Il s'agit en fait d'un double tampon : un des deux tampons est remplis pendant que l'autre est disponible pour la transmission. La transmission se fait à deux conditions : le PC doit en avoir fait la demande et un nouveau tampon doit avoir été rempli depuis la dernière demande.

void send_data() {
  if ((data_0_ready)&&(data_0_request)) {
      data_0_ready = false;
      data_0_request = false;
      uint8_t nb;
      if (nbuf==1) nb=0; else nb=1;
      Serial.write((uint8_t *)(buffer[nb]),DATA_0_SIZE);
  }
}
                    

La fonction suivante permet de recevoir les données envoyées par le PC. Il s'agit ici de configurer l'accéléromètre et le gyromètre.

void set_data() {
  char n;
  while (Serial.available()<1) {};
  n = Serial.read();
  
  if (n==1) {
    while (Serial.available()<DATA_1_SIZE) {};
    Serial.readBytes(data_1,DATA_1_SIZE);
    memcpy(&accel_range,data_1,DATA_1_SIZE);
  }
  else if (n==2) {
    while (Serial.available()<DATA_2_SIZE) {};
    Serial.readBytes(data_2,DATA_2_SIZE);
    memcpy(&gyro_range,data_2,DATA_2_SIZE);
  }
  else if (n==3) {
    while (Serial.available()<DATA_2_SIZE) {};
    Serial.readBytes(data_2,DATA_2_SIZE);
    memcpy(&rate_div,data_2,DATA_2_SIZE);
  }
  else if (n==4) {
    while (Serial.available()<DATA_2_SIZE) {};
    Serial.readBytes(data_2,DATA_2_SIZE);
    memcpy(&dlpf_mode,data_2,DATA_2_SIZE);
  }
}
                    

La fonction suivante configure et démarre l'accéléromètre et le gyromètre. Ce dernier n'est utilisé que si gyro_range est inférieur à 4.

void start() {
  Serial.flush();
  if (gyro_range<4) {gyro = 1;} else gyro = 0;
    mpu.initialize();
    mpu.setFullScaleAccelRange(accel_range);
    if (gyro) mpu.setFullScaleGyroRange(gyro_range);
    mpu.setDLPFMode(dlpf_mode);
    mpu.setRate(rate_div);
    acquisition = 1;
    indice_buffer = 0;
    nbuf = 0;
    data_ready = 0;
    mpu.setIntDataReadyEnabled(true);
    mpuIntStatus = mpu.getIntStatus();
}
                     

La fonction suivante stoppe l'acquisition (mais le MPU6050 continu de fonctionner, ce qui est sans importance).

void stop() {
  acquisition = 0;
} 
                     

La fonction lit le caractère reçu sur le port série et déclenche l'action correspondante :

void read_serial() {
   char com;
   if (Serial.available()>0) {
        com = Serial.read();
        if (com==GET_DATA) get_data();
        else if (com==SET_DATA) set_data();
        else if (com==START) start();
        else if (com==STOP) stop();
   }
}
                     

Voici la fonction de démarrage du programme :

void setup() {
  Wire.begin();
  Serial.begin(19200);
  while(!Serial);
  attachInterrupt(digitalPinToInterrupt(2),data_ready_interrupt,RISING);
  mpuIntStatus = mpu.getIntStatus();
  
}
                     

La vitesse de transmission est volontairement basse car nous utiliserons une transmission radio par XBee. 19200 bits par seconde correpond à 1200 nombres de 16 bits par seconde, soit 200 fois les 3 accélérations et les 3 vitesses angulaires par secondes. On pourra donc sans problème travailler à une fréquence d'échantillonnage de 100 Hz, voire le double si on se contente des accélérations.

La fonction loop appelle les fonctions de communication par le port série puis, si des données en provenance du MPU6050 sont disponibles, récupère ces données et les place dans le tampon. Lorsque le tampon est plein, on signal que son contenu peut être transmis au PC (s'il en a fait la demande).

void loop() {
  read_serial();
  send_data();
  if (data_ready&&acquisition) {
    data_ready = 0;
    delayMicroseconds(100);
    if (gyro) {
          mpu.getMotion6(&buffer[nbuf][indice_buffer],&buffer[nbuf][indice_buffer+1],&buffer[nbuf][indice_buffer+2],&buffer[nbuf][indice_buffer+3],&buffer[nbuf][indice_buffer+4],&buffer[nbuf][indice_buffer+5]);
          indice_buffer += 6;
    }
    else {
          mpu.getAcceleration(&buffer[nbuf][indice_buffer],&buffer[nbuf][indice_buffer+1],&buffer[nbuf][indice_buffer+2]);
          indice_buffer += 3;
    }
    if (indice_buffer == BUFSIZE) {
            indice_buffer = 0;
            if (nbuf==1) nbuf=0; else nbuf=1;
            data_0_ready = true;
    }
  }

}
                      

3. Programme Python

La communication par port série est gérée par la classe Arduino.py définie dans le fichier Arduino.py.

La classe MPU6050 décrite ci-dessous permet de piloter l'accéléromètre/gyromètre.

L'unique argument du constructeur définit le port COM :

MPU6050.py
class MPU6050():
    def __init__(self,com):
        self.START = 12
        self.STOP = 13
        self.TAILLE_BLOC_INT16 = 180
        self.TAILLE_BLOC_ACCEL = int(self.TAILLE_BLOC_INT16/3)
        self.TAILLE_BLOC_ACCEL_GYRO = int(self.TAILLE_BLOC_INT16/6)
        self.ACCEL_FS_2 = 0
        self.ACCEL_FS_4 = 1
        self.ACCEL_FS_8 = 2
        self.ACCEL_FS_16 = 3
        self.accel_sensitivity = [16384.0,8192.0,4096.0,2048.0]
        self.GYRO_FS_250 = 0
        self.GYRO_FS_500 = 1
        self.GYRO_FS_1000 = 2
        self.GYRO_FS_2000 = 3
        self.gyro_sensitivity = [131,65.5,32.8,16.4]
        self.GYRO_NONE = 4
        self.DLPF_BW_260 = 0
        self.DLPF_BW_184 = 1
        self.DLPF_BW_94 = 2
        self.DLPF_BW_44 = 3
        self.DLPF_BW_21 = 4
        self.DLPF_BW_10 = 5
        self.DLPF_BW_5 = 6
        self.gyro = 1
        self.accel_range =3
        self.gyro_range = 3
        self.rate_div = 9
        self.dlpf_mode = 4
        self.axgp = self.accel_sensitivity[self.accel_range]
        self.axgm = -self.axgp
        self.aygp = self.axgp
        self.aygm = -self.aygp
        self.azgp = self.axgp
        self.azgm = -self.azgp
        self.set_accel_trans()
        self.arduino = Arduino(com,[self.TAILLE_BLOC_INT16*2,1,1,1,1],baudrate=19200)

    def close(self):
        self.arduino.close()
            

La fonction suivante calcule les coefficients des transformations affines qui permettent de calculer les accélérations à partir des nombres 16 bits. Ces coefficients seront modifiés lorsqu'on fera l'étalonnage de l'accéléromètre. Notons que nous ne prévoyons pas d'étalonnage pour le gyromètre mais nous ferons tout de même un réglage du zéro (gyromètre immobile). Les coefficients d'étalonnage peuvent être sauvegardés dans un fichier et celui est utilisé s'il existe. Il y a un fichier pour chaque calibre de l'accéléromètre puisque l'étalonnage doit être fait pour chaque calibre.

    def set_accel_trans(self):
        filename = "calibaccel-%d.txt"%self.accel_range
        if os.path.isfile(filename):
            [self.alpha_ax,self.beta_ax,self.alpha_ay,self.beta_ay,self.alpha_az,self.beta_az] = np.loadtxt(filename)
        else:
            self.alpha_ax = 2/(self.axgp-self.axgm)
            self.beta_ax = 1-self.alpha_ax*self.axgp
            self.alpha_ay = 2/(self.aygp-self.aygm)
            self.beta_ay = 1-self.alpha_ay*self.aygp
            self.alpha_az = 2/(self.azgp-self.azgm)
            self.beta_az = 1-self.alpha_az*self.azgp        
            

La fonction suivante sauvegarde les coefficients d'étalonnage dans un fichier. Cette fonction doit être appelée explicitement. Si on veut refaire l'étalonnage, il faut effacer le fichier.

    def save_calib(self):
        filename = "calibaccel-%d.txt"%self.accel_range
        np.savetxt(filename,[self.alpha_ax,self.beta_ax,self.alpha_ay,self.beta_ay,self.alpha_az,self.beta_az])
            

La fonction suivante renvoie la fréquence d'échantillonnage des données renvoyées, qui dépend de la configuration du filtre et du diviseur de fréquence.

    def fechant(self):
        if self.dlpf_mode==self.DLPF_BW_260:
            fechant = 8000/(1+self.rate_div)
        else:
            fechant = 1000/(1+self.rate_div)
        return fechant

            

Les trois fonctions suivantes permettent de configurer respectivement le calibre de l'accéléromètre, celui du gyromètre, le diviseur de fréquence et le mode de filtrage :

    def set_accel_range(self,accel_range):
        self.arduino.write_int8(1,accel_range,signed=False)
        self.accel_range = accel_range
        self.axgp = self.accel_sensitivity[self.accel_range]
        self.axgm = -self.axgp
        self.aygp = self.axgp
        self.aygm = -self.aygp
        self.azgp = self.axgp
        self.azgm = -self.azgp
        self.set_accel_trans()

    def set_gyro_range(self,gyro_range):
        if gyro_range<4:
            self.gyro=1
        else:
            self.gyro=0
        self.arduino.write_int8(2,gyro_range,signed=False)
        self.gyro_range = gyro_range

    def set_rate_div(self,rate_div):
        self.arduino.write_int8(3,rate_div,signed=False)
        self.rate_div = rate_div

    def set_dlpf_mode(self,dlpf_mode):
        self.arduino.write_int8(4,dlpf_mode,signed=True)
        self.dlpf_mode = dlpf_mode
             

Les deux fonctions suivantes permettent de démarrer et de stopper l'acquisition :

    def start(self):
        self.arduino.ser.write((self.START).to_bytes(1,byteorder='big'))

    def stop(self):
        self.arduino.ser.write((self.STOP).to_bytes(1,byteorder='big'))
             

La fonction suivante renvoie les accélérations et les vitesses angulaires sous la forme d'un tableau pour chaque composante :

    def get_accel_gyro(self):
        data = self.arduino.read_int16_array(0,signed=True)
        if (self.gyro):
            ax = self.alpha_ax*np.array(data[0::6],dtype=np.double)+self.beta_ax
            ay = self.alpha_ay*np.array(data[1::6],dtype=np.double)+self.beta_ay
            az = self.alpha_az*np.array(data[2::6],dtype=np.double)+self.beta_az
            rx = (np.array(data[3::6],dtype=np.double)-self.rx_zero)/self.gyro_sensitivity[self.accel_range]
            ry = (np.array(data[4::6],dtype=np.double)-self.ry_zero)/self.gyro_sensitivity[self.accel_range]
            rz = (np.array(data[5::6],dtype=np.double)-self.rz_zero)/self.gyro_sensitivity[self.accel_range]
            return ax,ay,az,rx,ry,rz
        else:
            ax = self.alpha_ax*np.array(data[0::3],dtype=np.double)+self.beta_ax
            ay = self.alpha_ay*np.array(data[1::3],dtype=np.double)+self.beta_ay
            az = self.alpha_az*np.array(data[2::3],dtype=np.double)+self.beta_az
            return ax,ay,az       
             

La fonction suivante renvoie les accélérations et les vitesses angulaires sous forme brute (nombres 16 bits) :

    def get_accel_gyro_raw(self):
        data = self.arduino.read_int16_array(0,signed=True)
        if (self.gyro):
            ax = np.array(data[0::6],dtype=np.double)
            ay = np.array(data[1::6],dtype=np.double)
            az = np.array(data[2::6],dtype=np.double)
            rx = np.array(data[3::6],dtype=np.double)
            ry = np.array(data[4::6],dtype=np.double)
            rz = np.array(data[5::6],dtype=np.double)
            return ax,ay,az,rx,ry,rz
        else:
            ax = np.array(data[0::3],dtype=np.double)
            ay = np.array(data[1::3],dtype=np.double)
            az = np.array(data[2::3],dtype=np.double)
            return ax,ay,az

             

Les fonctions suivantes permettent de faire l'étalonnage de l'accéléromètre. Par exemple, la fonction calibAxGp doit appelée lorsque l'accéléromètre est immobile avec son axe X vers le haut dans le champ de pesanteur terrestre. La valeur d'accélération mesurée sur cet axe est alors g. Bien sûr, il ne s'agit pas d'une accélération mais de l'opposé du champ de pesanteur terrestre (une erreur répandue consiste à coire qu'il s'agit de l'accélération de la pesanteur alors que c'est l'opposé).

    def calibAxGp(self):
        self.axgp = 0
        N = 5
        for k in range(N):
            ax,ay,az,rx,ry,rz = self.get_accel_gyro_raw()
            self.axgp += ax.mean()
        self.axgp /= N
        return self.axgp


    def calibAxGm(self):
        self.axgm = 0
        N = 5
        for k in range(N):
            ax,ay,az,rx,ry,rz = self.get_accel_gyro_raw()
            self.axgm += ax.mean()
        self.axgm /= N
        return self.axgm

    def calibAyGp(self):
        self.aygp = 0
        N = 5
        for k in range(N):
            ax,ay,az,rx,ry,rz = self.get_accel_gyro_raw()
            self.aygp += ay.mean()
        self.aygp /= N
        return self.aygp

    def calibAyGm(self):
        self.aygm = 0
        N = 5
        for k in range(N):
            ax,ay,az,rx,ry,rz = self.get_accel_gyro_raw()
            self.aygm += ay.mean()
        self.aygm /= N
        return self.aygm

    def calibAzGp(self):
        self.azgp = 0
        N = 5
        for k in range(N):
            ax,ay,az,rx,ry,rz = self.get_accel_gyro_raw()
            self.azgp += az.mean()
        self.azgp /= N
        return self.azgp

    def calibAzGm(self):
        self.azgm = 0
        N = 5
        for k in range(N):
            ax,ay,az,rx,ry,rz = self.get_accel_gyro_raw()
            self.azgm += az.mean()
        self.azgm /= N
        return self.azgm
                

La fonction suivante permet de régler les zéros du gyromètre. Elle doit être appelée lorsque le MPU6050 est immobile dans le référentiel terrestre (le gyromètre mesure la force de Coriolis).

    def calib_gyro_zero(self):
        N = 5
        self.rx_zero =0
        self.ry_zero =0
        self.rz_zero =0
        for k in range(N):
            ax,ay,az,rx,ry,rz = self.get_accel_gyro_raw()
            self.rx_zero += rx.mean()
            self.ry_zero += ry.mean()
            self.rz_zero += rz.mean()
        self.rx_zero /= N
        self.ry_zero /= N
        self.rz_zero /= N
              

Le script suivant permet de faire l'acquisition des accélérations et des vitesses angulaires pendant une durée définie par T. La fenêtre affichée par l'animation a une durée définie par Tfen. Il est possible de configurer l'accéléromètre/gyromètre (calibres, filtre et diviseur de fréquence) et de faire l'étalonnage de l'accéléromètre. Lorsque celui-ci est fait pour un calibre donné, il n'est pas en principe nécessaire de le refaire car les coefficients sont stockés dans un fichier. Pour refaire l'étalonnage, il faut tout d'abord effacer ce fichier.

acquisitionAnimateMPU6050.py
import numpy as np
import matplotlib.pyplot as plt
import matplotlib.animation as animation
from MPU6050 import *

ard = MPU6050("COM3")
accel_range = ard.ACCEL_FS_2
g_max = 2
gyro_range = ard.GYRO_FS_500
r_max = 500
dlpf_mode = ard.DLPF_BW_44
rate_div = 9 # fréquence finale de 100 Hz

ard.set_accel_range(accel_range)
ard.set_gyro_range(gyro_range)
ard.set_rate_div(rate_div)
ard.set_dlpf_mode(dlpf_mode)

fe = ard.fechant()
print("fe = %f"%fe)

Nbuf = 30 # nombre de valeurs dans le tampon
T = 20 # durée de l'acquisition
Ne = int(T*fe)
Tfen = 5 # durée de la fenêtre visualisée
Nfen = int(Tfen*fe)
temps = np.arange(Nfen)*1/fe
a = np.zeros(Nfen)

ard.start()
print("Gyromètre immobile..")
ard.calib_gyro_zero()

calib=False
if calib:
    print("Nfen = %d"%Nfen)
    input("Axe Z vers le haut ..")
    print(ard.calibAzGp())
    input("Axe Z vers le bas..")
    print(ard.calibAzGm())
    input("Axe X vers le haut ..")
    print(ard.calibAxGp())
    input("Axe X vers le bas..")
    print(ard.calibAxGm())
    input("Axe Y vers le haut ..")
    print(ard.calibAyGp())
    input("Axe Y vers le bas..")
    print(ard.calibAyGm())
    ard.set_accel_trans()
    ard.save_calib()

    

ax = np.zeros(Ne)
ay = np.zeros(Ne)
az = np.zeros(Ne)
rx = np.zeros(Ne)
ry = np.zeros(Ne)
rz = np.zeros(Ne)


fig,axis = plt.subplots(2,1)
line0, = axis[0].plot(temps,a,"r",label="ax")
line1, = axis[0].plot(temps,a,"g",label="ay")
line2, = axis[0].plot(temps,a,"b",label="az")
line3, = axis[1].plot(temps,a,"r",label="rx")
line4, = axis[1].plot(temps,a,"g",label="ry")
line5, = axis[1].plot(temps,a,"b",label="rz")
axis[0].grid()
axis[0].set_xlabel("t (s)")
axis[0].set_ylabel("g")
axis[0].axis([0,temps[-1],-g_max,g_max])
axis[0].legend(loc="upper right")
axis[1].grid()
axis[1].set_xlabel("t (s)")
axis[1].set_ylabel("deg/sec")
axis[1].axis([0,temps[-1],-r_max,r_max])
axis[1].legend(loc="upper right")


i = 0
def animate(frame):
    global i
    if i+Nbuf >= Ne: return
    buf_ax,buf_ay,buf_az,buf_rx,buf_ry,buf_rz = ard.get_accel_gyro()
    ax[i:i+Nbuf] = buf_ax
    ay[i:i+Nbuf] = buf_ay
    az[i:i+Nbuf] = buf_az
    rx[i:i+Nbuf] = buf_rx
    ry[i:i+Nbuf] = buf_ry
    rz[i:i+Nbuf] = buf_rz
    i += Nbuf
    i0 = i-Nfen
    i1 = i
    if i0<0:
        i0=0
        i1 = i
        t = np.arange(i)*1/fe
    else:
        t = temps+i0/fe
        axis[0].axis([t[0],t[-1],-g_max,g_max])
        axis[1].axis([t[0],t[-1],-r_max,r_max])
    line0.set_xdata(t)
    line1.set_xdata(t)
    line2.set_xdata(t)
    line3.set_xdata(t)
    line4.set_xdata(t)
    line5.set_xdata(t)
    line0.set_ydata(ax[i0:i1])
    line1.set_ydata(ay[i0:i1])
    line2.set_ydata(az[i0:i1])
    line3.set_ydata(rx[i0:i1])
    line4.set_ydata(ry[i0:i1])
    line5.set_ydata(rz[i0:i1])


ani = animation.FuncAnimation(fig,animate,frames = Ne//Nbuf,repeat=False,interval=1e-2)
plt.show()
ard.close()
temps = np.arange(Ne)*1/fe
filename = "accelgyro-1.txt"
np.savetxt(filename,np.array([temps,ax,ay,az,rx,ry,rz]).T,header="t(s)\t ax(g)\t ax(g)\t az(g)\t rx(deg/s)\t ry(deg/s)\t rz(deg\s) ")
[t,ax,ay,az,rx,ry,rz] = np.loadtxt(filename,unpack=True,skiprows=1)
plt.figure()
plt.subplot(211)
plt.plot(t,ax,"r",label="ax")
plt.plot(t,ay,"g",label="ay")
plt.plot(t,az,"b",label="az")
plt.ylabel("g")
plt.grid()
plt.subplot(212)
plt.plot(t,rx,"r",label="rx")
plt.plot(t,ry,"g",label="ry")
plt.plot(t,rz,"b",label="rz")
plt.xlabel("t (s)")
plt.ylabel("deg/sec")
plt.grid()
plt.show()
                 

4. Réalisation

La platine du MPU6050 et l'arduino NANO sont fixés sur un cadre. Les axes de l'accéléromètre sont en principe parallèles aux côtés du cadre. La communication avec le PC est faite par liaison radio au moyen de deux modules XBee.

accel

Le module XBee embarqué avec l'accéléromètre (visible sur la photo ci-dessus) est relié à l'arduino au moyen d'un platine d'adaptation de la manière suivante :

Remarque importante : la platine du XBee doit être retirée lorsqu'on téléverse le programme de l'Arduino.

Le MPU6050 est branché à l'Arduino de la manière suivante :

L'Arduino est alimenté par une pile 9 V branchée sur les bornes Vin et GND.

Le second module XBee est relié au PC au moyen d'un adaptateur USB. Les deux modules XBee doivent être configurés avec DIGI XCTU. Pour configurer un XBee, on le relie au PC par l'adaptateur USB. Il faut configurer la vitesse de transmission à 19200 bauds puisque c'est la vitesse utilisée aussi bien dans le programme Arduino que dans le programe Python. Il faut aussi configurer les deux modules pour qu'ils communiquent entre eux (cette configuration est expliquée dans Exploring XBees and XCTU.

Pour faire l'étalonnage de l'accéléromètre, on pose le cadre successivement sur ces 6 côtés en suivant les directives affichées par le programme (Axe X vers le haut, etc.). Pour faciliter le repérage, nous avons placé sur le cadre un tracé des axes :

accel

Lorsque l'accéléromètre est au repos dans le référentiel terrestre et l'axe Z est vers le haut (comme sur la photo ci-dessus), l'accélération az doit être égale à g. Comme expliqué plus haut, il s'agit en fait de l'opposé du champ de pesanteur dans le référentiel terrestre (rappelons que l'accéléromètre mesure le champ de pesanteur et affiche l'opposé). Si le cadre est accéléré vers le haut par rapport au référentiel terrestre, il y a en plus cette accélération dans az. Si le cadre est en chute libre dans le référentiel terrestre, l'accélération mesurée sur les trois axes est nulle puisqu'il y a impesanteur dans un référentiel en chute libre (si on néglige les forces de frottement de l'air).

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