Test unitaire

Unit testing is a method of testing code by dividing the code into the smallest « units » possible and testing each unit. In robot code, this can mean testing the code for each subsystem individually. There are many unit testing frameworks for most languages. Java robot projects have JUnit 5 available by default, and C++ robot projects have Google Test.

Écriture de code testable

Note

This example can be easily adapted to the command-based paradigm by having Intake inherit from 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.PneumaticsModuleType;
import edu.wpi.first.wpilibj.examples.unittest.Constants.IntakeConstants;
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;

public class Intake implements AutoCloseable {
  private final PWMSparkMax m_motor;
  private final DoubleSolenoid m_piston;

  public Intake() {
    m_motor = new PWMSparkMax(IntakeConstants.kMotorPort);
    m_piston =
        new DoubleSolenoid(
            PneumaticsModuleType.CTREPCM,
            IntakeConstants.kPistonFwdChannel,
            IntakeConstants.kPistonRevChannel);
  }

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

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

  public void activate(double speed) {
    if (isDeployed()) {
      m_motor.set(speed);
    } else { // if piston isn't open, do nothing
      m_motor.set(0);
    }
  }

  public boolean isDeployed() {
    return m_piston.get() == DoubleSolenoid.Value.kForward;
  }

  @Override
  public void close() {
    m_piston.close();
    m_motor.close();
  }
}
#include <frc/DoubleSolenoid.h>
#include <frc/motorcontrol/PWMSparkMax.h>

#include "Constants.h"

class Intake {
 public:
  void Deploy();
  void Retract();
  void Activate(double speed);
  bool IsDeployed() const;

 private:
  frc::PWMSparkMax m_motor{IntakeConstants::kMotorPort};
  frc::DoubleSolenoid m_piston{frc::PneumaticsModuleType::CTREPCM,
                               IntakeConstants::kPistonFwdChannel,
                               IntakeConstants::kPistonRevChannel};
};
#include "subsystems/Intake.h"

void Intake::Deploy() {
  m_piston.Set(frc::DoubleSolenoid::Value::kForward);
}

void Intake::Retract() {
  m_piston.Set(frc::DoubleSolenoid::Value::kReverse);
  m_motor.Set(0);  // turn off the motor
}

void Intake::Activate(double speed) {
  if (IsDeployed()) {
    m_motor.Set(speed);
  } else {  // if piston isn't open, do nothing
    m_motor.Set(0);
  }
}

bool Intake::IsDeployed() const {
  return m_piston.Get() == frc::DoubleSolenoid::Value::kForward;
}

É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.

In Java, each test class contains at least one test method marked with @org.junit.jupiter.api.Test, each method representing a test case. Additional methods for opening resources (such as our Intake object) before each test and closing them after are respectively marked with @org.junit.jupiter.api.BeforeEach and @org.junit.jupiter.api.AfterEach. In C++, test fixture classes inheriting from testing::Test contain our subsystem and simulation hardware objects, and test methods are written using the TEST_F(testfixture, testname) macro. The SetUp() and TearDown() methods can be overridden in the test fixture class and will be run respectively before and after each 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.

Both JUnit and GoogleTest have multiple assertion types; the most common is equality: assertEquals(expected, actual)/EXPECT_EQ(expected, actual). When comparing numbers, a third parameter - delta, the acceptable error, can be given. In JUnit (Java), these assertions are static methods and can be used without qualification by adding the static star import import static org.junit.jupiter.api.Assertions.*. In Google Test (C++), assertions are macros from the <gtest/gtest.h> header.

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.jupiter.api.Assertions.assertEquals;

import edu.wpi.first.hal.HAL;
import edu.wpi.first.wpilibj.DoubleSolenoid;
import edu.wpi.first.wpilibj.PneumaticsModuleType;
import edu.wpi.first.wpilibj.examples.unittest.Constants.IntakeConstants;
import edu.wpi.first.wpilibj.simulation.DoubleSolenoidSim;
import edu.wpi.first.wpilibj.simulation.PWMSim;
import org.junit.jupiter.api.AfterEach;
import org.junit.jupiter.api.BeforeEach;
import org.junit.jupiter.api.Test;

class IntakeTest {
  static final double DELTA = 1e-2; // acceptable deviation range
  Intake m_intake;
  PWMSim m_simMotor;
  DoubleSolenoidSim m_simPiston;

  @BeforeEach // this method will run before each test
  void setup() {
    assert HAL.initialize(500, 0); // initialize the HAL, crash if failed
    m_intake = new Intake(); // create our intake
    m_simMotor =
        new PWMSim(IntakeConstants.kMotorPort); // create our simulation PWM motor controller
    m_simPiston =
        new DoubleSolenoidSim(
            PneumaticsModuleType.CTREPCM,
            IntakeConstants.kPistonFwdChannel,
            IntakeConstants.kPistonRevChannel); // create our simulation solenoid
  }

  @SuppressWarnings("PMD.SignatureDeclareThrowsException")
  @AfterEach // this method will run after each test
  void shutdown() throws Exception {
    m_intake.close(); // destroy our intake object
  }

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

  @Test
  void worksWhenOpen() {
    m_intake.deploy();
    m_intake.activate(0.5);
    assertEquals(0.5, m_simMotor.getSpeed(), DELTA);
  }

  @Test
  void retractTest() {
    m_intake.retract();
    assertEquals(DoubleSolenoid.Value.kReverse, m_simPiston.get());
  }

  @Test
  void deployTest() {
    m_intake.deploy();
    assertEquals(DoubleSolenoid.Value.kForward, m_simPiston.get());
  }
}
#include <frc/DoubleSolenoid.h>
#include <frc/simulation/DoubleSolenoidSim.h>
#include <frc/simulation/PWMSim.h>
#include <gtest/gtest.h>

#include "Constants.h"
#include "subsystems/Intake.h"

class IntakeTest : public testing::Test {
 protected:
  Intake intake;  // create our intake
  frc::sim::PWMSim simMotor{
      IntakeConstants::kMotorPort};  // create our simulation PWM
  frc::sim::DoubleSolenoidSim simPiston{
      frc::PneumaticsModuleType::CTREPCM, IntakeConstants::kPistonFwdChannel,
      IntakeConstants::kPistonRevChannel};  // create our simulation solenoid
};

TEST_F(IntakeTest, DoesntWorkWhenClosed) {
  intake.Retract();      // close the intake
  intake.Activate(0.5);  // try to activate the motor
  EXPECT_DOUBLE_EQ(
      0.0,
      simMotor.GetSpeed());  // make sure that the value set to the motor is 0
}

TEST_F(IntakeTest, WorksWhenOpen) {
  intake.Deploy();
  intake.Activate(0.5);
  EXPECT_DOUBLE_EQ(0.5, simMotor.GetSpeed());
}

TEST_F(IntakeTest, Retract) {
  intake.Retract();
  EXPECT_EQ(frc::DoubleSolenoid::Value::kReverse, simPiston.Get());
}

TEST_F(IntakeTest, Deploy) {
  intake.Deploy();
  EXPECT_EQ(frc::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 :

74test {
75    useJUnitPlatform()
76    systemProperty 'junit.jupiter.extensions.autodetection.enabled', 'true'
77}

Use Test Robot Code from the Command Palette to run the tests. Results will be reported in the terminal output, each test will have a FAILED or PASSED/OK label next to the test name in the output. JUnit (Java only) will generate a HTML document in build/reports/tests/test/index.html with a more detailed overview of the results; if there are any failed tests a link to render the document in your browser will be printed in the terminal output.

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.