Tutorial

Unit Testing Commands

The WPILib command framework divides your robot program into two types of classes: subsystems and commands.  The subsystem classes represent the major physical parts of the robot, such as a shooter subsystem, a drive-train subsystem, or a manipulator arm subsystem.  The command classes define the actions taken by the subsystems, such as shooting a ball, moving the drive-train, or raising the manipulator arm.

unit_test_commands

Most of your programming time will go into creating, refining and debugging new commands.  Commands will be the most sophisticated part of your code.  Therefore they also have the greatest risk of going wrong.  Therefore you should spend a lot of time testing your commands.

So far we have tested simple functions and verified the primitive functionality in subsystems.  The next step is to created automated tests for your commands.

Testing a simple Command

Our simple example robot contains a Shooter subsystem that shoots balls.  The ShooterSubsystem has a high-speed wheel for throwing the ball, and a servo arm that can raise the ball up until it touches the wheel.  We will need a command to set the wheel speed, and another to control the servo arm.

A simple Command

Here is the command to raise or lower the servo arm:

package frc.robot.commands;

import edu.wpi.first.wpilibj.experimental.command.*;
import frc.robot.subsystems.*;

public class ShooterServoArmCommand extends SendableCommandBase {

  private final boolean fire;
  private final ShooterSubsystem shooter;

  public ShooterServoArmCommand(boolean fireArm, ShooterSubsystem shooterSubsystem) {
    fire = fireArm;
    shooter = shooterSubsystem;
    addRequirements(shooter);
  }

  @Override
  public void execute() {
    if (fire) {
      shooter.fire();
    } else {
      shooter.retract();
    }
  }

  @Override
  public boolean isFinished() {
    return true;
  }
}

Take note of the two parameters on the constructor:  fireArm and shooterSubsystem.   This command can either raise the arm or lower it, depending on whether the fireArm parameter is true or false.

By specifying the shooterSubsytem in the constructor we are using Dependency Injection, which makes the code more reusable and more testable.  When testing, we can replace the real subsystems with mock objects that fake the subsystem’s functionality.

A simple Test

Our task does two different things: retract and fire. First let’s test that firing the ball works:

package frc.robot.commands;

import edu.wpi.first.wpilibj.experimental.command.*;
import frc.robot.subsystems.*;
import org.junit.*;

import static org.mockito.Mockito.mock;
import static org.mockito.Mockito.verify;

public class ShooterServoArmCommandTest {

    private CommandScheduler scheduler = null;

    @Before
    public void setup() {
        scheduler = CommandScheduler.getInstance();
    }

    @Test
    public void testFireArm() {
        // Arrange
        ShooterSubsystem shooter = mock(ShooterSubsystem.class);
        ShooterServoArmCommand fireCommand 
                = new ShooterServoArmCommand(true, shooter);

        // Act
        scheduler.schedule(fireCommand);
        scheduler.run();

        // Assert
        verify(shooter).fire();
    }
}

The test follows our Arrange / Act / Assert pattern:

  • We create a mock version of our ShooterSubsystem.  If we wanted, we could also define some mock behaviors at this point.
    We create the actual command we will test.  In this case we set the fireArm parameter to true, indicating that we want to fire the ball.
  • In the command framework, we never explicitly execute the command methods.  Instead, we “put it on the schedule”.   After this, the command scheduler will run the methods appropriately.  On a real robot, the scheduler tries to run all scheduled commands every 20 milliseconds.
    In this case we know that  our command will only run once before it’s done.
  • At the end of the test, we ask the mock framework to verify that the shooter’s “fire” command was called exactly once.

Unit tests will all execute whenever we build the code.  Go ahead and execute the “Build Robot Code” action within Visual Studio code.  Next write a similar test to verify that the command also correctly retracts the servo arm:

@Test
public void testRetractArm() {
    // Arrange
    ShooterSubsystem shooter = mock(ShooterSubsystem.class);
    ShooterServoArmCommand retractCommand = new ShooterServoArmCommand(false, shooter);

    // Act
    scheduler.schedule(retractCommand);
    scheduler.run();

    // Assert
    verify(shooter).retract();
}

Testing a Command Group

Simple commands can be grouped together to run sequentially or in parallel as more complicated commands.

A more complex Command

For instance, actually shooting a ball is a sequence of steps:

package frc.robot.commands;

import edu.wpi.first.wpilibj.experimental.command.*;
import frc.robot.subsystems.*;

public class AutoShootCommand extends SequentialCommandGroup {
    public AutoShootCommand(ShooterSubsystem shooter) {
        super(
                new PrintCommand("BEGIN: AutoShootCommand"),
                new ShooterServoArmCommand(false, shooter),
                new ShooterSetSpeedCommand(1.0, shooter),
                new WaitCommand(0.5),
                new ShooterServoArmCommand(true, shooter),
                new WaitCommand(0.5),
                new ShooterSetSpeedCommand(0.0, shooter),
                new ShooterServoArmCommand(false, shooter),
                new PrintCommand("END: AutoShootCommand")
        );
    }
}

Note that we are again using dependency injection, but that the same ShooterSubsystem will be used in all the internal commands.

Besides the shooter commands, we’ve also thrown in a couple of PrintCommands.  These commands print out to the console at the beginning and end of the command.  They also print to the Log File Viewer to be reviewed after a match.

Also we’ve thrown in a couple of WaitCommands, which give the shooter wheel half a second to spin up before shooting and then maintain speed while the ball is firing.

Testing a Command Group

A command group test follows the same pattern as simpler tests:

package frc.robot.commands;

import static org.junit.Assert.*;
import static org.mockito.Mockito.*;

import org.junit.*;

import edu.wpi.first.wpilibj.experimental.command.CommandScheduler;
import frc.robot.subsystems.ShooterSubsystem;

public class AutoShootCommandTest {

    private CommandScheduler scheduler = null;

    @Before
    public void setup() {
        scheduler = CommandScheduler.getInstance();
    }

    @Test
    public void testShoot() throws InterruptedException {
        // Arrange
        ShooterSubsystem shooter = mock(ShooterSubsystem.class);
        AutoShootCommand command = new AutoShootCommand(shooter);

        // Act
        scheduler.schedule(command);
        for (int i=0; i<100; i++) {
            scheduler.run();
            Thread.sleep(20);
        }

        // Assert
        verify(shooter, times(2)).retract();
        verify(shooter, times(1)).fire();
        verify(shooter).setSpeed(1.0);
        verify(shooter).setSpeed(0.0);
    }
}

This command takes many run cycles, so run it many times, pausing 20 milliseconds between each execution.

After executing everything in the command group, we verify that the subsystem experienced all the actions for shooting.

Writing quality tests

It’s important to remember why we do unit testing.: we create suites of automated tests to improve the quality of our software.  Writing quality tests is a big subject and these last three articles have covered a lot of ground.  It would be easy to be overwhelmed, or in fact dubious, with all of this.  So keep your eye on the end goal:  software quality.

In a sense, writing methodical tests is a stepping stone from just programming into Software Engineering. Engineering means using systematic and disciplined practices when creating things.  Your tests will verify and quantify your software quality, in way that others can read and evaluate.

Further Reading

Tutorial

Unit Testing Subsystems

Testing is an element of any software development, and certainly it’s a big part of robot programming.  You’ve probably already done a lot of robot testing; deploy your code and test the robot.  Hopefully you’re already familiar with the idea of unit testing of small functions, but we can also automate the testing of whole subsystems.

Unit testing with WPILib

To demonstrate automated testing of robot subsystems, we’ll use a simplified robot program.  This program runs on a real robot build for the 2016 game, FIRST Stronghold.

A simple subsystem

In the WPILib command pattern a subsystem class represents a physical subset of the robot.  A subsystem contains physical components, such as motors and sensors.  There will be actions to perform on the subsystem, such as to drive or shoot.  For this example, we have a simple robot with two subsystems representing the robot chassis with its drive motors, and a shooter for throwing balls.

unit_test_subsystems.png

Mostly we’re going to work on testing the ShooterSubsystem.  The shooter has two components: a motor attached to a spinner wheel  and an arm attached to a servo that manipulates the ball.  To shoot a ball we will:

  1. Retract the servo arm so we can pick up a ball.
  2. Start the shooter wheel spinning.
  3. Extend the servo arm so the ball is pushed into the wheel.  The ball will go flying.
  4. Reset the system.  The wheel will be stopped and the servo retracted.

(Shooter Picture)

Here’s the code for the shooter subsystem:

package frc.robot.subsystems;

import static frc.robot.Constants.*;
import edu.wpi.first.wpilibj.Servo;
import edu.wpi.first.wpilibj.SpeedController;
import edu.wpi.first.wpilibj.experimental.command.*;

public class ShooterSubsystem extends SendableSubsystemBase {

    protected final SpeedController shooterMotor;
    protected final Servo shooterServo;
    protected boolean servoRetracted = true;

    public ShooterSubsystem(SpeedController motor, Servo servo) {
        shooterMotor = motor;
        shooterServo = servo;
    }

    public void setSpeed(double speed) {
        shooterMotor.set(speed);
    }

    public void retract() {
        shooterServo.set(SHOOTER_SERVO_MIN);
        servoRetracted = true;
    }

    public void fire() {
        shooterServo.set(SHOOTER_SERVO_MAX);
        servoRetracted = false;
    }

    public void reset() {
        setSpeed(0.0);
        retract();
    }
}

Note that the constructor takes two parameters as inputs: motor and servo. The motor and servo objects will be created elsewhere and then injected when the subsystem is constructed.

Mock testing with WPILib

The best way to do testing is with the full robot; load your code and go through a methodical test process.  Too often however, we don’t have sufficient access to the robot.  Maybe it hasn’t been built at all, or maybe it is shared with our teammates.  How can we test the code without access to the robot?  The answer is that we can test much of the logic with “mock” components.  Mocks are software objects that stand in for the real classes.  Instead of real motors, servos, and sensors, we’ll use mock motors, mock servos, and mock sensors.

We will use the Mockito framework to create mock SpeedControllers and mock Servos.   Mockito is a professional package for creating Java mocks, defining the mock behavior and checking the results.

To use Mockito, you’ll need to make two simple changes to your build.gradle file.

    1. Change the value of the includeDesktopSupport variable to true.
    2. Add the following line into the dependencies section: testCompile"org.mockito:mockito-core:2.+" .

unit_test_mockito

A simple unit test

Add a “test” directory under “src” for your java unit tests.  Right-click on “src”, select “New Folder” and enter “test/java/frc/robot/subsystems”.  Right-click on “subsystems” and select “create an empty class” named “ShooterSubsystemTest.java”

unit_test_test2.png

Now we can create a test of the subsystem’s constructor:

package frc.robot.subsystems;

import static org.junit.Assert.*;
import static org.mockito.Mockito.*;
import edu.wpi.first.wpilibj.*;
import org.junit.*;

public class ShooterSubsystemTest {

    @Test
    public void testConstructor() {
       // Arrange
        SpeedController motor = mock(SpeedController.class);
        Servo servo = mock(Servo.class);

        // Act
        ShooterSubsystem shooter = new ShooterSubsystem(motor, servo);

        // Assert
        assertEquals(true, shooter.servoRetracted);

    }
}

In this test we first create mock objects for the motor and the servo.  The action we are testing is just to create the shooter object.  After performing the action, we verify that the servo is retracted.

Note that the test is broken into sections.  The Arrange / Act / Assert breakdown is a common pattern for designing tests.  Sometimes we’ll add some extra sections, but most tests will have the basic three parts.

You could argue that this test is a little superficial, and you’d be right. However, this test does serve a purpose. If at some later date someone changed the subsystem so it didn’t initially retract the server, then this test would fail.   We would then need to decide whether the code or the test has become incorrect.

Another unit test

Next let’s write a test for the setSpeed method.  This method sets the speed of the motor.  After it has been executed, the motor controller will have a different speed:

@Test
public void testSetSpeed() {
    // Arrange
    SpeedController motor = mock(SpeedController.class);
    Servo servo = mock(Servo.class);
    ShooterSubsystem shooter = new ShooterSubsystem(motor, servo);

    when(motor.get()).thenReturn(0.5);

    // Act
    shooter.setSpeed(0.5);

    // Assert
    assertEquals(0.5, shooter.shooterMotor.get(), 0.001);
}

First we set up the mock objects and the shooter subsystem. This time we tweak the mock motor a little, specifying that when we get the motor’s speed, then it will return 0.5. The action is to set the speed. Afterwards we check that the speed was really set (and specifying a margin of error of 0.001).

As your tests get more sophisticated, you’ll use the “when” method to add more mock behavior to your mock objects.

The code above is another fairly superficial test, but it does exercise the code and the mock objects.  Let’s consider more features of the mock framework:

Yet another unit test

Let’s test the “reset” method of our subsystem.  In this case we want to verify that the motor has really been stopped and the servo arm has been retracted.

@Test
public void testReset() {
    // Arrange
    SpeedController motor = mock(SpeedController.class);
    Servo servo = mock(Servo.class);
    ShooterSubsystem shooter = new ShooterSubsystem(motor, servo);

    // Act
    shooter.reset();

    // Assert
    assertEquals(true, shooter.servoRetracted);
    verify(motor).set(0.0);
    verify(servo).set(SHOOTER_SERVO_MIN);
}

This time there are more lines of code in the “Assert” section.  Besides verifying that the server arm was retracted, we also run two verifications on the mock objects.

The “when” and “verify” features of mock objects are allow some sophisticated tests.  You may see your tests growing with many fiddly mock behaviors.  This is usually OK.  Just make your tests as simple as possible, but no simpler.

Dependency injection

Our ShooterSubsystem depends on two objects created elsewhere, a servo and a motor speed controller.  Those dependent objects are specified in our subsystems constructor.   This pattern is called Dependency Injection.  The tests described above wouldn’t be possible if we weren’t able to inject mock objects into our system-under-test.

Dependency Injection is an important concept within software engineering.  Besides encouraging testability, it supports the concept of Separation of Concerns. This means that we often break a large program into sections that each handle different concerns.  In this case we have one class that handles creation and definition of physical components (typically a RobotMap or RobotTemplate class) and another class that defines the behavior and interaction between those components (our subsystem).

Further Reading

Tutorial

Simple Unit Tests

Every programmer has at one time deployed code without having tested it.  Simple changes go out with the assumption that they can not possibly fail. And then they betray us.  We learn the lesson:  all code must be tested, thoroughly and repeatedly.

On robots we often need the hardware to do some of the testing, but there are still a lot of tests that can be executed offline.  Ideally, you should build up suites of tests that execute automatically; just start one test program and all tests execute.  There are many categories of automated tests, but the most common is called unit testing, because they test small units of functionality, including the functions you assumed can’t fail.

Well crafted unit tests will improve the quality of your software and insure its quality down the road.  You may choose to organize your development around those tests, a practice called Test Driven Development.  Unit tests are also essential to refactoring, which is a systematic technique for improving your code;  you’ll need automated test to verify that your refactored code still works correctly.

Unit testing with WPILib

GradleRIO is already set up for the unit testing frameworks JUnit and GoogleTest.   If you define unit test classes in your project, they will automatically execute every time you build the code.

Let’s define a simple function and create unit tests for it.  Don’t worry that this code looks too simple to merit testing.   Remember that no code is so trivial that it won’t fail.

A simple function

Suppose you’ve got a Gyro installed on your robot.  When you first start it up, the gyro will show 0 degrees.  Rotate the robot a little to the right and it might read 30 degrees.  However, the gyro’s scale is continuous, so after a lot of driving around it might read 1537 degrees or -2781 degrees.  This might mess up the math in some of your autonomous commands, since 1537 degrees is really the same as 97 degrees.  We need a function that simplifies angles into the range -180 to 180.  Here are some test cases:

  • 270 degree is the same as -90 degrees
  • -315 degrees is the same as 45 degrees
  • 30 degrees is still 30 degrees
  • -60 degrees is still -60 degrees

Here’s a simple conversion function.  It definitely isn’t perfect, but we’ll fix that in a minute:

public int simplifyAngle(int angle) {
    if (angle > 180) {
        angle = angle - 360;
    }
    if (angle < -180) {
        angle = angle + 360;
    }
    return angle;
}

For this example, this function is in your Robot class which is stored with the other java main classes in your “src” directory:

unit_test_func1

A simple unit test

Add a “test” directory under “src” for your java unit tests.  Right-click on “src”, select “New Folder” and enter “test/java/frc/robot”.  Right-click on “robot” and select create an empty class named “RobotTest.java”

unit_test_test1.png

Consider the test method:

@Test
public void testSimplifyAngle() {
    Robot robot = newRobot();
    assertEquals(-90, robot.simplifyAngle(270));
    assertEquals(-45, robot.simplifyAngle(315));
    assertEquals(-60, robot.simplifyAngle(-60));
    assertEquals(30, robot.simplifyAngle(30));
}

The @Test annotation on top means that this method will be executed by the GradleRIO test task.  We create a Robot object and then test our method for each of the test cases.

This test class will execute every time you build robot code.  If any of the assertions fail, the whole build will be rejected. To see what happens on a failure, temporarily change the 30 degree test so it expects -30 degrees. The build will fail and tell you to check line 15:

unit_test_fail1

Improving the function

How many test cases should you use?  Usually more than you would expect, even for simple functions.

Always include a trivial test case, sometimes called the “happy path” case. The 30 degree and -60 degree test might be considered happy path tests, but we could also test 0 degrees.  Add some test scenarios where there are logical transitions; these are called “corner cases”.  For this example, corner tests might be at 180 degrees and -180 degrees.  Also test a couple extreme cases, such as 1537 degrees and -2781 degrees.  Extreme tests at absolute maximums or minimums are called “edge cases”.

Now our test looks like this:

@Test
public void testSimplifyAngle() {
    Robot robot=new Robot();
    assertEquals(-90, robot.simplifyAngle(270));
    assertEquals(-45, robot.simplifyAngle(315));
    assertEquals(-60, robot.simplifyAngle(-60));
    assertEquals(30, robot.simplifyAngle(30));
    assertEquals(0, robot.simplifyAngle(0));
    assertEquals(180, robot.simplifyAngle(180));
    assertEquals(-180, robot.simplifyAngle(-180));
    assertEquals(97, robot.simplifyAngle(1537));
    assertEquals(99, robot.simplifyAngle(-2781));
}

Executing this test reveals that our function fails for the extreme cases.  Our function can’t handle 1537 degrees.  We’ve found a bug in our logic.   We go back to the original function and, after a little thought,  change it to the following:

public int simplifyAngle(int angle) {
    while (angle > 180) {
        angle = angle - 360;
    }
    while (angle < -180) {
        angle = angle + 360;
    }
    return angle;
}
Now our test passes.  The bug is fixed.

Refactoring

At some point, you or one of your teammates will rewrite parts of the robot code, at which point you must retest and verify that the new code is at least as good as the old.  For instance, someone might refactor the angle simplification like this:

public int simplifyAngle(int angle) {
    return angle > 180 
    ? simplifyAngle(angle - 360) 
    : angle < -180 ? simplifyAngle(angle + 360) : angle;
}

Does this function do the same job?  It turns out that it does. Is this function better? Well, it is shorter, but you should decide if it’s really more readable.

Eventually, you might stumble on logic like this:

public int simplifyAngle(int angle) {
    return  (int)Math.round(Math.IEEEremainder(angle,360.0));
}

This is even shorter.  It’s much more cryptic, but it does pass the tests.  You could use any of these functions in your robot.  Unit tests have verified that they all do the same thing.

Writing good tests

Now that you know how to create unit tests, start adding them to your robot projects. You will find that writing good tests is as difficult and subtle a skill as programming the robot code.  You should start watching for opportunities to test.  Break up your big methods into smaller methods and structure them so they are more amenable to testing.  Test the simple things, but especially watch for code that is tricky.

It’s probably possible to write too many tests, but don’t worry about that.  On professional projects the test suites are often larger than the baseline code.

Good unit tests should have the following qualities:

  1. Test the requirements and nothing but requirements.  In the above example we require that 270 degrees is simplified down to -90 degrees.  However, don’t try to craft tests that verify the number of times the “while” loop executes to achieve this.
  2. Tests should be deterministic and always succeed or fail based on the requirements.  Take care around code that depends on hardware or file systems or random functions or timers or large memory usage.  Structure your code so you can manage any randomness.
  3. Unit tests should be fast.  They execute before every build and you don’t want to start regretting how slow they are.
  4. Tests should be easy to read, understand, and maintain later

The above example is intentionally simple.  Once you’ve mastered the concepts you can start to think about automated testing of larger classes, non-trivial state machines,  subsystems and commands.

Further Reading