Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add Unit Testing article #1203

Merged
merged 23 commits into from
Feb 27, 2021
Merged
Show file tree
Hide file tree
Changes from 1 commit
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -8,3 +8,4 @@ Robot Simulation
introduction
simulation-gui
physics-sim
unit-testing
Original file line number Diff line number Diff line change
@@ -0,0 +1,91 @@
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 4<https://junit.org/junit4/>`__ available by default, and C++ robot projects have `Google Test<https://github.com/google/googletest/blob/master/docs/primer.md>`__.
Starlight220 marked this conversation as resolved.
Show resolved Hide resolved

Let's write our subsystem code, and then we'll write a test for it.
Daltz333 marked this conversation as resolved.
Show resolved Hide resolved

Our subsystem will be an Infinite Recharge intake mechanism containing a piston and a motor: the piston deploys/retracts the intake, and the motor will pull the Power Cells inside. Since it won't do anything, we don't want the motor to run if the intake mechanism isn't deployed.
Starlight220 marked this conversation as resolved.
Show resolved Hide resolved

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

.. tabs::
.. code-tab:: Java
// src/main/frc/robot/subsystems/Intake.java
Starlight220 marked this conversation as resolved.
Show resolved Hide resolved

public class Intake {
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);
}
Starlight220 marked this conversation as resolved.
Show resolved Hide resolved
}
}

.. code-tab:: C++
// TODO


Now let's write the unit test to assert that everything works:

.. note:: Comparison of floating-point values isn't accurate, so comparing them should be done with an acceptable error parameter (``DELTA``).

.. tabs::
.. code-tab:: Java
// src/test/frc/robot/subsystems/IntakeTest.java

public class IntakeTest {
Starlight220 marked this conversation as resolved.
Show resolved Hide resolved
public static final DELTA = 1e-2; // acceptable difference
Intake intake;
PWMSim simMotor;
PCMSim simPcm;
Starlight220 marked this conversation as resolved.
Show resolved Hide resolved

@Before // this method will run before each test
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
simPcm = new PCMSim(); // default PCM
Starlight220 marked this conversation as resolved.
Show resolved Hide resolved
}

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

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

.. code-tab:: C++
// TODO


Each test contains at least one assertion (``assert*()``/``EXPECT_*()``). These assertions verify a certain condition and fail the test if the condition isn't met.

Both JUnit and GoogleTest have multiple __assertion__ types, but 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.