Test unitaire

Le test unitaire est une méthode de test de code qui consiste à diviser le code en de plus petites « unités » possibles et en testant chaque unité. Dans le code robot, cela peut consister à tester le code pour chaque sous-système individuellement. Il existe de nombreux cadres de test unitaires pour la plupart des langages de programmation. Les projets de robots en Java ont JUnit 4 disponible par défaut, et les projets de robots en C++ disposent de Google Test.

Écriture de code testable

Note

Cet exemple peut être facilement adapté au paradigme orienté commande en dérivant (héritage) Intake de SubsystemBase.

Notre sous-système sera un mécanisme Intake du défin Infinite Recharge constitué d’un piston et d’un moteur : le piston déploie/rétracte le Intake, et le moteur tirera les cellules de puissance à l’intérieur. Nous ne voulons pas que le moteur fonctionne si le mécanisme Intake n’est pas déployé parce qu’il n’aura aucun effet.

Pour fournir un « clean slate » pour chaque test, nous avons besoin d’avoir une fonction pour détruire l’objet et libérer toutes les allocations matérielles. En Java, cela se fait en implémentant l’interface AutoCloseable et sa méthode .close(), détruisant chaque objet membre en appelant la méthode membre .close() - un objet sans méthode .close() n’a probablement pas besoin d’être fermé. En C++, le destructeur par défaut sera appelé automatiquement lorsque l’objet sort de sa portée et appellera à son tour les destructeurs des objets membres.

Note

Les fournisseurs tiers peuvent ne pas prendre en charge la fermeture des ressources de la même manière que celle indiquée ici. Consultez la documentation de votre fournisseur pour plus d’informations sur ce qu’il prend en charge et comment.

import edu.wpi.first.wpilibj.DoubleSolenoid;
import edu.wpi.first.wpilibj.PWMSparkMax;
import frc.robot.Constants.IntakeConstants;

public class Intake implements AutoCloseable {
  private PWMSparkMax motor;
  private DoubleSolenoid piston;

  public Intake() {
    motor = new PWMSparkMax(IntakeConstants.MOTOR_PORT);
    piston = new DoubleSolenoid(IntakeConstants.PISTON_FWD, IntakeConstants.PISTON_REV);
  }

  public void deploy() {
    piston.set(DoubleSolenoid.Value.kForward);
  }

  public void retract() {
    piston.set(DoubleSolenoid.Value.kReverse);
    motor.set(0); // turn off the motor
  }

  public void activate(double speed) {
    if (piston.get() == DoubleSolenoid.Value.kForward) {
      motor.set(speed);
    } else { // if piston isn't open, do nothing
      motor.set(0);
    }
  }

  @Override
  public void close() throws Exception {
    piston.close();
    motor.close();
  }
}

Écriture des Tests

Important

Les tests sont placés à l’intérieur de l’ensemble source test : /src/test/java/ et /src/test/cpp/ pour les tests Java et C++, respectivement. Les fichiers en dehors de cette racine source n’ont pas accès au cadre de test - cela fera échouer la compilation en raison de références non résolues.

En Java, chaque classe de test contient au moins une méthode de test marquée de @org.junit.Test, chaque méthode représentant un cas de test. D’autres méthodes d’ouverture des ressources (telles que notre objet Intake) avant chaque test et leur fermeture après sont respectivement marquées de @org.junit.Before et @org.junit.After. En C++, les classes de montage de test héritant de testing::Test contiennent nos objets matériels pour les sous-systèmes et la simulation, et les méthodes de test sont écrites à l’aide de la macro TEST_F(testfixture, testname). Les méthodes SetUp() et TearDown() peuvent être remplacées dans la classe de montage d’essai et seront exécutés respectivement avant et après chaque test.

Chaque méthode de test doit contenir au moins une assertion (assert*() en Java ou EXPECT_*() en C++). Ces assertions vérifient une condition à moment de l’exécution et échouent au test si la condition n’est pas remplie. S’il y a plus d’une assertion dans une méthode de test, la première assertion échouée plantera le test - l’exécution n’atteindra pas les assertions subséquentes.

JUnit et GoogleTest ont tous deux plusieurs types d’assertions, mais la plus commune est l’égalité : assertEquals(valeur attendue, valeur actuelle)/EXPECT_EQ(valeur attendue, valeur actuelle). Lors de la comparaison des nombres, un troisième paramètre - delta, l’erreur acceptable, peut être donné. Dans JUnit (Java), ces assertions sont des méthodes statiques et peuvent être utilisées sans qualification en ajoutant l’importation statique étoile (star) import static org.junit.Asssert.*. Dans Google Test (C++), les assertions sont des macros de l’en-tête <gtest/gtest.h>.

Note

La comparaison des valeurs en point-flottants n’est pas exacte, de sorte que leur comparaison doit être faite avec un paramètre d’erreur acceptable (DELTA).

import static org.junit.Assert.*;

import edu.wpi.first.hal.HAL;
import edu.wpi.first.wpilibj.DoubleSolenoid;
import edu.wpi.first.wpilibj.simulation.DoubleSolenoidSim;
import edu.wpi.first.wpilibj.simulation.PWMSim;
import frc.robot.Constants.IntakeConstants;
import org.junit.*;

public class IntakeTest {
  public static final double DELTA = 1e-2; // acceptable deviation range
  Intake intake;
  PWMSim simMotor;
  DoubleSolenoidSim simPiston;

  @Before // this method will run before each test
  public void setup() {
    assert HAL.initialize(500, 0); // initialize the HAL, crash if failed
    intake = new Intake(); // create our intake
    simMotor = new PWMSim(IntakeConstants.MOTOR_PORT); // create our simulation PWM motor controller
    simPiston = new DoubleSolenoidSim(IntakeConstants.PISTON_FWD, IntakeConstants.PISTON_REV); // create our simulation solenoid
  }

  @After // this method will run after each test
  public void shutdown() throws Exception {
    intake.close(); // destroy our intake object
  }

  @Test // marks this method as a test
  public void doesntWorkWhenClosed() {
    intake.retract(); // close the intake
    intake.activate(0.5); // try to activate the motor
    assertEquals(0.0, simMotor.getSpeed(), DELTA); // make sure that the value set to the motor is 0
  }

  @Test
  public void worksWhenOpen() {
    intake.deploy();
    intake.activate(0.5);
    assertEquals(0.5, simMotor.getSpeed(), DELTA);
  }

  @Test
  public void retractTest() {
    intake.retract();
    assertEquals(DoubleSolenoid.Value.kReverse, simPiston.get());
  }

  @Test
  public void deployTest() {
    intake.deploy();
    assertEquals(DoubleSolenoid.Value.kForward, simPiston.get());
  }
}

Pour une utilisation plus avancée de JUnit et Google Test, consultez les documents cadres.

Exécution des tests

Note

Les tests seront toujours exécutés en simulation sur votre bureau. Pour les conditions préalables et plus d’informations, consultez Introduction à la simulation.

Pour que les tests Java s’exécutent, assurez-vous que votre fichier build.gradle contient le bloc suivant :

test {
   useJUnit()
}

Utilisez Test Robot Code de la palette de Commande pour exécuter les tests. Les résultats seront affichés dans le terminal de sortie, chaque test aura une étiquette FAILED ou PASSED/OK à côté du nom de test dans la sortie. JUnit (Java uniquement) générera un document HTML dans build/reports/tests/test/index.html avec une vue d’ensemble plus détaillée des résultats; s’il y a un test qui a échoué un lien pour rendre le document dans votre navigateur sera imprimé dans le terminal de sortie.

Par défaut, Gradle exécute les tests chaque fois que le code robot est compilé, y compris les déploiements. Cela augmentera le temps de déploiement, et des tests défaillants et provoquera l’échec de la compilation et du déploiement. Pour éviter que cela ne se produise, vous pouvez utiliser Change Skip Tests On Deploy Setting de la palette de commande pour configurer, s’il y a lieu, l’exécution des tests lors du déploiement.