单元测试

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.

编写可测试的代码

备注

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

我们的子系统将是一个 Infinite Recharge 进气机构,包含一个活塞和一个电机:活塞展开/收回进气口,电机将把电池拉到里面。如果未部署进气机构,我们不希望电机运行,因为它不会做任何事情。

为了为每个测试提供一个“干净的石板”,我们需要有一个函数来销毁对象并释放所有硬件分配。在 Java 中,这是通过实现 AutoCloseable 接口及其 .close() 方法来完成的,通过调用成员的 .close() 方法来销毁每个成员对象 - 一个没有 ` 的对象`.close()`` 方法可能不需要关闭。在C++中,当对象超出作用域时会自动调用默认的析构函数,并调用成员对象的析构函数。

备注

供应商可能不支持与此处显示的方式相同的资源关闭。有关他们支持的内容和方式的更多信息,请参阅供应商的文档。

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

编写测试

重要

测试放置在 test 源集中:/src/test/java//src/test/cpp/ 分别用于 Java 和 C++ 测试。该源根目录之外的文件无法访问测试框架 - 由于未解析的引用,这将导致编译失败。

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.

每个测试方法应至少包含一个 *assertion*(Java 中的“assert*()”或 C++ 中的“EXPECT_*()”)。这些断言在运行时验证条件,如果不满足条件,则测试失败。如果测试方法中有多个断言,第一个失败的断言将使测试崩溃 - 执行不会到达后面的断言。

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.

备注

浮点值的比较不准确,因此应该使用可接受的错误参数(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());
}

有关 JUnit 和 Google Test 的更高级用法,请参阅框架文档。

运行测试

备注

测试将始终在您的桌面上以模拟方式运行。有关先决条件和更多信息,请参阅:doc:模拟介绍

要运行 Java 测试,请确保您的“build.gradle”文件包含以下块:

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.

默认情况下,Gradle 会在构建机器人代码(包括部署)时运行测试。这将增加部署时间,失败的测试将导致构建和部署失败。为了防止这种情况发生,您可以使用指令面板中的:guilabel:Change Skip Tests On Deploy Setting 来配置是否在部署时运行测试。