Unit Testing

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.

Escribir código para pruebas

Nota

This example can be easily adapted to the command-based paradigm by having Intake inherit from SubsystemBase.

Nuestro subsistema será un mecanismo Intake para Infinite Recharge que contiene un pistón y un motor: el pistón despliega/retrae la admisión y el motor arrastrará las Power Cells hacia adentro. No queremos que el motor funcione si el mecanismo de admisión no está desplegado porque no hará nada.

Para proporcionar una «pizarra limpia» para cada prueba, necesitamos tener una función para destruir el objeto y liberar todas las asignaciones de hardware. En Java, esto se hace implementando la interfaz AutoCloseable y su método .close(), destruyendo cada objeto de los miembros al llamar al método .close() del objeto - un objeto sin un método .close() probablemente no necesite ser cerrado. En C ++, el destructor predeterminado se llamará automáticamente cuando el objeto salga del alcance y llamará a los destructores de los objetos miembros.

Nota

Es posible que los proveedores no admitan el cierre de recursos de la misma manera que se muestra aquí. Consulte la documentación de su proveedor para obtener más información sobre qué admiten y cómo.

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;
}

Writing Tests

Importante

Los tests se colocan dentro del conjunto de fuentes de test: /src/test/java/ y /src/test/cpp/ para tests de Java y C++ respectivamente. Los archivos fuera de esa raíz de origen no tienen acceso al marco de prueba; esto fallará en la compilación debido a referencias sin resolver.

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.

Cada método de prueba debe contener al menos una aserción (assert*() en Java o EXPECT_*() en C++). Estas aserciones verifican una condición en tiempo de ejecución y fallan la prueba si la condición no se cumple. Si hay más de una aserción en un método de prueba, la primera aserción fallida bloqueará la prueba - la ejecución no llegará a las aserciones posteriores.

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.

Nota

La comparación de valores de punto flotante no es precisa, por lo que la comparación debe hacerse con un parámetro de error aceptable (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());
}

Para un uso más avanzado de JUnit y Google Test, consulte la documentación del framework.

Pruebas para correrlo

Nota

Las pruebas se ejecutarán siempre en simulación en su escritorio. Para conocer los requisitos previos y más información, consulte el documento introducción a la simulación.

Para que las pruebas Java se ejecuten, asegúrese de que su archivo build.gradle contenga el siguiente bloque:

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.

Por defecto, Gradle ejecuta las pruebas cada vez que se construye el código del robot, incluyendo los despliegues. Esto aumentará el tiempo de despliegue, y las pruebas fallidas harán que la construcción y el despliegue fallen. Para evitar que esto ocurra, puedes utilizar Change Skip Tests On Deploy Setting de la paleta de comandos para configurar si se ejecutan las pruebas al desplegar.