Rename our allwpilib (which is now 2020) to not have 2019 in the name
Change-Id: I3c07f85ed32ab8b97db765a9b43f2a6ce7da964a
diff --git a/wpilibjIntegrationTests/build.gradle b/wpilibjIntegrationTests/build.gradle
new file mode 100644
index 0000000..ec5714e
--- /dev/null
+++ b/wpilibjIntegrationTests/build.gradle
@@ -0,0 +1,49 @@
+plugins {
+ id 'java'
+ id 'application'
+}
+
+ext {
+ useJava = true
+ useCpp = false
+ skipDev = true
+}
+
+apply from: "${rootDir}/shared/opencv.gradle"
+
+mainClassName = 'edu.wpi.first.wpilibj.test.AntJunitLanucher'
+
+apply plugin: 'com.github.johnrengelman.shadow'
+
+repositories {
+ mavenCentral()
+}
+
+dependencies {
+ implementation project(':wpilibj')
+ implementation project(':hal')
+ implementation project(':wpiutil')
+ implementation project(':ntcore')
+ implementation project(':cscore')
+ implementation project(':cameraserver')
+ implementation 'junit:junit:4.11'
+ testImplementation 'org.hamcrest:hamcrest-all:1.3'
+ implementation 'com.googlecode.junit-toolbox:junit-toolbox:2.0'
+ implementation 'org.apache.ant:ant:1.9.4'
+ implementation 'org.apache.ant:ant-junit:1.9.4'
+}
+
+build.dependsOn shadowJar
+
+def testOutputFolder = file("${project(':').buildDir}/integrationTestFiles")
+
+task copyWpilibJIntegrationTestJarToOutput(type: Copy) {
+ destinationDir testOutputFolder
+ dependsOn shadowJar
+ inputs.file shadowJar.archivePath
+ from(shadowJar) {
+ into 'java'
+ }
+}
+
+build.dependsOn copyWpilibJIntegrationTestJarToOutput
diff --git a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/AbstractInterruptTest.java b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/AbstractInterruptTest.java
new file mode 100644
index 0000000..de54234
--- /dev/null
+++ b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/AbstractInterruptTest.java
@@ -0,0 +1,311 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project. */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import java.util.concurrent.atomic.AtomicBoolean;
+import java.util.concurrent.atomic.AtomicInteger;
+import java.util.concurrent.atomic.AtomicLong;
+
+import org.junit.After;
+import org.junit.Test;
+
+import edu.wpi.first.wpilibj.test.AbstractComsSetup;
+
+import static org.hamcrest.Matchers.both;
+import static org.hamcrest.Matchers.greaterThan;
+import static org.hamcrest.Matchers.lessThan;
+import static org.junit.Assert.assertEquals;
+import static org.junit.Assert.assertSame;
+import static org.junit.Assert.assertThat;
+
+/**
+ * This class should not be run as a test explicitly. Instead it should be extended by tests that
+ * use the InterruptableSensorBase.
+ */
+public abstract class AbstractInterruptTest extends AbstractComsSetup {
+ private InterruptableSensorBase m_interruptable = null;
+
+ private InterruptableSensorBase getInterruptable() {
+ if (m_interruptable == null) {
+ m_interruptable = giveInterruptableSensorBase();
+ }
+ return m_interruptable;
+ }
+
+
+ @After
+ public void interruptTeardown() {
+ if (m_interruptable != null) {
+ freeInterruptableSensorBase();
+ m_interruptable = null;
+ }
+ }
+
+ /**
+ * Give the interruptable sensor base that interrupts can be attached to.
+ */
+ abstract InterruptableSensorBase giveInterruptableSensorBase();
+
+ /**
+ * Cleans up the interruptable sensor base. This is only called if {@link
+ * #giveInterruptableSensorBase()} is called.
+ */
+ abstract void freeInterruptableSensorBase();
+
+ /**
+ * Perform whatever action is required to set the interrupt high.
+ */
+ abstract void setInterruptHigh();
+
+ /**
+ * Perform whatever action is required to set the interrupt low.
+ */
+ abstract void setInterruptLow();
+
+
+ private class InterruptCounter {
+ private final AtomicInteger m_count = new AtomicInteger();
+
+ void increment() {
+ m_count.addAndGet(1);
+ }
+
+ int getCount() {
+ return m_count.get();
+ }
+ }
+
+ private class TestInterruptHandlerFunction extends InterruptHandlerFunction<InterruptCounter> {
+ protected final AtomicBoolean m_exceptionThrown = new AtomicBoolean(false);
+ /**
+ * Stores the time that the interrupt fires.
+ */
+ final AtomicLong m_interruptFireTime = new AtomicLong();
+ /**
+ * Stores if the interrupt has completed at least once.
+ */
+ final AtomicBoolean m_interruptComplete = new AtomicBoolean(false);
+ protected Exception m_ex;
+ final InterruptCounter m_counter;
+
+ TestInterruptHandlerFunction(InterruptCounter counter) {
+ m_counter = counter;
+ }
+
+ @Override
+ public void interruptFired(int interruptAssertedMask, InterruptCounter param) {
+ m_interruptFireTime.set(RobotController.getFPGATime());
+ m_counter.increment();
+ try {
+ // This won't cause the test to fail
+ assertSame(m_counter, param);
+ } catch (Exception ex) {
+ // So we must throw the exception within the test
+ m_exceptionThrown.set(true);
+ m_ex = ex;
+ }
+ m_interruptComplete.set(true);
+ }
+
+ @Override
+ public InterruptCounter overridableParameter() {
+ return m_counter;
+ }
+ }
+
+ @Test(timeout = 1000)
+ public void testSingleInterruptsTriggering() throws Exception {
+ // Given
+ final InterruptCounter counter = new InterruptCounter();
+ TestInterruptHandlerFunction function = new TestInterruptHandlerFunction(counter);
+
+ // When
+ getInterruptable().requestInterrupts(function);
+ getInterruptable().enableInterrupts();
+
+ setInterruptLow();
+ Timer.delay(0.01);
+ // Note: Utility.getFPGATime() is used because double values can turn over
+ // after the robot has been running for a long time
+ final long interruptTriggerTime = RobotController.getFPGATime();
+ setInterruptHigh();
+
+ // Delay until the interrupt is complete
+ while (!function.m_interruptComplete.get()) {
+ Timer.delay(0.005);
+ }
+
+
+ // Then
+ assertEquals("The interrupt did not fire the expected number of times", 1, counter.getCount());
+ // If the test within the interrupt failed
+ if (function.m_exceptionThrown.get()) {
+ throw function.m_ex;
+ }
+ final long range = 10000; // in microseconds
+ assertThat(
+ "The interrupt did not fire within the expected time period (values in milliseconds)",
+ function.m_interruptFireTime.get(),
+ both(greaterThan(interruptTriggerTime - range)).and(lessThan(interruptTriggerTime
+ + range)));
+ assertThat(
+ "The readRisingTimestamp() did not return the correct value (values in seconds)",
+ getInterruptable().readRisingTimestamp(),
+ both(greaterThan((interruptTriggerTime - range) / 1e6)).and(
+ lessThan((interruptTriggerTime + range) / 1e6)));
+ }
+
+ @Test(timeout = 2000)
+ public void testMultipleInterruptsTriggering() {
+ // Given
+ final InterruptCounter counter = new InterruptCounter();
+ TestInterruptHandlerFunction function = new TestInterruptHandlerFunction(counter);
+
+ // When
+ getInterruptable().requestInterrupts(function);
+ getInterruptable().enableInterrupts();
+
+ final int fireCount = 50;
+ for (int i = 0; i < fireCount; i++) {
+ setInterruptLow();
+ setInterruptHigh();
+ // Wait for the interrupt to complete before moving on
+ while (!function.m_interruptComplete.getAndSet(false)) {
+ Timer.delay(0.005);
+ }
+ }
+ // Then
+ assertEquals("The interrupt did not fire the expected number of times", fireCount,
+ counter.getCount());
+ }
+
+ /**
+ * The timeout length for this test in seconds.
+ */
+ private static final int synchronousTimeout = 5;
+
+ @Test(timeout = (long) (synchronousTimeout * 1e3))
+ public void testSynchronousInterruptsTriggering() {
+ // Given
+ getInterruptable().requestInterrupts();
+
+ final double synchronousDelay = synchronousTimeout / 2.0;
+ final Runnable runnable = () -> {
+ Timer.delay(synchronousDelay);
+ setInterruptLow();
+ setInterruptHigh();
+ };
+
+ // When
+
+ // Note: the long time value is used because doubles can flip if the robot
+ // is left running for long enough
+ final long startTimeStamp = RobotController.getFPGATime();
+ new Thread(runnable).start();
+ // Delay for twice as long as the timeout so the test should fail first
+ getInterruptable().waitForInterrupt(synchronousTimeout * 2);
+ final long stopTimeStamp = RobotController.getFPGATime();
+
+ // Then
+ // The test will not have timed out and:
+ final double interruptRunTime = (stopTimeStamp - startTimeStamp) * 1e-6;
+ assertEquals("The interrupt did not run for the expected amount of time (units in seconds)",
+ synchronousDelay, interruptRunTime, 0.1);
+ }
+
+ @Test(timeout = (long) (synchronousTimeout * 1e3))
+ public void testSynchronousInterruptsWaitResultTimeout() {
+ // Given
+ getInterruptable().requestInterrupts();
+
+ //Don't fire interrupt. Expect it to timeout.
+ InterruptableSensorBase.WaitResult result = getInterruptable()
+ .waitForInterrupt(synchronousTimeout / 2);
+
+ assertEquals("The interrupt did not time out correctly.", result, InterruptableSensorBase
+ .WaitResult.kTimeout);
+ }
+
+ @Test(timeout = (long) (synchronousTimeout * 1e3))
+ public void testSynchronousInterruptsWaitResultRisingEdge() {
+ // Given
+ getInterruptable().requestInterrupts();
+
+ final double synchronousDelay = synchronousTimeout / 2.0;
+ final Runnable runnable = () -> {
+ Timer.delay(synchronousDelay);
+ setInterruptLow();
+ setInterruptHigh();
+ };
+
+ new Thread(runnable).start();
+ // Delay for twice as long as the timeout so the test should fail first
+ InterruptableSensorBase.WaitResult result = getInterruptable()
+ .waitForInterrupt(synchronousTimeout * 2);
+
+ assertEquals("The interrupt did not fire on the rising edge.", result,
+ InterruptableSensorBase.WaitResult.kRisingEdge);
+ }
+
+ @Test(timeout = (long) (synchronousTimeout * 1e3))
+ public void testSynchronousInterruptsWaitResultFallingEdge() {
+ // Given
+ getInterruptable().requestInterrupts();
+ getInterruptable().setUpSourceEdge(false, true);
+
+ final double synchronousDelay = synchronousTimeout / 2.0;
+ final Runnable runnable = () -> {
+ Timer.delay(synchronousDelay);
+ setInterruptHigh();
+ setInterruptLow();
+ };
+
+ new Thread(runnable).start();
+ // Delay for twice as long as the timeout so the test should fail first
+ InterruptableSensorBase.WaitResult result = getInterruptable()
+ .waitForInterrupt(synchronousTimeout * 2);
+
+ assertEquals("The interrupt did not fire on the falling edge.", result,
+ InterruptableSensorBase.WaitResult.kFallingEdge);
+ }
+
+
+ @Test(timeout = 4000)
+ public void testDisableStopsInterruptFiring() {
+ final InterruptCounter counter = new InterruptCounter();
+ TestInterruptHandlerFunction function = new TestInterruptHandlerFunction(counter);
+
+ // When
+ getInterruptable().requestInterrupts(function);
+ getInterruptable().enableInterrupts();
+
+ final int fireCount = 50;
+ for (int i = 0; i < fireCount; i++) {
+ setInterruptLow();
+ setInterruptHigh();
+ // Wait for the interrupt to complete before moving on
+ while (!function.m_interruptComplete.getAndSet(false)) {
+ Timer.delay(0.005);
+ }
+ }
+ getInterruptable().disableInterrupts();
+ // TestBench.out().println("Finished disabling the robot");
+
+ for (int i = 0; i < fireCount; i++) {
+ setInterruptLow();
+ setInterruptHigh();
+ // Just wait because the interrupt should not fire
+ Timer.delay(0.005);
+ }
+
+ // Then
+ assertEquals("The interrupt did not fire the expected number of times", fireCount,
+ counter.getCount());
+ }
+
+}
diff --git a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/AnalogCrossConnectTest.java b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/AnalogCrossConnectTest.java
new file mode 100644
index 0000000..14b7034
--- /dev/null
+++ b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/AnalogCrossConnectTest.java
@@ -0,0 +1,200 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project. */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import java.util.logging.Logger;
+
+import org.junit.AfterClass;
+import org.junit.Before;
+import org.junit.BeforeClass;
+import org.junit.Test;
+
+import edu.wpi.first.wpilibj.AnalogTriggerOutput.AnalogTriggerType;
+import edu.wpi.first.wpilibj.fixtures.AnalogCrossConnectFixture;
+import edu.wpi.first.wpilibj.test.TestBench;
+
+import static org.junit.Assert.assertEquals;
+import static org.junit.Assert.assertFalse;
+import static org.junit.Assert.assertTrue;
+
+/**
+ * Test that covers the {@link AnalogCrossConnectFixture}.
+ */
+public class AnalogCrossConnectTest extends AbstractInterruptTest {
+ private static final Logger logger = Logger.getLogger(AnalogCrossConnectTest.class.getName());
+
+ private static AnalogCrossConnectFixture analogIO;
+
+ static final double kDelayTime = 0.01;
+
+ @Override
+ protected Logger getClassLogger() {
+ return logger;
+ }
+
+
+ @BeforeClass
+ public static void setUpBeforeClass() {
+ analogIO = TestBench.getAnalogCrossConnectFixture();
+ }
+
+ @AfterClass
+ public static void tearDownAfterClass() {
+ analogIO.teardown();
+ analogIO = null;
+ }
+
+ @Before
+ public void setUp() {
+ analogIO.setup();
+ }
+
+
+ @Test
+ public void testAnalogOuput() {
+ for (int i = 0; i < 50; i++) {
+ analogIO.getOutput().setVoltage(i / 10.0);
+ Timer.delay(kDelayTime);
+ assertEquals(analogIO.getOutput().getVoltage(), analogIO.getInput().getVoltage(), 0.01);
+ }
+ }
+
+ @Test
+ public void testAnalogTriggerBelowWindow() {
+ // Given
+ AnalogTrigger trigger = new AnalogTrigger(analogIO.getInput());
+ trigger.setLimitsVoltage(2.0, 3.0);
+
+ // When the output voltage is than less the lower limit
+ analogIO.getOutput().setVoltage(1.0);
+ Timer.delay(kDelayTime);
+
+ // Then the analog trigger is not in the window and the trigger state is off
+ assertFalse("Analog trigger is in the window (2V, 3V)", trigger.getInWindow());
+ assertFalse("Analog trigger is on", trigger.getTriggerState());
+
+ trigger.close();
+ }
+
+ @Test
+ public void testAnalogTriggerInWindow() {
+ // Given
+ AnalogTrigger trigger = new AnalogTrigger(analogIO.getInput());
+ trigger.setLimitsVoltage(2.0, 3.0);
+
+ // When the output voltage is within the lower and upper limits
+ analogIO.getOutput().setVoltage(2.5f);
+ Timer.delay(kDelayTime);
+
+ // Then the analog trigger is in the window and the trigger state is off
+ assertTrue("Analog trigger is not in the window (2V, 3V)", trigger.getInWindow());
+ assertFalse("Analog trigger is on", trigger.getTriggerState());
+
+ trigger.close();
+ }
+
+ @Test
+ public void testAnalogTriggerAboveWindow() {
+ // Given
+ AnalogTrigger trigger = new AnalogTrigger(analogIO.getInput());
+ trigger.setLimitsVoltage(2.0, 3.0);
+
+ // When the output voltage is greater than the upper limit
+ analogIO.getOutput().setVoltage(4.0);
+ Timer.delay(kDelayTime);
+
+ // Then the analog trigger is not in the window and the trigger state is on
+ assertFalse("Analog trigger is in the window (2V, 3V)", trigger.getInWindow());
+ assertTrue("Analog trigger is not on", trigger.getTriggerState());
+
+ trigger.close();
+ }
+
+ @Test
+ public void testAnalogTriggerCounter() {
+ // Given
+ AnalogTrigger trigger = new AnalogTrigger(analogIO.getInput());
+ trigger.setLimitsVoltage(2.0, 3.0);
+ Counter counter = new Counter(trigger);
+
+ // When the analog output is turned low and high 50 times
+ for (int i = 0; i < 50; i++) {
+ analogIO.getOutput().setVoltage(1.0);
+ Timer.delay(kDelayTime);
+ analogIO.getOutput().setVoltage(4.0);
+ Timer.delay(kDelayTime);
+ }
+
+ // Then the counter should be at 50
+ assertEquals("Analog trigger counter did not count 50 ticks", 50, counter.get());
+
+ counter.close();
+ }
+
+ @Test(expected = RuntimeException.class)
+ public void testRuntimeExceptionOnInvalidAccumulatorPort() {
+ analogIO.getInput().getAccumulatorCount();
+ }
+
+ private AnalogTrigger m_interruptTrigger;
+ private AnalogTriggerOutput m_interruptTriggerOutput;
+
+ /*
+ * (non-Javadoc)
+ *
+ * @see
+ * edu.wpi.first.wpilibj.AbstractInterruptTest#giveInterruptableSensorBase()
+ */
+ @Override
+ InterruptableSensorBase giveInterruptableSensorBase() {
+ m_interruptTrigger = new AnalogTrigger(analogIO.getInput());
+ m_interruptTrigger.setLimitsVoltage(2.0, 3.0);
+ m_interruptTriggerOutput = new AnalogTriggerOutput(m_interruptTrigger,
+ AnalogTriggerType.kState);
+ return m_interruptTriggerOutput;
+ }
+
+
+ /*
+ * (non-Javadoc)
+ *
+ * @see
+ * edu.wpi.first.wpilibj.AbstractInterruptTest#freeInterruptableSensorBase()
+ */
+ @Override
+ void freeInterruptableSensorBase() {
+ m_interruptTriggerOutput.cancelInterrupts();
+ m_interruptTriggerOutput.close();
+ m_interruptTriggerOutput = null;
+ m_interruptTrigger.close();
+ m_interruptTrigger = null;
+ }
+
+
+ /*
+ * (non-Javadoc)
+ *
+ * @see edu.wpi.first.wpilibj.AbstractInterruptTest#setInterruptHigh()
+ */
+ @Override
+ void setInterruptHigh() {
+ analogIO.getOutput().setVoltage(4.0);
+ Timer.delay(kDelayTime);
+ }
+
+ /*
+ * (non-Javadoc)
+ *
+ * @see edu.wpi.first.wpilibj.AbstractInterruptTest#setInterruptLow()
+ */
+ @Override
+ void setInterruptLow() {
+ analogIO.getOutput().setVoltage(1.0);
+ Timer.delay(kDelayTime);
+ }
+}
diff --git a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/AnalogPotentiometerTest.java b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/AnalogPotentiometerTest.java
new file mode 100644
index 0000000..29ac6e4
--- /dev/null
+++ b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/AnalogPotentiometerTest.java
@@ -0,0 +1,70 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project. */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import java.util.logging.Logger;
+
+import org.junit.After;
+import org.junit.Before;
+import org.junit.Test;
+
+import edu.wpi.first.wpilibj.fixtures.AnalogCrossConnectFixture;
+import edu.wpi.first.wpilibj.mockhardware.FakePotentiometerSource;
+import edu.wpi.first.wpilibj.test.AbstractComsSetup;
+import edu.wpi.first.wpilibj.test.TestBench;
+
+import static org.junit.Assert.assertEquals;
+
+/**
+ * Tests the {@link AnalogPotentiometer}.
+ */
+public class AnalogPotentiometerTest extends AbstractComsSetup {
+ private static final Logger logger = Logger.getLogger(AnalogPotentiometerTest.class.getName());
+ private AnalogCrossConnectFixture m_analogIO;
+ private FakePotentiometerSource m_potSource;
+ private AnalogPotentiometer m_pot;
+
+ private static final double DOUBLE_COMPARISON_DELTA = 2.0;
+
+ @Before
+ public void setUp() {
+ m_analogIO = TestBench.getAnalogCrossConnectFixture();
+ m_potSource = new FakePotentiometerSource(m_analogIO.getOutput(), 360);
+ m_pot = new AnalogPotentiometer(m_analogIO.getInput(), 360.0, 0);
+
+ }
+
+ @After
+ public void tearDown() {
+ m_potSource.reset();
+ m_pot.close();
+ m_analogIO.teardown();
+ }
+
+ @Override
+ protected Logger getClassLogger() {
+ return logger;
+ }
+
+ @Test
+ public void testInitialSettings() {
+ assertEquals(0, m_pot.get(), DOUBLE_COMPARISON_DELTA);
+ }
+
+ @Test
+ public void testRangeValues() {
+ for (double i = 0.0; i < 360.0; i = i + 1.0) {
+ m_potSource.setAngle(i);
+ m_potSource.setMaxVoltage(RobotController.getVoltage5V());
+ Timer.delay(0.02);
+ assertEquals(i, m_pot.get(), DOUBLE_COMPARISON_DELTA);
+ }
+ }
+
+
+}
diff --git a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/BuiltInAccelerometerTest.java b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/BuiltInAccelerometerTest.java
new file mode 100644
index 0000000..dbfddfa
--- /dev/null
+++ b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/BuiltInAccelerometerTest.java
@@ -0,0 +1,69 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2014-2018 FIRST. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project. */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import java.util.Arrays;
+import java.util.Collection;
+import java.util.logging.Logger;
+
+import org.junit.BeforeClass;
+import org.junit.Test;
+import org.junit.runner.RunWith;
+import org.junit.runners.Parameterized;
+import org.junit.runners.Parameterized.Parameters;
+
+import edu.wpi.first.wpilibj.interfaces.Accelerometer;
+import edu.wpi.first.wpilibj.test.AbstractComsSetup;
+
+import static org.junit.Assert.assertEquals;
+
+@RunWith(Parameterized.class)
+public class BuiltInAccelerometerTest extends AbstractComsSetup {
+ private static final Logger logger = Logger.getLogger(BuiltInAccelerometerTest.class.getName());
+ private static final double kAccelerationTolerance = 0.1;
+ private final BuiltInAccelerometer m_accelerometer;
+
+ public BuiltInAccelerometerTest(Accelerometer.Range range) {
+ m_accelerometer = new BuiltInAccelerometer(range);
+ }
+
+ @BeforeClass
+ public static void waitASecond() {
+ /*
+ * The testbench sometimes shakes a little from a previous test. Give it
+ * some time.
+ */
+ Timer.delay(1.0);
+ }
+
+ /**
+ * Test with all valid ranges to make sure unpacking is always done correctly.
+ */
+ @Parameters
+ public static Collection<Accelerometer.Range[]> generateData() {
+ return Arrays.asList(new Accelerometer.Range[][]{{Accelerometer.Range.k2G},
+ {Accelerometer.Range.k4G}, {Accelerometer.Range.k8G}});
+ }
+
+ @Override
+ protected Logger getClassLogger() {
+ return logger;
+ }
+
+ /**
+ * There's not much we can automatically test with the on-board accelerometer, but checking for
+ * gravity is probably good enough to tell that it's working.
+ */
+ @Test
+ public void testAccelerometer() {
+ assertEquals(0.0, m_accelerometer.getX(), kAccelerationTolerance);
+ assertEquals(1.0, m_accelerometer.getY(), kAccelerationTolerance);
+ assertEquals(0.0, m_accelerometer.getZ(), kAccelerationTolerance);
+ }
+
+}
diff --git a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/ConstantsPortsTest.java b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/ConstantsPortsTest.java
new file mode 100644
index 0000000..aae1661
--- /dev/null
+++ b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/ConstantsPortsTest.java
@@ -0,0 +1,100 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2018 FIRST. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project. */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import java.util.logging.Logger;
+
+import org.junit.Test;
+
+import edu.wpi.first.wpilibj.test.AbstractComsSetup;
+
+import static org.junit.Assert.assertEquals;
+
+/**
+ * Tests for checking our constant and port values.
+ */
+public class ConstantsPortsTest extends AbstractComsSetup {
+ private static final Logger logger = Logger.getLogger(ConstantsPortsTest.class.getName());
+
+ @Override
+ protected Logger getClassLogger() {
+ return logger;
+ }
+
+ /**
+ * kDigitalChannels.
+ */
+ @Test
+ public void testDigitalChannels() {
+ assertEquals(31, SensorUtil.kDigitalChannels);
+ }
+
+ /**
+ * kAnalogInputChannels.
+ */
+ @Test
+ public void testAnalogInputChannels() {
+ assertEquals(8, SensorUtil.kAnalogInputChannels);
+ }
+
+ /**
+ * kAnalogOutputChannels.
+ */
+ @Test
+ public void testAnalogOutputChannels() {
+ assertEquals(2, SensorUtil.kAnalogOutputChannels);
+ }
+
+ /**
+ * kSolenoidChannels.
+ */
+ @Test
+ public void testSolenoidChannels() {
+ assertEquals(8, SensorUtil.kSolenoidChannels);
+ }
+
+ /**
+ * kPwmChannels.
+ */
+ @Test
+ public void testPwmChannels() {
+ assertEquals(20, SensorUtil.kPwmChannels);
+ }
+
+ /**
+ * kRelayChannels.
+ */
+ @Test
+ public void testRelayChannels() {
+ assertEquals(4, SensorUtil.kRelayChannels);
+ }
+
+ /**
+ * kPDPChannels.
+ */
+ @Test
+ public void testPDPChannels() {
+ assertEquals(16, SensorUtil.kPDPChannels);
+ }
+
+ /**
+ * kPDPModules.
+ */
+ @Test
+ public void testPDPModules() {
+ assertEquals(63, SensorUtil.kPDPModules);
+ }
+
+ /**
+ * kPCMModules.
+ */
+ @Test
+ public void testPCMModules() {
+ assertEquals(63, SensorUtil.kPCMModules);
+ }
+}
diff --git a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/CounterTest.java b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/CounterTest.java
new file mode 100644
index 0000000..f6e3326
--- /dev/null
+++ b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/CounterTest.java
@@ -0,0 +1,115 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project. */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import java.util.Collection;
+import java.util.logging.Logger;
+
+import org.junit.AfterClass;
+import org.junit.Before;
+import org.junit.BeforeClass;
+import org.junit.Test;
+import org.junit.runner.RunWith;
+import org.junit.runners.Parameterized;
+import org.junit.runners.Parameterized.Parameters;
+
+import edu.wpi.first.wpilibj.fixtures.FakeCounterFixture;
+import edu.wpi.first.wpilibj.test.AbstractComsSetup;
+import edu.wpi.first.wpilibj.test.TestBench;
+
+import static org.junit.Assert.assertEquals;
+import static org.junit.Assert.assertTrue;
+
+/**
+ * Tests to see if the Counter is working properly.
+ */
+@RunWith(Parameterized.class)
+public class CounterTest extends AbstractComsSetup {
+ private static FakeCounterFixture counter = null;
+ private static final Logger logger = Logger.getLogger(CounterTest.class.getName());
+
+ Integer m_input;
+ Integer m_output;
+
+ @Override
+ protected Logger getClassLogger() {
+ return logger;
+ }
+
+ /**
+ * Constructs a Counter Test with the given inputs.
+ *
+ * @param input The input Port
+ * @param output The output Port
+ */
+ public CounterTest(Integer input, Integer output) {
+ assert input != null;
+ assert output != null;
+
+ m_input = input;
+ m_output = output;
+ // System.out.println("Counter Test: Input: " + input + " Output: " +
+ // output);
+ if (counter != null) {
+ counter.teardown();
+ }
+ counter = new FakeCounterFixture(input, output);
+ }
+
+ /**
+ * Test data generator. This method is called the the JUnit parameterized test runner and returns
+ * a Collection of Arrays. For each Array in the Collection, each array element corresponds to a
+ * parameter in the constructor.
+ */
+ @Parameters
+ public static Collection<Integer[]> generateData() {
+ // In this example, the parameter generator returns a List of
+ // arrays. Each array has two elements: { Digital input port, Digital output
+ // port}.
+ // These data are hard-coded into the class, but they could be
+ // generated or loaded in any way you like.
+ return TestBench.getInstance().getDIOCrossConnectCollection();
+ }
+
+
+ @BeforeClass
+ public static void setUpBeforeClass() {
+ }
+
+ @AfterClass
+ public static void tearDownAfterClass() {
+ counter.teardown();
+ counter = null;
+ }
+
+ @Before
+ public void setUp() {
+ counter.setup();
+ }
+
+ /**
+ * Tests the default state of the counter immediately after reset.
+ */
+ @Test
+ public void testDefault() {
+ assertEquals("Counter did not reset to 0", 0, counter.getCounter().get());
+ }
+
+ @Test(timeout = 5000)
+ public void testCount() {
+ final int goal = 100;
+ counter.getFakeCounterSource().setCount(goal);
+ counter.getFakeCounterSource().execute();
+
+ final int count = counter.getCounter().get();
+
+ assertTrue("Fake Counter, Input: " + m_input + ", Output: " + m_output + ", did not return "
+ + goal + " instead got: " + count, count == goal);
+ }
+
+}
diff --git a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/DIOCrossConnectTest.java b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/DIOCrossConnectTest.java
new file mode 100644
index 0000000..14eed0c
--- /dev/null
+++ b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/DIOCrossConnectTest.java
@@ -0,0 +1,196 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project. */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import java.util.Collection;
+import java.util.logging.Logger;
+
+import org.junit.After;
+import org.junit.AfterClass;
+import org.junit.Test;
+import org.junit.runner.RunWith;
+import org.junit.runners.Parameterized;
+import org.junit.runners.Parameterized.Parameters;
+
+import edu.wpi.first.wpilibj.fixtures.DIOCrossConnectFixture;
+import edu.wpi.first.wpilibj.test.TestBench;
+
+import static org.junit.Assert.assertFalse;
+import static org.junit.Assert.assertTrue;
+
+/**
+ * Tests to see if the Digital ports are working properly.
+ */
+@RunWith(Parameterized.class)
+public class DIOCrossConnectTest extends AbstractInterruptTest {
+ private static final Logger logger = Logger.getLogger(DIOCrossConnectTest.class.getName());
+
+ private static DIOCrossConnectFixture dio = null;
+
+ @Override
+ protected Logger getClassLogger() {
+ return logger;
+ }
+
+ /**
+ * Default constructor for the DIOCrossConnectTest This test is parameterized in order to allow it
+ * to be tested using a variety of different input/output pairs without duplicate code.<br> This
+ * class takes Integer port values instead of DigitalClasses because it would force them to be
+ * instantiated at the same time which could (untested) cause port binding errors.
+ *
+ * @param input The port for the input wire
+ * @param output The port for the output wire
+ */
+ public DIOCrossConnectTest(Integer input, Integer output) {
+ if (dio != null) {
+ dio.teardown();
+ }
+ dio = new DIOCrossConnectFixture(input, output);
+ }
+
+
+ /**
+ * Test data generator. This method is called the the JUnit parameterized test runner and returns
+ * a Collection of Arrays. For each Array in the Collection, each array element corresponds to a
+ * parameter in the constructor.
+ */
+ @Parameters(name = "{index}: Input Port: {0} Output Port: {1}")
+ public static Collection<Integer[]> generateData() {
+ // In this example, the parameter generator returns a List of
+ // arrays. Each array has two elements: { Digital input port, Digital output
+ // port}.
+ // These data are hard-coded into the class, but they could be
+ // generated or loaded in any way you like.
+ return TestBench.getInstance().getDIOCrossConnectCollection();
+ }
+
+ @AfterClass
+ public static void tearDownAfterClass() {
+ dio.teardown();
+ dio = null;
+ }
+
+ @After
+ public void tearDown() {
+ dio.reset();
+ }
+
+ /**
+ * Tests to see if the DIO can create and recognize a high value.
+ */
+ @Test
+ public void testSetHigh() {
+ dio.getOutput().set(true);
+ assertTrue("DIO Not High after no delay", dio.getInput().get());
+ Timer.delay(0.02);
+ assertTrue("DIO Not High after .05s delay", dio.getInput().get());
+ }
+
+ /**
+ * Tests to see if the DIO can create and recognize a low value.
+ */
+ @Test
+ public void testSetLow() {
+ dio.getOutput().set(false);
+ assertFalse("DIO Not Low after no delay", dio.getInput().get());
+ Timer.delay(0.02);
+ assertFalse("DIO Not Low after .05s delay", dio.getInput().get());
+ }
+
+ /**
+ * Tests to see if the DIO PWM functionality works.
+ */
+ @Test
+ public void testDIOpulseWidthModulation() {
+ dio.getOutput().set(false);
+ assertFalse("DIO Not Low after no delay", dio.getInput().get());
+ //Set frequency to 2.0 Hz
+ dio.getOutput().setPWMRate(2.0);
+ //Enable PWM, but leave it off.
+ dio.getOutput().enablePWM(0.0);
+ Timer.delay(0.5);
+ dio.getOutput().updateDutyCycle(0.5);
+ dio.getInput().requestInterrupts();
+ dio.getInput().setUpSourceEdge(false, true);
+ //TODO: Add return value from WaitForInterrupt
+ dio.getInput().waitForInterrupt(3.0, true);
+ Timer.delay(0.5);
+ final boolean firstCycle = dio.getInput().get();
+ Timer.delay(0.5);
+ final boolean secondCycle = dio.getInput().get();
+ Timer.delay(0.5);
+ final boolean thirdCycle = dio.getInput().get();
+ Timer.delay(0.5);
+ final boolean forthCycle = dio.getInput().get();
+ Timer.delay(0.5);
+ final boolean fifthCycle = dio.getInput().get();
+ Timer.delay(0.5);
+ final boolean sixthCycle = dio.getInput().get();
+ Timer.delay(0.5);
+ final boolean seventhCycle = dio.getInput().get();
+ dio.getOutput().disablePWM();
+ Timer.delay(0.5);
+ final boolean firstAfterStop = dio.getInput().get();
+ Timer.delay(0.5);
+ final boolean secondAfterStop = dio.getInput().get();
+
+ assertFalse("DIO Not Low after first delay", firstCycle);
+ assertTrue("DIO Not High after second delay", secondCycle);
+ assertFalse("DIO Not Low after third delay", thirdCycle);
+ assertTrue("DIO Not High after forth delay", forthCycle);
+ assertFalse("DIO Not Low after fifth delay", fifthCycle);
+ assertTrue("DIO Not High after sixth delay", sixthCycle);
+ assertFalse("DIO Not Low after seventh delay", seventhCycle);
+ assertFalse("DIO Not Low after stopping first read", firstAfterStop);
+ assertFalse("DIO Not Low after stopping second read", secondAfterStop);
+ }
+
+ /*
+ * (non-Javadoc)
+ *
+ * @see
+ * edu.wpi.first.wpilibj.AbstractInterruptTest#giveInterruptableSensorBase()
+ */
+ @Override
+ InterruptableSensorBase giveInterruptableSensorBase() {
+ return dio.getInput();
+ }
+
+ /*
+ * (non-Javadoc)
+ *
+ * @see
+ * edu.wpi.first.wpilibj.AbstractInterruptTest#freeInterruptableSensorBase()
+ */
+ @Override
+ void freeInterruptableSensorBase() {
+ // Handled in the fixture
+ }
+
+ /*
+ * (non-Javadoc)
+ *
+ * @see edu.wpi.first.wpilibj.AbstractInterruptTest#setInterruptHigh()
+ */
+ @Override
+ void setInterruptHigh() {
+ dio.getOutput().set(true);
+ }
+
+ /*
+ * (non-Javadoc)
+ *
+ * @see edu.wpi.first.wpilibj.AbstractInterruptTest#setInterruptLow()
+ */
+ @Override
+ void setInterruptLow() {
+ dio.getOutput().set(false);
+
+ }
+
+}
diff --git a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/DigitalGlitchFilterTest.java b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/DigitalGlitchFilterTest.java
new file mode 100644
index 0000000..821f5cc
--- /dev/null
+++ b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/DigitalGlitchFilterTest.java
@@ -0,0 +1,83 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2018 FIRST. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project. */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import java.util.logging.Logger;
+
+import org.junit.Test;
+
+import edu.wpi.first.wpilibj.test.AbstractComsSetup;
+
+import static org.junit.Assert.assertEquals;
+
+/**
+ * Test for the DigitalGlitchFilter class.
+ */
+public class DigitalGlitchFilterTest extends AbstractComsSetup {
+ private static final Logger logger = Logger.getLogger(
+ DigitalGlitchFilterTest.class.getName());
+
+ @Override
+ protected Logger getClassLogger() {
+ return logger;
+ }
+
+ /**
+ * This is a test to make sure that filters can be created and are consistent. This assumes that
+ * the FPGA implementation to actually implement the filter has been tested. It does validate
+ * that we are successfully able to set and get the active filters for ports and makes sure that
+ * the FPGA filter is changed correctly, and does the same for the period.
+ */
+ @Test
+ public void testDigitalGlitchFilterBasic() {
+ final DigitalInput input1 = new DigitalInput(1);
+ final DigitalInput input2 = new DigitalInput(2);
+ final DigitalInput input3 = new DigitalInput(3);
+ final DigitalInput input4 = new DigitalInput(4);
+ final Encoder encoder5 = new Encoder(5, 6);
+ final Counter counter7 = new Counter(7);
+
+ final DigitalGlitchFilter filter1 = new DigitalGlitchFilter();
+ filter1.add(input1);
+ filter1.setPeriodNanoSeconds(4200);
+
+ final DigitalGlitchFilter filter2 = new DigitalGlitchFilter();
+ filter2.add(input2);
+ filter2.add(input3);
+ filter2.setPeriodNanoSeconds(97100);
+
+ final DigitalGlitchFilter filter3 = new DigitalGlitchFilter();
+ filter3.add(input4);
+ filter3.add(encoder5);
+ filter3.add(counter7);
+ filter3.setPeriodNanoSeconds(167800);
+
+ assertEquals(4200, filter1.getPeriodNanoSeconds());
+ assertEquals(97100, filter2.getPeriodNanoSeconds());
+ assertEquals(167800, filter3.getPeriodNanoSeconds());
+
+ filter1.remove(input1);
+
+ filter2.remove(input2);
+ filter2.remove(input3);
+
+ filter3.remove(input4);
+ filter3.remove(encoder5);
+ filter3.remove(counter7);
+
+ input1.close();
+ input2.close();
+ input3.close();
+ input4.close();
+ encoder5.close();
+ counter7.close();
+ filter1.close();
+ filter2.close();
+ filter3.close();
+ }
+}
diff --git a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/DriverStationTest.java b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/DriverStationTest.java
new file mode 100644
index 0000000..301a7ee
--- /dev/null
+++ b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/DriverStationTest.java
@@ -0,0 +1,44 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2018 FIRST. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project. */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import java.util.logging.Logger;
+
+import org.junit.Test;
+
+import edu.wpi.first.wpilibj.test.AbstractComsSetup;
+
+import static org.junit.Assert.assertEquals;
+
+
+public class DriverStationTest extends AbstractComsSetup {
+ private static final Logger logger = Logger.getLogger(TimerTest.class.getName());
+ private static final double TIMER_TOLERANCE = 0.2;
+ private static final long TIMER_RUNTIME = 1000000; // 1 second
+
+ @Override
+ protected Logger getClassLogger() {
+ return logger;
+ }
+
+ @Test
+ public void waitForDataTest() {
+ long startTime = RobotController.getFPGATime();
+
+ // Wait for data 50 times
+ for (int i = 0; i < 50; i++) {
+ DriverStation.getInstance().waitForData();
+ }
+ long endTime = RobotController.getFPGATime();
+ long difference = endTime - startTime;
+
+ assertEquals("DriverStation waitForData did not wait long enough", TIMER_RUNTIME, difference,
+ TIMER_TOLERANCE * TIMER_RUNTIME);
+ }
+
+}
diff --git a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/EncoderTest.java b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/EncoderTest.java
new file mode 100644
index 0000000..3a639ab
--- /dev/null
+++ b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/EncoderTest.java
@@ -0,0 +1,149 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project. */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import java.util.Collection;
+import java.util.logging.Logger;
+
+import org.junit.After;
+import org.junit.AfterClass;
+import org.junit.Before;
+import org.junit.Test;
+import org.junit.runner.RunWith;
+import org.junit.runners.Parameterized;
+import org.junit.runners.Parameterized.Parameters;
+
+import edu.wpi.first.wpilibj.fixtures.FakeEncoderFixture;
+import edu.wpi.first.wpilibj.test.AbstractComsSetup;
+import edu.wpi.first.wpilibj.test.TestBench;
+
+import static org.junit.Assert.assertTrue;
+
+
+/**
+ * Test to see if the FPGA properly recognizes a mock Encoder input.
+ */
+@RunWith(Parameterized.class)
+public class EncoderTest extends AbstractComsSetup {
+ private static final Logger logger = Logger.getLogger(EncoderTest.class.getName());
+ private static FakeEncoderFixture encoder = null;
+
+ private final boolean m_flip; // Does this test need to flip the inputs
+ private final int m_inputA;
+ private final int m_inputB;
+ private final int m_outputA;
+ private final int m_outputB;
+
+ @Override
+ protected Logger getClassLogger() {
+ return logger;
+ }
+
+ /**
+ * Test data generator. This method is called the the JUnit parametrized test runner and returns
+ * a Collection of Arrays. For each Array in the Collection, each array element corresponds to a
+ * parameter in the constructor.
+ */
+ @Parameters
+ public static Collection<Integer[]> generateData() {
+ return TestBench.getInstance().getEncoderDIOCrossConnectCollection();
+ }
+
+ /**
+ * Constructs a parametrized Encoder Test.
+ *
+ * @param inputA The port number for inputA
+ * @param outputA The port number for outputA
+ * @param inputB The port number for inputB
+ * @param outputB The port number for outputB
+ * @param flip whether or not these set of values require the encoder to be reversed (0 or 1)
+ */
+ public EncoderTest(int inputA, int outputA, int inputB, int outputB, int flip) {
+ m_inputA = inputA;
+ m_inputB = inputB;
+ m_outputA = outputA;
+ m_outputB = outputB;
+
+ // If the encoder from a previous test is allocated then we must free its
+ // members
+ if (encoder != null) {
+ encoder.teardown();
+ }
+ m_flip = flip == 0;
+ encoder = new FakeEncoderFixture(inputA, outputA, inputB, outputB);
+ }
+
+ @AfterClass
+ public static void tearDownAfterClass() {
+ encoder.teardown();
+ encoder = null;
+ }
+
+ /**
+ * Sets up the test and verifies that the test was reset to the default state.
+ */
+ @Before
+ public void setUp() {
+ encoder.setup();
+ testDefaultState();
+ }
+
+ @After
+ public void tearDown() {
+ encoder.reset();
+ }
+
+ /**
+ * Tests to see if Encoders initialize to zero.
+ */
+ @Test
+ public void testDefaultState() {
+ int value = encoder.getEncoder().get();
+ assertTrue(errorMessage(0, value), value == 0);
+ }
+
+ /**
+ * Tests to see if Encoders can count up successfully.
+ */
+ @Test
+ public void testCountUp() {
+ int goal = 100;
+ encoder.getFakeEncoderSource().setCount(goal);
+ encoder.getFakeEncoderSource().setForward(m_flip);
+ encoder.getFakeEncoderSource().execute();
+ int value = encoder.getEncoder().get();
+ assertTrue(errorMessage(goal, value), value == goal);
+
+ }
+
+ /**
+ * Tests to see if Encoders can count down successfully.
+ */
+ @Test
+ public void testCountDown() {
+ int goal = -100;
+ encoder.getFakeEncoderSource().setCount(goal); // Goal has to be positive
+ encoder.getFakeEncoderSource().setForward(!m_flip);
+ encoder.getFakeEncoderSource().execute();
+ int value = encoder.getEncoder().get();
+ assertTrue(errorMessage(goal, value), value == goal);
+
+ }
+
+ /**
+ * Creates a simple message with the error that was encountered for the Encoders.
+ *
+ * @param goal The goal that was trying to be reached
+ * @param trueValue The actual value that was reached by the test
+ * @return A fully constructed message with data about where and why the the test failed.
+ */
+ private String errorMessage(int goal, int trueValue) {
+ return "Encoder ({In,Out}): {" + m_inputA + ", " + m_outputA + "},{" + m_inputB + ", "
+ + m_outputB + "} Returned: " + trueValue + ", Wanted: " + goal;
+ }
+}
diff --git a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/GyroTest.java b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/GyroTest.java
new file mode 100644
index 0000000..1fc828c
--- /dev/null
+++ b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/GyroTest.java
@@ -0,0 +1,129 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project. */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import java.util.logging.Logger;
+
+import org.junit.After;
+import org.junit.Before;
+import org.junit.Test;
+
+import edu.wpi.first.wpilibj.fixtures.TiltPanCameraFixture;
+import edu.wpi.first.wpilibj.test.AbstractComsSetup;
+import edu.wpi.first.wpilibj.test.TestBench;
+
+import static org.junit.Assert.assertEquals;
+
+/**
+ * Tests that the {@link TiltPanCameraFixture}.
+ */
+public class GyroTest extends AbstractComsSetup {
+ private static final Logger logger = Logger.getLogger(GyroTest.class.getName());
+
+ public static final double TEST_ANGLE = 90.0;
+
+ private TiltPanCameraFixture m_tpcam;
+
+ @Override
+ protected Logger getClassLogger() {
+ return logger;
+ }
+
+ @Before
+ public void setUp() {
+ logger.fine("Setup: TiltPan camera");
+ m_tpcam = TestBench.getInstance().getTiltPanCam();
+ m_tpcam.setup();
+ }
+
+ @After
+ public void tearDown() {
+ m_tpcam.teardown();
+ }
+
+ @Test
+ public void testAllGyroTests() {
+ testInitial(m_tpcam.getGyro());
+ testDeviationOverTime(m_tpcam.getGyro());
+ testGyroAngle(m_tpcam.getGyro());
+ testGyroAngleCalibratedParameters();
+ }
+
+ public void testInitial(AnalogGyro gyro) {
+ double angle = gyro.getAngle();
+ assertEquals(errorMessage(angle, 0), 0, angle, 0.5);
+ }
+
+ /**
+ * Test to see if the Servo and the gyroscope is turning 90 degrees Note servo on TestBench is not
+ * the same type of servo that servo class was designed for so setAngle is significantly off. This
+ * has been calibrated for the servo on the rig.
+ */
+ public void testGyroAngle(AnalogGyro gyro) {
+ // Set angle
+ for (int i = 0; i < 5; i++) {
+ m_tpcam.getPan().set(0);
+ Timer.delay(0.1);
+ }
+
+ Timer.delay(0.5);
+ // Reset for setup
+ gyro.reset();
+ Timer.delay(0.5);
+
+ // Perform test
+ for (int i = 0; i < 53; i++) {
+ m_tpcam.getPan().set(i / 100.0);
+ Timer.delay(0.05);
+ }
+ Timer.delay(1.2);
+
+ double angle = gyro.getAngle();
+
+ double difference = TEST_ANGLE - angle;
+
+ double diff = Math.abs(difference);
+
+ assertEquals(errorMessage(diff, TEST_ANGLE), TEST_ANGLE, angle, 10);
+ }
+
+
+ protected void testDeviationOverTime(AnalogGyro gyro) {
+ // Make sure that the test isn't influenced by any previous motions.
+ Timer.delay(0.5);
+ gyro.reset();
+ Timer.delay(0.25);
+ double angle = gyro.getAngle();
+ assertEquals(errorMessage(angle, 0), 0, angle, 0.5);
+ Timer.delay(5);
+ angle = gyro.getAngle();
+ assertEquals("After 5 seconds " + errorMessage(angle, 0), 0, angle, 2.0);
+ }
+
+ /**
+ * Gets calibrated parameters from already calibrated gyro, allocates a new gyro with the center
+ * and offset parameters, and re-runs the test.
+ */
+ public void testGyroAngleCalibratedParameters() {
+ // Get calibrated parameters to make new Gyro with parameters
+ final double calibratedOffset = m_tpcam.getGyro().getOffset();
+ final int calibratedCenter = m_tpcam.getGyro().getCenter();
+ m_tpcam.freeGyro();
+ m_tpcam.setupGyroParam(calibratedCenter, calibratedOffset);
+ Timer.delay(TiltPanCameraFixture.RESET_TIME);
+ // Repeat tests
+ testInitial(m_tpcam.getGyroParam());
+ testDeviationOverTime(m_tpcam.getGyroParam());
+ testGyroAngle(m_tpcam.getGyroParam());
+ }
+
+ private String errorMessage(double difference, double target) {
+ return "Gyro angle skewed " + difference + " deg away from target " + target;
+ }
+
+}
diff --git a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/MockDS.java b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/MockDS.java
new file mode 100644
index 0000000..0998ee9
--- /dev/null
+++ b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/MockDS.java
@@ -0,0 +1,84 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-2018 FIRST. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project. */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import java.io.IOException;
+import java.net.DatagramPacket;
+import java.net.DatagramSocket;
+import java.net.InetSocketAddress;
+import java.net.SocketException;
+
+public class MockDS {
+ private Thread m_thread;
+
+ private void generateEnabledDsPacket(byte[] data, short sendCount) {
+ data[0] = (byte) (sendCount >> 8);
+ data[1] = (byte) sendCount;
+ data[2] = 0x01; // general data tag
+ data[3] = 0x04; // teleop enabled
+ data[4] = 0x10; // normal data request
+ data[5] = 0x00; // red 1 station
+ }
+
+ @SuppressWarnings("JavadocMethod")
+ public void start() {
+ m_thread = new Thread(() -> {
+ DatagramSocket socket;
+ try {
+ socket = new DatagramSocket();
+ } catch (SocketException e1) {
+ // TODO Auto-generated catch block
+ e1.printStackTrace();
+ return;
+ }
+ InetSocketAddress addr = new InetSocketAddress("127.0.0.1", 1110);
+ byte[] sendData = new byte[6];
+ DatagramPacket packet = new DatagramPacket(sendData, 0, 6, addr);
+ short sendCount = 0;
+ int initCount = 0;
+ while (!Thread.currentThread().isInterrupted()) {
+ try {
+ Thread.sleep(20);
+ generateEnabledDsPacket(sendData, sendCount++);
+ // ~50 disabled packets are required to make the robot actually enable
+ // 1 is definitely not enough.
+ if (initCount < 50) {
+ initCount++;
+ sendData[3] = 0;
+ }
+ packet.setData(sendData);
+ socket.send(packet);
+ } catch (InterruptedException ex) {
+ Thread.currentThread().interrupt();
+ } catch (IOException ex) {
+ // TODO Auto-generated catch block
+ ex.printStackTrace();
+ }
+ }
+ socket.close();
+ });
+ // Because of the test setup in Java, this thread will not be stopped
+ // So it must be a daemon thread
+ m_thread.setDaemon(true);
+ m_thread.start();
+ }
+
+ @SuppressWarnings("JavadocMethod")
+ public void stop() {
+ if (m_thread == null) {
+ return;
+ }
+ m_thread.interrupt();
+ try {
+ m_thread.join(1000);
+ } catch (InterruptedException ex) {
+ // TODO Auto-generated catch block
+ ex.printStackTrace();
+ }
+ }
+}
diff --git a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/MockSpeedController.java b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/MockSpeedController.java
new file mode 100644
index 0000000..d183723
--- /dev/null
+++ b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/MockSpeedController.java
@@ -0,0 +1,48 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-2018 FIRST. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project. */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+public class MockSpeedController implements SpeedController {
+ private double m_speed;
+ private boolean m_isInverted;
+
+ @Override
+ public void set(double speed) {
+ m_speed = m_isInverted ? -speed : speed;
+ }
+
+ @Override
+ public double get() {
+ return m_speed;
+ }
+
+ @Override
+ public void setInverted(boolean isInverted) {
+ m_isInverted = isInverted;
+ }
+
+ @Override
+ public boolean getInverted() {
+ return m_isInverted;
+ }
+
+ @Override
+ public void disable() {
+ m_speed = 0;
+ }
+
+ @Override
+ public void stopMotor() {
+ disable();
+ }
+
+ @Override
+ public void pidWrite(double output) {
+ set(output);
+ }
+}
diff --git a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/MotorEncoderTest.java b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/MotorEncoderTest.java
new file mode 100644
index 0000000..7fcd01f
--- /dev/null
+++ b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/MotorEncoderTest.java
@@ -0,0 +1,243 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project. */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import java.util.Arrays;
+import java.util.Collection;
+import java.util.logging.Logger;
+
+import org.junit.After;
+import org.junit.AfterClass;
+import org.junit.Before;
+import org.junit.Test;
+import org.junit.runner.RunWith;
+import org.junit.runners.Parameterized;
+import org.junit.runners.Parameterized.Parameters;
+
+import edu.wpi.first.wpilibj.controller.PIDController;
+import edu.wpi.first.wpilibj.fixtures.MotorEncoderFixture;
+import edu.wpi.first.wpilibj.test.AbstractComsSetup;
+import edu.wpi.first.wpilibj.test.TestBench;
+import edu.wpi.first.wpiutil.math.MathUtil;
+
+import static org.junit.Assert.assertEquals;
+import static org.junit.Assert.assertFalse;
+import static org.junit.Assert.assertTrue;
+
+
+@RunWith(Parameterized.class)
+public class MotorEncoderTest extends AbstractComsSetup {
+ private static final Logger logger = Logger.getLogger(MotorEncoderTest.class.getName());
+
+ private static final double MOTOR_RUNTIME = 0.25;
+
+ // private static final List<MotorEncoderFixture> pairs = new
+ // ArrayList<MotorEncoderFixture>();
+ private static MotorEncoderFixture<?> me = null;
+
+ @Override
+ protected Logger getClassLogger() {
+ return logger;
+ }
+
+ /**
+ * Constructs the test.
+ *
+ * @param mef The fixture under test.
+ */
+ public MotorEncoderTest(MotorEncoderFixture<?> mef) {
+ logger.fine("Constructor with: " + mef.getType());
+ if (me != null && !me.equals(mef)) {
+ me.teardown();
+ }
+ me = mef;
+ }
+
+ @Parameters(name = "{index}: {0}")
+ public static Collection<MotorEncoderFixture<?>[]> generateData() {
+ // logger.fine("Loading the MotorList");
+ return Arrays.asList(new MotorEncoderFixture<?>[][]{{TestBench.getInstance().getTalonPair()},
+ {TestBench.getInstance().getVictorPair()}, {TestBench.getInstance().getJaguarPair()}});
+ }
+
+ @Before
+ public void setUp() {
+ double initialSpeed = me.getMotor().get();
+ assertTrue(
+ me.getType() + " Did not start with an initial speed of 0 instead got: " + initialSpeed,
+ Math.abs(initialSpeed) < 0.001);
+ me.setup();
+
+ }
+
+ @After
+ public void tearDown() {
+ me.reset();
+ encodersResetCheck(me);
+ }
+
+ @AfterClass
+ public static void tearDownAfterClass() {
+ // Clean up the fixture after the test
+ me.teardown();
+ me = null;
+ }
+
+ /**
+ * Test to ensure that the isMotorWithinRange method is functioning properly. Really only needs to
+ * run on one MotorEncoderFixture to ensure that it is working correctly.
+ */
+ @Test
+ public void testIsMotorWithinRange() {
+ double range = 0.01;
+ assertTrue(me.getType() + " 1", me.isMotorSpeedWithinRange(0.0, range));
+ assertTrue(me.getType() + " 2", me.isMotorSpeedWithinRange(0.0, -range));
+ assertFalse(me.getType() + " 3", me.isMotorSpeedWithinRange(1.0, range));
+ assertFalse(me.getType() + " 4", me.isMotorSpeedWithinRange(-1.0, range));
+ }
+
+ /**
+ * This test is designed to see if the values of different motors will increment when spun
+ * forward.
+ */
+ @Test
+ public void testIncrement() {
+ int startValue = me.getEncoder().get();
+
+ me.getMotor().set(0.2);
+ Timer.delay(MOTOR_RUNTIME);
+ int currentValue = me.getEncoder().get();
+ assertTrue(me.getType() + " Encoder not incremented: start: " + startValue + "; current: "
+ + currentValue, startValue < currentValue);
+
+ }
+
+ /**
+ * This test is designed to see if the values of different motors will decrement when spun in
+ * reverse.
+ */
+ @Test
+ public void testDecrement() {
+ int startValue = me.getEncoder().get();
+
+ me.getMotor().set(-0.2);
+ Timer.delay(MOTOR_RUNTIME);
+ int currentValue = me.getEncoder().get();
+ assertTrue(me.getType() + " Encoder not decremented: start: " + startValue + "; current: "
+ + currentValue, startValue > currentValue);
+ }
+
+ /**
+ * This method test if the counters count when the motors rotate.
+ */
+ @Test
+ public void testCounter() {
+ final int counter1Start = me.getCounters()[0].get();
+ final int counter2Start = me.getCounters()[1].get();
+
+ me.getMotor().set(0.75);
+ Timer.delay(MOTOR_RUNTIME);
+ int counter1End = me.getCounters()[0].get();
+ int counter2End = me.getCounters()[1].get();
+ assertTrue(me.getType() + " Counter not incremented: start: " + counter1Start + "; current: "
+ + counter1End, counter1Start < counter1End);
+ assertTrue(me.getType() + " Counter not incremented: start: " + counter1Start + "; current: "
+ + counter2End, counter2Start < counter2End);
+ me.reset();
+ encodersResetCheck(me);
+ }
+
+ /**
+ * Tests to see if you set the speed to something not {@literal <=} 1.0 if the code appropriately
+ * throttles the value.
+ */
+ @Test
+ public void testSetHighForwardSpeed() {
+ me.getMotor().set(15);
+ assertTrue(me.getType() + " Motor speed was not close to 1.0, was: " + me.getMotor().get(),
+ me.isMotorSpeedWithinRange(1.0, 0.001));
+ }
+
+ /**
+ * Tests to see if you set the speed to something not {@literal >=} -1.0 if the code appropriately
+ * throttles the value.
+ */
+ @Test
+ public void testSetHighReverseSpeed() {
+ me.getMotor().set(-15);
+ assertTrue(me.getType() + " Motor speed was not close to 1.0, was: " + me.getMotor().get(),
+ me.isMotorSpeedWithinRange(-1.0, 0.001));
+ }
+
+
+ @Test
+ public void testPositionPIDController() {
+ PIDController pidController = new PIDController(0.001, 0.0005, 0);
+ pidController.setTolerance(50.0);
+ pidController.setIntegratorRange(-0.2, 0.2);
+ pidController.setSetpoint(1000);
+
+ Notifier pidRunner = new Notifier(() -> {
+ var speed = pidController.calculate(me.getEncoder().getDistance());
+ me.getMotor().set(MathUtil.clamp(speed, -0.2, 0.2));
+ });
+
+ pidRunner.startPeriodic(pidController.getPeriod());
+ Timer.delay(10.0);
+ pidRunner.stop();
+
+ assertTrue(
+ "PID loop did not reach reference within 10 seconds. The current error was" + pidController
+ .getPositionError(), pidController.atSetpoint());
+
+ pidRunner.close();
+ }
+
+ @Test
+ public void testVelocityPIDController() {
+ LinearFilter filter = LinearFilter.movingAverage(50);
+ PIDController pidController = new PIDController(1e-5, 0.0, 0.0006);
+ pidController.setTolerance(200);
+ pidController.setSetpoint(600);
+
+ Notifier pidRunner = new Notifier(() -> {
+ var speed = filter.calculate(me.getEncoder().getRate());
+ me.getMotor().set(MathUtil.clamp(speed, -0.3, 0.3));
+ });
+
+ pidRunner.startPeriodic(pidController.getPeriod());
+ Timer.delay(10.0);
+ pidRunner.stop();
+
+ assertTrue("PID loop did not reach reference within 10 seconds. The error was: " + pidController
+ .getPositionError(), pidController.atSetpoint());
+
+ pidRunner.close();
+ }
+
+ /**
+ * Checks to see if the encoders and counters are appropriately reset to zero when reset.
+ *
+ * @param me The MotorEncoderFixture under test
+ */
+ private void encodersResetCheck(MotorEncoderFixture<?> me) {
+ assertEquals(me.getType() + " Encoder value was incorrect after reset.", me.getEncoder().get(),
+ 0);
+ assertEquals(me.getType() + " Motor value was incorrect after reset.", me.getMotor().get(), 0,
+ 0);
+ assertEquals(me.getType() + " Counter1 value was incorrect after reset.",
+ me.getCounters()[0].get(), 0);
+ assertEquals(me.getType() + " Counter2 value was incorrect after reset.",
+ me.getCounters()[1].get(), 0);
+ Timer.delay(0.5); // so this doesn't fail with the 0.5 second default
+ // timeout on the encoders
+ assertTrue(me.getType() + " Encoder.getStopped() returned false after the motor was reset.",
+ me.getEncoder().getStopped());
+ }
+
+}
diff --git a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/MotorInvertingTest.java b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/MotorInvertingTest.java
new file mode 100644
index 0000000..5857681
--- /dev/null
+++ b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/MotorInvertingTest.java
@@ -0,0 +1,134 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-2018 FIRST. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project. */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import java.util.Arrays;
+import java.util.Collection;
+import java.util.logging.Logger;
+
+import org.junit.AfterClass;
+import org.junit.Before;
+import org.junit.Test;
+import org.junit.runner.RunWith;
+import org.junit.runners.Parameterized;
+import org.junit.runners.Parameterized.Parameters;
+
+import edu.wpi.first.wpilibj.fixtures.MotorEncoderFixture;
+import edu.wpi.first.wpilibj.test.AbstractComsSetup;
+import edu.wpi.first.wpilibj.test.TestBench;
+
+import static org.junit.Assert.assertFalse;
+import static org.junit.Assert.assertTrue;
+
+/**
+ * Tests Inversion of motors using the SpeedController setInverted.
+ */
+@RunWith(Parameterized.class)
+public class MotorInvertingTest extends AbstractComsSetup {
+ static MotorEncoderFixture<?> fixture = null;
+ private static final double motorspeed = 0.2;
+ private static final double delaytime = 0.3;
+
+
+ /**
+ * Constructs the test.
+ *
+ * @param afixture The fixture under test.
+ */
+ public MotorInvertingTest(MotorEncoderFixture<?> afixture) {
+ logger.fine("Constructor with: " + afixture.getType());
+ if (fixture != null && !fixture.equals(afixture)) {
+ fixture.teardown();
+ }
+ fixture = afixture;
+ fixture.setup();
+ }
+
+ @Parameters(name = "{index}: {0}")
+ public static Collection<MotorEncoderFixture<?>[]> generateData() {
+ // logger.fine("Loading the MotorList");
+ return Arrays.asList(new MotorEncoderFixture<?>[][]{{TestBench.getInstance().getTalonPair()},
+ {TestBench.getInstance().getVictorPair()}, {TestBench.getInstance().getJaguarPair()}});
+ }
+
+ private static final Logger logger = Logger.getLogger(MotorInvertingTest.class.getName());
+
+ @Override
+ protected Logger getClassLogger() {
+ return logger;
+ }
+
+ @Before
+ public void setUp() {
+ // Reset the fixture elements before every test
+ fixture.reset();
+ }
+
+ @AfterClass
+ public static void tearDown() {
+ fixture.getMotor().setInverted(false);
+ // Clean up the fixture after the test
+ fixture.teardown();
+ }
+
+ @Test
+ public void testInvertingPositive() {
+ fixture.getMotor().setInverted(false);
+ fixture.getMotor().set(motorspeed);
+ Timer.delay(delaytime);
+ final boolean initDirection = fixture.getEncoder().getDirection();
+ fixture.getMotor().setInverted(true);
+ fixture.getMotor().set(motorspeed);
+ Timer.delay(delaytime);
+ assertFalse("Inverting with Positive value does not change direction", fixture.getEncoder()
+ .getDirection() == initDirection);
+ fixture.getMotor().set(0);
+ }
+
+ @Test
+ public void testInvertingNegative() {
+ fixture.getMotor().setInverted(false);
+ fixture.getMotor().set(-motorspeed);
+ Timer.delay(delaytime);
+ final boolean initDirection = fixture.getEncoder().getDirection();
+ fixture.getMotor().setInverted(true);
+ fixture.getMotor().set(-motorspeed);
+ Timer.delay(delaytime);
+ assertFalse("Inverting with Negative value does not change direction", fixture.getEncoder()
+ .getDirection() == initDirection);
+ fixture.getMotor().set(0);
+ }
+
+ @Test
+ public void testInvertingSwitchingPosToNeg() {
+ fixture.getMotor().setInverted(false);
+ fixture.getMotor().set(motorspeed);
+ Timer.delay(delaytime);
+ final boolean initDirection = fixture.getEncoder().getDirection();
+ fixture.getMotor().setInverted(true);
+ fixture.getMotor().set(-motorspeed);
+ Timer.delay(delaytime);
+ assertTrue("Inverting with Switching value does change direction", fixture.getEncoder()
+ .getDirection() == initDirection);
+ fixture.getMotor().set(0);
+ }
+
+ @Test
+ public void testInvertingSwitchingNegToPos() {
+ fixture.getMotor().setInverted(false);
+ fixture.getMotor().set(-motorspeed);
+ Timer.delay(delaytime);
+ final boolean initDirection = fixture.getEncoder().getDirection();
+ fixture.getMotor().setInverted(true);
+ fixture.getMotor().set(motorspeed);
+ Timer.delay(delaytime);
+ assertTrue("Inverting with Switching value does change direction", fixture.getEncoder()
+ .getDirection() == initDirection);
+ fixture.getMotor().set(0);
+ }
+}
diff --git a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/PCMTest.java b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/PCMTest.java
new file mode 100644
index 0000000..2c1eac1
--- /dev/null
+++ b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/PCMTest.java
@@ -0,0 +1,274 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2014-2019 FIRST. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project. */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import java.util.logging.Logger;
+
+import org.junit.AfterClass;
+import org.junit.Before;
+import org.junit.BeforeClass;
+import org.junit.Test;
+
+import edu.wpi.first.wpilibj.test.AbstractComsSetup;
+
+import static org.junit.Assert.assertEquals;
+import static org.junit.Assert.assertFalse;
+import static org.junit.Assert.assertTrue;
+
+/**
+ * Test that covers the {@link Compressor}.
+ */
+
+public class PCMTest extends AbstractComsSetup {
+ private static final Logger logger = Logger.getLogger(PCMTest.class.getName());
+ /*
+ * The PCM switches the compressor up to 2 seconds after the pressure switch
+ * changes.
+ */
+ protected static final double kCompressorDelayTime = 2.0;
+
+ /* Solenoids should change much more quickly */
+ protected static final double kSolenoidDelayTime = 1.0;
+
+ /*
+ * The voltage divider on the test bench should bring the compressor output to
+ * around these values.
+ */
+ protected static final double kCompressorOnVoltage = 5.00;
+ protected static final double kCompressorOffVoltage = 1.68;
+
+ private static Compressor compressor;
+
+ private static DigitalOutput fakePressureSwitch;
+ private static AnalogInput fakeCompressor;
+
+ private static DigitalInput fakeSolenoid1;
+ private static DigitalInput fakeSolenoid2;
+
+ @BeforeClass
+ public static void setUpBeforeClass() {
+ compressor = new Compressor();
+
+ fakePressureSwitch = new DigitalOutput(11);
+ fakeCompressor = new AnalogInput(1);
+
+ fakeSolenoid1 = new DigitalInput(12);
+ fakeSolenoid2 = new DigitalInput(13);
+ }
+
+ @AfterClass
+ public static void tearDownAfterClass() {
+ fakePressureSwitch.close();
+ fakeCompressor.close();
+
+ fakeSolenoid1.close();
+ fakeSolenoid2.close();
+ }
+
+ @Before
+ public void reset() {
+ compressor.stop();
+ fakePressureSwitch.set(false);
+ }
+
+ /**
+ * Test if the compressor turns on and off when the pressure switch is toggled.
+ */
+ @Test
+ public void testPressureSwitch() throws Exception {
+ final double range = 0.5;
+ reset();
+ compressor.setClosedLoopControl(true);
+
+ // Turn on the compressor
+ fakePressureSwitch.set(true);
+ Timer.delay(kCompressorDelayTime);
+ assertEquals("Compressor did not turn on when the pressure switch turned on.",
+ kCompressorOnVoltage, fakeCompressor.getVoltage(), range);
+
+ // Turn off the compressor
+ fakePressureSwitch.set(false);
+ Timer.delay(kCompressorDelayTime);
+ assertEquals("Compressor did not turn off when the pressure switch turned off.",
+ kCompressorOffVoltage, fakeCompressor.getVoltage(), range);
+ }
+
+ /**
+ * Test if the correct solenoids turn on and off when they should.
+ */
+ @Test
+ public void testSolenoid() throws Exception {
+ reset();
+
+ Solenoid solenoid1 = new Solenoid(0);
+ Solenoid solenoid2 = new Solenoid(1);
+
+ solenoid1.set(false);
+ solenoid2.set(false);
+ Timer.delay(kSolenoidDelayTime);
+ assertTrue("Solenoid #1 did not turn off", fakeSolenoid1.get());
+ assertTrue("Solenoid #2 did not turn off", fakeSolenoid2.get());
+ assertFalse("Solenoid #1 did not report off", solenoid1.get());
+ assertFalse("Solenoid #2 did not report off", solenoid2.get());
+
+ // Turn Solenoid #1 on, and turn Solenoid #2 off
+ solenoid1.set(true);
+ solenoid2.set(false);
+ Timer.delay(kSolenoidDelayTime);
+ assertFalse("Solenoid #1 did not turn on", fakeSolenoid1.get());
+ assertTrue("Solenoid #2 did not turn off", fakeSolenoid2.get());
+ assertTrue("Solenoid #1 did not report on", solenoid1.get());
+ assertFalse("Solenoid #2 did not report off", solenoid2.get());
+
+ // Turn Solenoid #1 off, and turn Solenoid #2 on
+ solenoid1.set(false);
+ solenoid2.set(true);
+ Timer.delay(kSolenoidDelayTime);
+ assertTrue("Solenoid #1 did not turn off", fakeSolenoid1.get());
+ assertFalse("Solenoid #2 did not turn on", fakeSolenoid2.get());
+ assertFalse("Solenoid #1 did not report off", solenoid1.get());
+ assertTrue("Solenoid #2 did not report on", solenoid2.get());
+
+ // Turn both Solenoids on
+ solenoid1.set(true);
+ solenoid2.set(true);
+ Timer.delay(kSolenoidDelayTime);
+ assertFalse("Solenoid #1 did not turn on", fakeSolenoid1.get());
+ assertFalse("Solenoid #2 did not turn on", fakeSolenoid2.get());
+ assertTrue("Solenoid #1 did not report on", solenoid1.get());
+ assertTrue("Solenoid #2 did not report on", solenoid2.get());
+
+ solenoid1.close();
+ solenoid2.close();
+ }
+
+ /**
+ * Test if the correct solenoids turn on and off when they should when used with the
+ * DoubleSolenoid class.
+ */
+ @Test
+ public void doubleSolenoid() {
+ DoubleSolenoid solenoid = new DoubleSolenoid(0, 1);
+
+ solenoid.set(DoubleSolenoid.Value.kOff);
+ Timer.delay(kSolenoidDelayTime);
+ assertTrue("Solenoid #1 did not turn off", fakeSolenoid1.get());
+ assertTrue("Solenoid #2 did not turn off", fakeSolenoid2.get());
+ assertTrue("DoubleSolenoid did not report off", solenoid.get() == DoubleSolenoid.Value.kOff);
+
+ solenoid.set(DoubleSolenoid.Value.kForward);
+ Timer.delay(kSolenoidDelayTime);
+ assertFalse("Solenoid #1 did not turn on", fakeSolenoid1.get());
+ assertTrue("Solenoid #2 did not turn off", fakeSolenoid2.get());
+ assertTrue("DoubleSolenoid did not report Forward", solenoid.get() == DoubleSolenoid.Value
+ .kForward);
+
+ solenoid.set(DoubleSolenoid.Value.kReverse);
+ Timer.delay(kSolenoidDelayTime);
+ assertTrue("Solenoid #1 did not turn off", fakeSolenoid1.get());
+ assertFalse("Solenoid #2 did not turn on", fakeSolenoid2.get());
+ assertTrue("DoubleSolenoid did not report Reverse", solenoid.get() == DoubleSolenoid.Value
+ .kReverse);
+
+ solenoid.close();
+ }
+
+ /**
+ * Test if the correct solenoids turn on and off when they should.
+ */
+ @Test
+ public void testOneShot() throws Exception {
+ reset();
+
+ Solenoid solenoid1 = new Solenoid(0);
+ Solenoid solenoid2 = new Solenoid(1);
+
+ solenoid1.set(false);
+ solenoid2.set(false);
+ Timer.delay(kSolenoidDelayTime);
+ assertTrue("Solenoid #1 did not turn off", fakeSolenoid1.get());
+ assertTrue("Solenoid #2 did not turn off", fakeSolenoid2.get());
+ assertFalse("Solenoid #1 did not report off", solenoid1.get());
+ assertFalse("Solenoid #2 did not report off", solenoid2.get());
+
+ // Pulse Solenoid #1 on, and turn Solenoid #2 off
+ solenoid1.setPulseDuration(2 * kSolenoidDelayTime);
+ solenoid1.startPulse();
+ solenoid2.set(false);
+ Timer.delay(kSolenoidDelayTime);
+ assertFalse("Solenoid #1 did not turn on", fakeSolenoid1.get());
+ assertTrue("Solenoid #2 did not turn off", fakeSolenoid2.get());
+ assertTrue("Solenoid #1 did not report on", solenoid1.get());
+ assertFalse("Solenoid #2 did not report off", solenoid2.get());
+ Timer.delay(2 * kSolenoidDelayTime);
+ assertTrue("Solenoid #1 did not turn off", fakeSolenoid1.get());
+ assertTrue("Solenoid #2 did not turn off", fakeSolenoid2.get());
+ assertFalse("Solenoid #1 did not report off", solenoid1.get());
+ assertFalse("Solenoid #2 did not report off", solenoid2.get());
+
+ // Turn Solenoid #1 off, and pulse Solenoid #2 on
+ solenoid1.set(false);
+ solenoid2.setPulseDuration(2 * kSolenoidDelayTime);
+ solenoid2.startPulse();
+ Timer.delay(kSolenoidDelayTime);
+ assertTrue("Solenoid #1 did not turn off", fakeSolenoid1.get());
+ assertFalse("Solenoid #2 did not turn on", fakeSolenoid2.get());
+ assertFalse("Solenoid #1 did not report off", solenoid1.get());
+ assertTrue("Solenoid #2 did not report on", solenoid2.get());
+ Timer.delay(2 * kSolenoidDelayTime);
+ assertTrue("Solenoid #1 did not turn off", fakeSolenoid1.get());
+ assertTrue("Solenoid #2 did not turn off", fakeSolenoid2.get());
+ assertFalse("Solenoid #1 did not report off", solenoid1.get());
+ assertFalse("Solenoid #2 did not report off", solenoid2.get());
+
+ // Pulse both Solenoids on
+ solenoid1.setPulseDuration(2 * kSolenoidDelayTime);
+ solenoid2.setPulseDuration(2 * kSolenoidDelayTime);
+ solenoid1.startPulse();
+ solenoid2.startPulse();
+ Timer.delay(kSolenoidDelayTime);
+ assertFalse("Solenoid #1 did not turn on", fakeSolenoid1.get());
+ assertFalse("Solenoid #2 did not turn on", fakeSolenoid2.get());
+ assertTrue("Solenoid #1 did not report on", solenoid1.get());
+ assertTrue("Solenoid #2 did not report on", solenoid2.get());
+ Timer.delay(2 * kSolenoidDelayTime);
+ assertTrue("Solenoid #1 did not turn off", fakeSolenoid1.get());
+ assertTrue("Solenoid #2 did not turn off", fakeSolenoid2.get());
+ assertFalse("Solenoid #1 did not report off", solenoid1.get());
+ assertFalse("Solenoid #2 did not report off", solenoid2.get());
+
+ // Pulse both Solenoids on with different durations
+ solenoid1.setPulseDuration(1.5 * kSolenoidDelayTime);
+ solenoid2.setPulseDuration(2.5 * kSolenoidDelayTime);
+ solenoid1.startPulse();
+ solenoid2.startPulse();
+ Timer.delay(kSolenoidDelayTime);
+ assertFalse("Solenoid #1 did not turn on", fakeSolenoid1.get());
+ assertFalse("Solenoid #2 did not turn on", fakeSolenoid2.get());
+ assertTrue("Solenoid #1 did not report on", solenoid1.get());
+ assertTrue("Solenoid #2 did not report on", solenoid2.get());
+ Timer.delay(kSolenoidDelayTime);
+ assertTrue("Solenoid #1 did not turn off", fakeSolenoid1.get());
+ assertFalse("Solenoid #2 did not turn on", fakeSolenoid2.get());
+ assertFalse("Solenoid #1 did not report off", solenoid1.get());
+ assertTrue("Solenoid #2 did not report on", solenoid2.get());
+ Timer.delay(kSolenoidDelayTime);
+ assertTrue("Solenoid #1 did not turn off", fakeSolenoid1.get());
+ assertTrue("Solenoid #2 did not turn off", fakeSolenoid2.get());
+ assertFalse("Solenoid #1 did not report off", solenoid1.get());
+ assertFalse("Solenoid #2 did not report off", solenoid2.get());
+
+ solenoid1.close();
+ solenoid2.close();
+ }
+
+ @Override
+ protected Logger getClassLogger() {
+ return logger;
+ }
+}
diff --git a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/PDPTest.java b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/PDPTest.java
new file mode 100644
index 0000000..b781060
--- /dev/null
+++ b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/PDPTest.java
@@ -0,0 +1,111 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-2019 FIRST. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project. */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import java.util.Arrays;
+import java.util.Collection;
+import java.util.logging.Logger;
+
+import org.junit.After;
+import org.junit.AfterClass;
+import org.junit.BeforeClass;
+import org.junit.Test;
+import org.junit.runner.RunWith;
+import org.junit.runners.Parameterized;
+import org.junit.runners.Parameterized.Parameters;
+
+import edu.wpi.first.hal.can.CANMessageNotFoundException;
+import edu.wpi.first.wpilibj.fixtures.MotorEncoderFixture;
+import edu.wpi.first.wpilibj.test.AbstractComsSetup;
+import edu.wpi.first.wpilibj.test.TestBench;
+
+import static org.hamcrest.Matchers.greaterThan;
+import static org.hamcrest.Matchers.is;
+import static org.junit.Assert.assertEquals;
+import static org.junit.Assert.assertThat;
+
+/**
+ * Test that covers the {@link PowerDistributionPanel}.
+ */
+@RunWith(Parameterized.class)
+public class PDPTest extends AbstractComsSetup {
+ private static final Logger logger = Logger.getLogger(PDPTest.class.getName());
+
+ private static PowerDistributionPanel pdp;
+ private static MotorEncoderFixture<?> me;
+ private final double m_expectedStoppedCurrentDraw;
+
+ @BeforeClass
+ public static void setUpBeforeClass() {
+ pdp = new PowerDistributionPanel();
+ }
+
+ @AfterClass
+ public static void tearDownAfterClass() {
+ pdp = null;
+ me.teardown();
+ me = null;
+ }
+
+
+ @SuppressWarnings("JavadocMethod")
+ public PDPTest(MotorEncoderFixture<?> mef, Double expectedCurrentDraw) {
+ logger.fine("Constructor with: " + mef.getType());
+ if (me != null && !me.equals(mef)) {
+ me.teardown();
+ }
+ me = mef;
+ me.setup();
+
+ m_expectedStoppedCurrentDraw = expectedCurrentDraw;
+ }
+
+ @Parameters(name = "{index}: {0}, Expected Stopped Current Draw: {1}")
+ public static Collection<Object[]> generateData() {
+ // logger.fine("Loading the MotorList");
+ return Arrays.asList(new Object[][]{
+ {TestBench.getInstance().getTalonPair(), 0.0}});
+ }
+
+ @After
+ public void tearDown() {
+ me.reset();
+ }
+
+
+ /**
+ * Test if the current changes when the motor is driven using a talon.
+ */
+ @Test
+ public void checkStoppedCurrentForSpeedController() throws CANMessageNotFoundException {
+ Timer.delay(0.25);
+
+ /* The Current should be 0 */
+ assertEquals("The low current was not within the expected range.", m_expectedStoppedCurrentDraw,
+ pdp.getCurrent(me.getPDPChannel()), 0.001);
+ }
+
+ /**
+ * Test if the current changes when the motor is driven using a talon.
+ */
+ @Test
+ public void checkRunningCurrentForSpeedController() throws CANMessageNotFoundException {
+ /* Set the motor to full forward */
+ me.getMotor().set(1.0);
+ Timer.delay(2);
+
+ /* The current should now be greater than the low current */
+ assertThat("The driven current is not greater than the resting current.",
+ pdp.getCurrent(me.getPDPChannel()), is(greaterThan(m_expectedStoppedCurrentDraw)));
+ }
+
+ @Override
+ protected Logger getClassLogger() {
+ return logger;
+ }
+}
diff --git a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/PIDTest.java b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/PIDTest.java
new file mode 100644
index 0000000..601fff5
--- /dev/null
+++ b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/PIDTest.java
@@ -0,0 +1,183 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project. */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import java.util.ArrayList;
+import java.util.Arrays;
+import java.util.Collection;
+import java.util.logging.Logger;
+
+import org.junit.After;
+import org.junit.AfterClass;
+import org.junit.Before;
+import org.junit.BeforeClass;
+import org.junit.Test;
+import org.junit.runner.RunWith;
+import org.junit.runners.Parameterized;
+import org.junit.runners.Parameterized.Parameters;
+
+import edu.wpi.first.networktables.NetworkTable;
+import edu.wpi.first.networktables.NetworkTableInstance;
+import edu.wpi.first.wpilibj.controller.PIDController;
+import edu.wpi.first.wpilibj.fixtures.MotorEncoderFixture;
+import edu.wpi.first.wpilibj.smartdashboard.SendableBuilderImpl;
+import edu.wpi.first.wpilibj.test.AbstractComsSetup;
+import edu.wpi.first.wpilibj.test.TestBench;
+
+import static org.junit.Assert.assertEquals;
+import static org.junit.Assert.assertFalse;
+import static org.junit.Assert.assertTrue;
+
+
+/**
+ * Test that covers the {@link PIDController}.
+ */
+
+@RunWith(Parameterized.class)
+public class PIDTest extends AbstractComsSetup {
+ private static final Logger logger = Logger.getLogger(PIDTest.class.getName());
+ private NetworkTable m_table;
+ private SendableBuilderImpl m_builder;
+
+ private static final double absoluteTolerance = 50;
+ private static final double integratorRange = 0.25;
+
+ private PIDController m_controller = null;
+ private static MotorEncoderFixture<?> me = null;
+
+ @SuppressWarnings({"MemberName", "EmptyLineSeparator", "MultipleVariableDeclarations"})
+ private final Double k_p, k_i, k_d;
+
+ @Override
+ protected Logger getClassLogger() {
+ return logger;
+ }
+
+
+ @SuppressWarnings({"ParameterName", "JavadocMethod"})
+ public PIDTest(Double p, Double i, Double d, MotorEncoderFixture<?> mef) {
+ logger.fine("Constructor with: " + mef.getType());
+ if (PIDTest.me != null && !PIDTest.me.equals(mef)) {
+ PIDTest.me.teardown();
+ }
+ PIDTest.me = mef;
+ this.k_p = p;
+ this.k_i = i;
+ this.k_d = d;
+ }
+
+
+ @Parameters
+ public static Collection<Object[]> generateData() {
+ // logger.fine("Loading the MotorList");
+ Collection<Object[]> data = new ArrayList<Object[]>();
+ double kp = 0.001;
+ double ki = 0.0005;
+ double kd = 0.0;
+ for (int i = 0; i < 1; i++) {
+ data.addAll(Arrays.asList(new Object[][]{{kp, ki, kd, TestBench.getInstance().getTalonPair()},
+ {kp, ki, kd, TestBench.getInstance().getVictorPair()},
+ {kp, ki, kd, TestBench.getInstance().getJaguarPair()}}));
+ }
+ return data;
+ }
+
+ @BeforeClass
+ public static void setUpBeforeClass() {
+ }
+
+ @AfterClass
+ public static void tearDownAfterClass() {
+ logger.fine("TearDownAfterClass: " + me.getType());
+ me.teardown();
+ me = null;
+ }
+
+ @Before
+ public void setUp() {
+ logger.fine("Setup: " + me.getType());
+ me.setup();
+ m_table = NetworkTableInstance.getDefault().getTable("TEST_PID");
+ m_builder = new SendableBuilderImpl();
+ m_builder.setTable(m_table);
+ m_controller = new PIDController(k_p, k_i, k_d);
+ m_controller.initSendable(m_builder);
+ }
+
+ @After
+ public void tearDown() {
+ logger.fine("Teardown: " + me.getType());
+ m_controller = null;
+ me.reset();
+ }
+
+ private void setupTolerance() {
+ m_controller.setTolerance(absoluteTolerance);
+ }
+
+ private void setupIntegratorRange() {
+ m_controller.setIntegratorRange(-integratorRange, integratorRange);
+ }
+
+ @Test
+ public void testInitialSettings() {
+ setupTolerance();
+ setupIntegratorRange();
+ double reference = 2500.0;
+ m_controller.setSetpoint(reference);
+ assertEquals("PID.getPositionError() did not start at " + reference,
+ reference, m_controller.getPositionError(), 0);
+ m_builder.updateTable();
+ assertEquals(k_p, m_table.getEntry("Kp").getDouble(9999999), 0);
+ assertEquals(k_i, m_table.getEntry("Ki").getDouble(9999999), 0);
+ assertEquals(k_d, m_table.getEntry("Kd").getDouble(9999999), 0);
+ assertEquals(reference, m_table.getEntry("reference").getDouble(9999999), 0);
+ assertFalse(m_table.getEntry("enabled").getBoolean(true));
+ }
+
+ @Test
+ public void testSetSetpoint() {
+ setupTolerance();
+ setupIntegratorRange();
+ double reference = 2500.0;
+ m_controller.setSetpoint(reference);
+ assertEquals("Did not correctly set reference", reference, m_controller.getSetpoint(), 1e-3);
+ }
+
+ @Test(timeout = 10000)
+ public void testRotateToTarget() {
+ setupTolerance();
+ setupIntegratorRange();
+ double reference = 1000.0;
+ assertEquals(pidData() + "did not start at 0", 0, me.getMotor().get(), 0);
+ m_controller.setSetpoint(reference);
+ assertEquals(pidData() + "did not have an error of " + reference, reference,
+ m_controller.getPositionError(), 0);
+ Notifier pidRunner = new Notifier(
+ () -> me.getMotor().set(m_controller.calculate(me.getEncoder().getDistance())));
+ pidRunner.startPeriodic(m_controller.getPeriod());
+ Timer.delay(5);
+ pidRunner.stop();
+ assertTrue(pidData() + "Was not on Target. Controller Error: "
+ + m_controller.getPositionError(), m_controller.atSetpoint());
+
+ pidRunner.close();
+ }
+
+ private String pidData() {
+ return me.getType() + " PID {P:" + m_controller.getP() + " I:" + m_controller.getI() + " D:"
+ + m_controller.getD() + "} ";
+ }
+
+
+ @Test(expected = RuntimeException.class)
+ public void testOnTargetNoToleranceSet() {
+ setupIntegratorRange();
+ m_controller.atSetpoint();
+ }
+}
diff --git a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/RelayCrossConnectTest.java b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/RelayCrossConnectTest.java
new file mode 100644
index 0000000..29fad5f
--- /dev/null
+++ b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/RelayCrossConnectTest.java
@@ -0,0 +1,150 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project. */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import java.util.logging.Logger;
+
+import org.junit.After;
+import org.junit.Before;
+import org.junit.Test;
+
+import edu.wpi.first.networktables.NetworkTable;
+import edu.wpi.first.networktables.NetworkTableInstance;
+import edu.wpi.first.wpilibj.Relay.Direction;
+import edu.wpi.first.wpilibj.Relay.InvalidValueException;
+import edu.wpi.first.wpilibj.Relay.Value;
+import edu.wpi.first.wpilibj.fixtures.RelayCrossConnectFixture;
+import edu.wpi.first.wpilibj.smartdashboard.SendableBuilderImpl;
+import edu.wpi.first.wpilibj.test.AbstractComsSetup;
+import edu.wpi.first.wpilibj.test.TestBench;
+
+import static org.junit.Assert.assertEquals;
+import static org.junit.Assert.assertFalse;
+import static org.junit.Assert.assertTrue;
+
+/**
+ * Tests the {@link RelayCrossConnectFixture}.
+ */
+public class RelayCrossConnectTest extends AbstractComsSetup {
+ private static final Logger logger = Logger.getLogger(RelayCrossConnectTest.class.getName());
+ private static final NetworkTable table =
+ NetworkTableInstance.getDefault().getTable("_RELAY_CROSS_CONNECT_TEST_");
+ private RelayCrossConnectFixture m_relayFixture;
+ private SendableBuilderImpl m_builder;
+
+
+ @Before
+ public void setUp() {
+ m_relayFixture = TestBench.getRelayCrossConnectFixture();
+ m_relayFixture.setup();
+ m_builder = new SendableBuilderImpl();
+ m_builder.setTable(table);
+ m_relayFixture.getRelay().initSendable(m_builder);
+ }
+
+ @After
+ public void tearDown() {
+ m_relayFixture.reset();
+ m_relayFixture.teardown();
+ }
+
+ @Test
+ public void testBothHigh() {
+ m_relayFixture.getRelay().setDirection(Direction.kBoth);
+ m_relayFixture.getRelay().set(Value.kOn);
+ m_builder.updateTable();
+ assertTrue("Input one was not high when relay set both high", m_relayFixture.getInputOne()
+ .get());
+ assertTrue("Input two was not high when relay set both high", m_relayFixture.getInputTwo()
+ .get());
+ assertEquals(Value.kOn, m_relayFixture.getRelay().get());
+ assertEquals("On", table.getEntry("Value").getString(""));
+ }
+
+ @Test
+ public void testFirstHigh() {
+ m_relayFixture.getRelay().setDirection(Direction.kBoth);
+ m_relayFixture.getRelay().set(Value.kForward);
+ m_builder.updateTable();
+ assertFalse("Input one was not low when relay set Value.kForward", m_relayFixture.getInputOne()
+ .get());
+ assertTrue("Input two was not high when relay set Value.kForward", m_relayFixture
+ .getInputTwo()
+ .get());
+ assertEquals(Value.kForward, m_relayFixture.getRelay().get());
+ assertEquals("Forward", table.getEntry("Value").getString(""));
+ }
+
+ @Test
+ public void testSecondHigh() {
+ m_relayFixture.getRelay().setDirection(Direction.kBoth);
+ m_relayFixture.getRelay().set(Value.kReverse);
+ m_builder.updateTable();
+ assertTrue("Input one was not high when relay set Value.kReverse", m_relayFixture.getInputOne()
+ .get());
+ assertFalse("Input two was not low when relay set Value.kReverse", m_relayFixture
+ .getInputTwo()
+ .get());
+ assertEquals(Value.kReverse, m_relayFixture.getRelay().get());
+ assertEquals("Reverse", table.getEntry("Value").getString(""));
+ }
+
+ @Test
+ public void testForwardDirection() {
+ m_relayFixture.getRelay().setDirection(Direction.kForward);
+ m_relayFixture.getRelay().set(Value.kOn);
+ m_builder.updateTable();
+ assertFalse("Input one was not low when relay set Value.kOn in kForward Direction",
+ m_relayFixture.getInputOne().get());
+ assertTrue("Input two was not high when relay set Value.kOn in kForward Direction",
+ m_relayFixture.getInputTwo().get());
+ assertEquals(Value.kOn, m_relayFixture.getRelay().get());
+ assertEquals("On", table.getEntry("Value").getString(""));
+ }
+
+ @Test
+ public void testReverseDirection() {
+ m_relayFixture.getRelay().setDirection(Direction.kReverse);
+ m_relayFixture.getRelay().set(Value.kOn);
+ m_builder.updateTable();
+ assertTrue("Input one was not high when relay set Value.kOn in kReverse Direction",
+ m_relayFixture.getInputOne().get());
+ assertFalse("Input two was not low when relay set Value.kOn in kReverse Direction",
+ m_relayFixture.getInputTwo().get());
+ assertEquals(Value.kOn, m_relayFixture.getRelay().get());
+ assertEquals("On", table.getEntry("Value").getString(""));
+ }
+
+ @Test(expected = InvalidValueException.class)
+ public void testSetValueForwardWithDirectionReverseThrowingException() {
+ m_relayFixture.getRelay().setDirection(Direction.kForward);
+ m_relayFixture.getRelay().set(Value.kReverse);
+ }
+
+ @Test(expected = InvalidValueException.class)
+ public void testSetValueReverseWithDirectionForwardThrowingException() {
+ m_relayFixture.getRelay().setDirection(Direction.kReverse);
+ m_relayFixture.getRelay().set(Value.kForward);
+ }
+
+ @Test
+ public void testInitialSettings() {
+ m_builder.updateTable();
+ assertEquals(Value.kOff, m_relayFixture.getRelay().get());
+ // Initially both outputs should be off
+ assertFalse(m_relayFixture.getInputOne().get());
+ assertFalse(m_relayFixture.getInputTwo().get());
+ assertEquals("Off", table.getEntry("Value").getString(""));
+ }
+
+ @Override
+ protected Logger getClassLogger() {
+ return logger;
+ }
+
+}
diff --git a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/SampleTest.java b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/SampleTest.java
new file mode 100644
index 0000000..efcea23
--- /dev/null
+++ b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/SampleTest.java
@@ -0,0 +1,66 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2018 FIRST. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project. */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import java.util.logging.Logger;
+
+import org.junit.AfterClass;
+import org.junit.Before;
+import org.junit.BeforeClass;
+import org.junit.Test;
+
+import edu.wpi.first.wpilibj.fixtures.SampleFixture;
+import edu.wpi.first.wpilibj.test.AbstractComsSetup;
+
+import static org.junit.Assert.assertTrue;
+
+/**
+ * Sample test for a sample PID controller. This demonstrates the general pattern of how to create a
+ * test and use testing fixtures and categories. All tests must extend from {@link
+ * AbstractComsSetup} in order to ensure that Network Communications are set up before the tests are
+ * run.
+ */
+public class SampleTest extends AbstractComsSetup {
+ private static final Logger logger = Logger.getLogger(SampleTest.class.getName());
+
+ static SampleFixture fixture = new SampleFixture();
+
+ @Override
+ protected Logger getClassLogger() {
+ return logger;
+ }
+
+ @BeforeClass
+ public static void classSetup() {
+ // Set up the fixture before the test is created
+ fixture.setup();
+ }
+
+ @Before
+ public void setUp() {
+ // Reset the fixture elements before every test
+ fixture.reset();
+ }
+
+ @AfterClass
+ public static void tearDown() {
+ // Clean up the fixture after the test
+ fixture.teardown();
+ }
+
+ /**
+ * This is just a sample test that asserts true. Any traditional junit code can be used, these are
+ * ordinary junit tests!
+ */
+ @Test
+ public void test() {
+ Timer.delay(0.5);
+ assertTrue(true);
+ }
+
+}
diff --git a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/TimerTest.java b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/TimerTest.java
new file mode 100644
index 0000000..2acd5bb
--- /dev/null
+++ b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/TimerTest.java
@@ -0,0 +1,45 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2018 FIRST. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project. */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import java.util.logging.Logger;
+
+import org.junit.Test;
+
+import edu.wpi.first.wpilibj.test.AbstractComsSetup;
+
+import static org.junit.Assert.assertEquals;
+
+
+public class TimerTest extends AbstractComsSetup {
+ private static final Logger logger = Logger.getLogger(TimerTest.class.getName());
+ private static final long TIMER_TOLERANCE = (long) (2.5 * 1000);
+ private static final long TIMER_RUNTIME = 5 * 1000000;
+
+ @Override
+ protected Logger getClassLogger() {
+ return logger;
+ }
+
+ @Test
+ public void delayTest() {
+ // Given
+ long startTime = RobotController.getFPGATime();
+
+ // When
+ Timer.delay(TIMER_RUNTIME / 1000000);
+ long endTime = RobotController.getFPGATime();
+ long difference = endTime - startTime;
+
+ // Then
+ long offset = difference - TIMER_RUNTIME;
+ assertEquals("Timer.delay ran " + offset + " microseconds too long", TIMER_RUNTIME, difference,
+ TIMER_TOLERANCE);
+ }
+
+}
diff --git a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/WpiLibJTestSuite.java b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/WpiLibJTestSuite.java
new file mode 100644
index 0000000..9ab6850
--- /dev/null
+++ b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/WpiLibJTestSuite.java
@@ -0,0 +1,28 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project. */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import org.junit.runner.RunWith;
+import org.junit.runners.Suite;
+import org.junit.runners.Suite.SuiteClasses;
+
+import edu.wpi.first.wpilibj.test.AbstractTestSuite;
+
+/**
+ * Holds all of the tests in the root wpilibj directory. Please list alphabetically so that it is
+ * easy to determine if a test is missing from the list.
+ */
+@RunWith(Suite.class)
+@SuiteClasses({AnalogCrossConnectTest.class, AnalogPotentiometerTest.class,
+ BuiltInAccelerometerTest.class, ConstantsPortsTest.class, CounterTest.class,
+ DigitalGlitchFilterTest.class, DIOCrossConnectTest.class,
+ DriverStationTest.class, EncoderTest.class, GyroTest.class, MotorEncoderTest.class,
+ MotorInvertingTest.class, PCMTest.class, PDPTest.class, PIDTest.class,
+ RelayCrossConnectTest.class, SampleTest.class, TimerTest.class})
+public class WpiLibJTestSuite extends AbstractTestSuite {
+}
diff --git a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/can/CANStatusTest.java b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/can/CANStatusTest.java
new file mode 100644
index 0000000..6aa6c8e
--- /dev/null
+++ b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/can/CANStatusTest.java
@@ -0,0 +1,22 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-2018 FIRST. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project. */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.can;
+
+import org.junit.Test;
+
+import edu.wpi.first.hal.can.CANJNI;
+import edu.wpi.first.hal.can.CANStatus;
+
+public class CANStatusTest {
+ @Test
+ public void canStatusGetDoesntThrow() {
+ CANStatus status = new CANStatus();
+ CANJNI.GetCANStatus(status);
+ // Nothing we can assert, so just make sure it didn't throw.
+ }
+}
diff --git a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/AnalogCrossConnectFixture.java b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/AnalogCrossConnectFixture.java
new file mode 100644
index 0000000..ece1dc9
--- /dev/null
+++ b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/AnalogCrossConnectFixture.java
@@ -0,0 +1,86 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2018 FIRST. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project. */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.fixtures;
+
+import edu.wpi.first.wpilibj.AnalogInput;
+import edu.wpi.first.wpilibj.AnalogOutput;
+
+/**
+ * A fixture that connects an {@link AnalogInput} and an {@link AnalogOutput}.
+ */
+public abstract class AnalogCrossConnectFixture implements ITestFixture {
+ private boolean m_initialized = false;
+
+ private AnalogInput m_input;
+ private AnalogOutput m_output;
+
+ protected abstract AnalogInput giveAnalogInput();
+
+ protected abstract AnalogOutput giveAnalogOutput();
+
+
+ private void initialize() {
+ synchronized (this) {
+ if (!m_initialized) {
+ m_input = giveAnalogInput();
+ m_output = giveAnalogOutput();
+ m_initialized = true;
+ }
+ }
+ }
+
+ /*
+ * (non-Javadoc)
+ *
+ * @see edu.wpi.first.wpilibj.fixtures.ITestFixture#setup()
+ */
+ @Override
+ public boolean setup() {
+ initialize();
+ m_output.setVoltage(0);
+ return true;
+ }
+
+ /*
+ * (non-Javadoc)
+ *
+ * @see edu.wpi.first.wpilibj.fixtures.ITestFixture#reset()
+ */
+ @Override
+ public boolean reset() {
+ initialize();
+ return true;
+ }
+
+ /*
+ * (non-Javadoc)
+ *
+ * @see edu.wpi.first.wpilibj.fixtures.ITestFixture#teardown()
+ */
+ @Override
+ public boolean teardown() {
+ m_input.close();
+ m_output.close();
+ return true;
+ }
+
+ /**
+ * Analog Output.
+ */
+ public final AnalogOutput getOutput() {
+ initialize();
+ return m_output;
+ }
+
+ public final AnalogInput getInput() {
+ initialize();
+ return m_input;
+ }
+
+
+}
diff --git a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/DIOCrossConnectFixture.java b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/DIOCrossConnectFixture.java
new file mode 100644
index 0000000..ade9e69
--- /dev/null
+++ b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/DIOCrossConnectFixture.java
@@ -0,0 +1,90 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2018 FIRST. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project. */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.fixtures;
+
+import java.util.logging.Level;
+import java.util.logging.Logger;
+
+import edu.wpi.first.wpilibj.DigitalInput;
+import edu.wpi.first.wpilibj.DigitalOutput;
+
+/**
+ * Connects a digital input to a digital output.
+ */
+public class DIOCrossConnectFixture implements ITestFixture {
+ private static final Logger logger = Logger.getLogger(DIOCrossConnectFixture.class.getName());
+
+ private final DigitalInput m_input;
+ private final DigitalOutput m_output;
+ private boolean m_allocated;
+
+ /**
+ * Constructs using two pre-allocated digital objects.
+ *
+ * @param input The input
+ * @param output The output.
+ */
+ public DIOCrossConnectFixture(DigitalInput input, DigitalOutput output) {
+ assert input != null;
+ assert output != null;
+ m_input = input;
+ m_output = output;
+ m_allocated = false;
+ }
+
+ /**
+ * Constructs a {@link DIOCrossConnectFixture} using the ports of the digital objects.
+ *
+ * @param input The port of the {@link DigitalInput}
+ * @param output The port of the {@link DigitalOutput}
+ */
+ public DIOCrossConnectFixture(Integer input, Integer output) {
+ assert input != null;
+ assert output != null;
+ assert !input.equals(output);
+ m_input = new DigitalInput(input);
+ m_output = new DigitalOutput(output);
+ m_allocated = true;
+ }
+
+ public DigitalInput getInput() {
+ return m_input;
+ }
+
+ public DigitalOutput getOutput() {
+ return m_output;
+ }
+
+ @Override
+ public boolean setup() {
+ return true;
+ }
+
+ @Override
+ public boolean reset() {
+ try {
+ m_input.cancelInterrupts();
+ } catch (IllegalStateException ex) {
+ // This will happen if the interrupt has not been allocated for this test.
+ }
+ m_output.set(false);
+ return true;
+ }
+
+ @Override
+ public boolean teardown() {
+ logger.log(Level.FINE, "Begining teardown");
+ if (m_allocated) {
+ m_input.close();
+ m_output.close();
+ m_allocated = false;
+ }
+ return true;
+ }
+
+}
diff --git a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/FakeCounterFixture.java b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/FakeCounterFixture.java
new file mode 100644
index 0000000..a944421
--- /dev/null
+++ b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/FakeCounterFixture.java
@@ -0,0 +1,112 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2018 FIRST. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project. */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.fixtures;
+
+import java.util.logging.Level;
+import java.util.logging.Logger;
+
+import edu.wpi.first.wpilibj.Counter;
+import edu.wpi.first.wpilibj.mockhardware.FakeCounterSource;
+
+/**
+ * A fixture that can test the {@link Counter} using a {@link DIOCrossConnectFixture}.
+ */
+public class FakeCounterFixture implements ITestFixture {
+ private static final Logger logger = Logger.getLogger(FakeEncoderFixture.class.getName());
+
+ private final DIOCrossConnectFixture m_dio;
+ private boolean m_allocated;
+ private final FakeCounterSource m_source;
+ private final Counter m_counter;
+
+ /**
+ * Constructs a FakeCounterFixture.
+ *
+ * @param dio A previously allocated DIOCrossConnectFixture (must be freed outside this class)
+ */
+ public FakeCounterFixture(DIOCrossConnectFixture dio) {
+ m_dio = dio;
+ m_allocated = false;
+ m_source = new FakeCounterSource(dio.getOutput());
+ m_counter = new Counter(dio.getInput());
+ }
+
+
+ /**
+ * Constructs a FakeCounterFixture using two port numbers.
+ *
+ * @param input the input port
+ * @param output the output port
+ */
+ public FakeCounterFixture(int input, int output) {
+ m_dio = new DIOCrossConnectFixture(input, output);
+ m_allocated = true;
+ m_source = new FakeCounterSource(m_dio.getOutput());
+ m_counter = new Counter(m_dio.getInput());
+ }
+
+ /**
+ * Retrieves the FakeCouterSource for use.
+ *
+ * @return the FakeCounterSource
+ */
+ public FakeCounterSource getFakeCounterSource() {
+ return m_source;
+ }
+
+ /**
+ * Gets the Counter for use.
+ *
+ * @return the Counter
+ */
+ public Counter getCounter() {
+ return m_counter;
+ }
+
+
+ /*
+ * (non-Javadoc)
+ *
+ * @see edu.wpi.first.wpilibj.fixtures.ITestFixture#setup()
+ */
+ @Override
+ public boolean setup() {
+ return true;
+
+ }
+
+ /*
+ * (non-Javadoc)
+ *
+ * @see edu.wpi.first.wpilibj.fixtures.ITestFixture#reset()
+ */
+ @Override
+ public boolean reset() {
+ m_counter.reset();
+ return true;
+ }
+
+ /*
+ * (non-Javadoc)
+ *
+ * @see edu.wpi.first.wpilibj.fixtures.ITestFixture#teardown()
+ */
+ @Override
+ public boolean teardown() {
+ logger.log(Level.FINE, "Begining teardown");
+ m_counter.close();
+ m_source.close();
+ if (m_allocated) { // Only tear down the dio if this class allocated it
+ m_dio.teardown();
+ m_allocated = false;
+ }
+ return true;
+ }
+
+
+}
diff --git a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/FakeEncoderFixture.java b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/FakeEncoderFixture.java
new file mode 100644
index 0000000..2b2b852
--- /dev/null
+++ b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/FakeEncoderFixture.java
@@ -0,0 +1,116 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2018 FIRST. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project. */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.fixtures;
+
+import java.util.logging.Logger;
+
+import edu.wpi.first.wpilibj.Encoder;
+import edu.wpi.first.wpilibj.mockhardware.FakeEncoderSource;
+
+/**
+ * An encoder that uses two {@link DIOCrossConnectFixture DIOCrossConnectFixtures} to test the
+ * {@link Encoder}.
+ */
+public class FakeEncoderFixture implements ITestFixture {
+ private static final Logger logger = Logger.getLogger(FakeEncoderFixture.class.getName());
+
+ private final DIOCrossConnectFixture m_dio1;
+ private final DIOCrossConnectFixture m_dio2;
+ private boolean m_allocated;
+
+ private final FakeEncoderSource m_source;
+ private int[] m_sourcePort = new int[2];
+ private final Encoder m_encoder;
+ private int[] m_encoderPort = new int[2];
+
+ /**
+ * Constructs a FakeEncoderFixture from two DIOCrossConnectFixture.
+ */
+ public FakeEncoderFixture(DIOCrossConnectFixture dio1, DIOCrossConnectFixture dio2) {
+ assert dio1 != null;
+ assert dio2 != null;
+ m_dio1 = dio1;
+ m_dio2 = dio2;
+ m_allocated = false;
+ m_source = new FakeEncoderSource(dio1.getOutput(), dio2.getOutput());
+ m_encoder = new Encoder(dio1.getInput(), dio2.getInput());
+ }
+
+ /**
+ * Construcst a FakeEncoderFixture from a set of Digital I/O ports.
+ */
+ public FakeEncoderFixture(int inputA, int outputA, int inputB, int outputB) {
+ assert outputA != outputB;
+ assert outputA != inputA;
+ assert outputA != inputB;
+ assert outputB != inputA;
+ assert outputB != inputB;
+ assert inputA != inputB;
+ m_dio1 = new DIOCrossConnectFixture(inputA, outputA);
+ m_dio2 = new DIOCrossConnectFixture(inputB, outputB);
+ m_allocated = true;
+ m_sourcePort[0] = outputA;
+ m_sourcePort[1] = outputB;
+ m_encoderPort[0] = inputA;
+ m_encoderPort[1] = inputB;
+ m_source = new FakeEncoderSource(m_dio1.getOutput(), m_dio2.getOutput());
+ m_encoder = new Encoder(m_dio1.getInput(), m_dio2.getInput());
+ }
+
+ public FakeEncoderSource getFakeEncoderSource() {
+ return m_source;
+ }
+
+ public Encoder getEncoder() {
+ return m_encoder;
+ }
+
+ /*
+ * (non-Javadoc)
+ *
+ * @see edu.wpi.first.wpilibj.fixtures.ITestFixture#setup()
+ */
+ @Override
+ public boolean setup() {
+ return true;
+ }
+
+ /*
+ * (non-Javadoc)
+ *
+ * @see edu.wpi.first.wpilibj.fixtures.ITestFixture#reset()
+ */
+ @Override
+ public boolean reset() {
+ m_dio1.reset();
+ m_dio2.reset();
+ m_encoder.reset();
+ return true;
+ }
+
+ /*
+ * (non-Javadoc)
+ *
+ * @see edu.wpi.first.wpilibj.fixtures.ITestFixture#teardown()
+ */
+ @Override
+ public boolean teardown() {
+ logger.fine("Begining teardown");
+ m_source.close();
+ logger.finer("Source freed " + m_sourcePort[0] + ", " + m_sourcePort[1]);
+ m_encoder.close();
+ logger.finer("Encoder freed " + m_encoderPort[0] + ", " + m_encoderPort[1]);
+ if (m_allocated) {
+ m_dio1.teardown();
+ m_dio2.teardown();
+ }
+ return true;
+ }
+
+
+}
diff --git a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/ITestFixture.java b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/ITestFixture.java
new file mode 100644
index 0000000..df797f1
--- /dev/null
+++ b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/ITestFixture.java
@@ -0,0 +1,47 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2018 FIRST. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project. */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.fixtures;
+
+import edu.wpi.first.wpilibj.test.TestBench;
+
+/**
+ * Master interface for all test fixtures. This ensures that all test fixtures have setup and
+ * teardown methods, to ensure that the tests run properly. Test fixtures should be modeled around
+ * the content of a test, rather than the actual physical layout of the testing board. They should
+ * obtain references to hardware from the {@link TestBench} class, which is a singleton. Testing
+ * Fixtures are responsible for ensuring that the hardware is in an appropriate state for the start
+ * of a test, and ensuring that future tests will not be affected by the results of a test.
+ */
+public interface ITestFixture {
+ /**
+ * Performs any required setup for this fixture, ensuring that all fixture elements are ready for
+ * testing.
+ *
+ * @return True if the fixture is ready for testing
+ */
+ boolean setup();
+
+ /**
+ * Resets the fixture back to test start state. This should be called by the test class in the
+ * test setup method to ensure that the hardware is in the default state. This differs from {@link
+ * ITestFixture#setup()} as that is called once, before the class is constructed, so it may need
+ * to start sensors. This method should not have to start anything, just reset sensors and ensure
+ * that motors are stopped.
+ *
+ * @return True if the fixture is ready for testing
+ */
+ boolean reset();
+
+ /**
+ * Performs any required teardown after use of the fixture, ensuring that future tests will not
+ * run into conflicts.
+ *
+ * @return True if the teardown succeeded
+ */
+ boolean teardown();
+}
diff --git a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/MotorEncoderFixture.java b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/MotorEncoderFixture.java
new file mode 100644
index 0000000..fab3306
--- /dev/null
+++ b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/MotorEncoderFixture.java
@@ -0,0 +1,245 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2018 FIRST. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project. */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.fixtures;
+
+import java.lang.reflect.ParameterizedType;
+import java.util.logging.Logger;
+
+import edu.wpi.first.wpilibj.Counter;
+import edu.wpi.first.wpilibj.DigitalInput;
+import edu.wpi.first.wpilibj.Encoder;
+import edu.wpi.first.wpilibj.PWM;
+import edu.wpi.first.wpilibj.SpeedController;
+import edu.wpi.first.wpilibj.Timer;
+import edu.wpi.first.wpilibj.test.TestBench;
+
+/**
+ * Represents a physically connected Motor and Encoder to allow for unit tests on these different
+ * pairs<br> Designed to allow the user to easily setup and tear down the fixture to allow for
+ * reuse. This class should be explicitly instantiated in the TestBed class to allow any test to
+ * access this fixture. This allows tests to be mailable so that you can easily reconfigure the
+ * physical testbed without breaking the tests.
+ */
+public abstract class MotorEncoderFixture<T extends SpeedController> implements ITestFixture {
+ private static final Logger logger = Logger.getLogger(MotorEncoderFixture.class.getName());
+ private boolean m_initialized = false;
+ private boolean m_tornDown = false;
+ protected T m_motor;
+ private Encoder m_encoder;
+ private final Counter[] m_counters = new Counter[2];
+ protected DigitalInput m_alphaSource; // Stored so it can be freed at tear down
+ protected DigitalInput m_betaSource;
+
+ /**
+ * Default constructor for a MotorEncoderFixture.
+ */
+ public MotorEncoderFixture() {
+ }
+
+ public abstract int getPDPChannel();
+
+ /**
+ * Where the implementer of this class should pass the speed controller Constructor should only be
+ * called from outside this class if the Speed controller is not also an implementation of PWM
+ * interface.
+ *
+ * @return SpeedController
+ */
+ protected abstract T giveSpeedController();
+
+ /**
+ * Where the implementer of this class should pass one of the digital inputs.
+ *
+ * <p>CONSTRUCTOR SHOULD NOT BE CALLED FROM OUTSIDE THIS CLASS!
+ *
+ * @return DigitalInput
+ */
+ protected abstract DigitalInput giveDigitalInputA();
+
+ /**
+ * Where the implementer fo this class should pass the other digital input.
+ *
+ * <p>CONSTRUCTOR SHOULD NOT BE CALLED FROM OUTSIDE THIS CLASS!
+ *
+ * @return Input B to be used when this class is instantiated
+ */
+ protected abstract DigitalInput giveDigitalInputB();
+
+ private void initialize() {
+ synchronized (this) {
+ if (!m_initialized) {
+ m_initialized = true; // This ensures it is only initialized once
+
+ m_alphaSource = giveDigitalInputA();
+ m_betaSource = giveDigitalInputB();
+
+
+ m_encoder = new Encoder(m_alphaSource, m_betaSource);
+ m_counters[0] = new Counter(m_alphaSource);
+ m_counters[1] = new Counter(m_betaSource);
+ logger.fine("Creating the speed controller!");
+ m_motor = giveSpeedController();
+ }
+ }
+ }
+
+ @Override
+ public boolean setup() {
+ initialize();
+ return true;
+ }
+
+ /**
+ * Gets the motor for this Object.
+ *
+ * @return the motor this object refers too
+ */
+ public T getMotor() {
+ initialize();
+ return m_motor;
+ }
+
+ /**
+ * Gets the encoder for this object.
+ *
+ * @return the encoder that this object refers too
+ */
+ public Encoder getEncoder() {
+ initialize();
+ return m_encoder;
+ }
+
+ public Counter[] getCounters() {
+ initialize();
+ return m_counters;
+ }
+
+ /**
+ * Retrieves the name of the motor that this object refers to.
+ *
+ * @return The simple name of the motor {@link Class#getSimpleName()}
+ */
+ public String getType() {
+ initialize();
+ return m_motor.getClass().getSimpleName();
+ }
+
+ /**
+ * Checks to see if the speed of the motor is within some range of a given value. This is used
+ * instead of equals() because doubles can have inaccuracies.
+ *
+ * @param value The value to compare against
+ * @param accuracy The accuracy range to check against to see if the
+ * @return true if the range of values between motors speed accuracy contains the 'value'.
+ */
+ public boolean isMotorSpeedWithinRange(double value, double accuracy) {
+ initialize();
+ return Math.abs(Math.abs(m_motor.get()) - Math.abs(value)) < Math.abs(accuracy);
+ }
+
+ @Override
+ public boolean reset() {
+ initialize();
+ m_motor.setInverted(false);
+ m_motor.set(0);
+ Timer.delay(TestBench.MOTOR_STOP_TIME); // DEFINED IN THE TestBench
+ m_encoder.reset();
+ for (Counter c : m_counters) {
+ c.reset();
+ }
+
+ boolean wasReset = true;
+ wasReset = wasReset && m_motor.get() == 0;
+ wasReset = wasReset && m_encoder.get() == 0;
+ for (Counter c : m_counters) {
+ wasReset = wasReset && c.get() == 0;
+ }
+
+ return wasReset;
+ }
+
+
+ /**
+ * Safely tears down the MotorEncoder Fixture in a way that makes sure that even if an object
+ * fails to initialize the rest of the fixture can still be torn down and the resources
+ * deallocated.
+ */
+ @Override
+ @SuppressWarnings("Regexp")
+ public boolean teardown() {
+ String type;
+ if (m_motor != null) {
+ type = getType();
+ } else {
+ type = "null";
+ }
+ if (!m_tornDown) {
+ boolean wasNull = false;
+ if (m_motor instanceof PWM && m_motor != null) {
+ ((PWM) m_motor).close();
+ m_motor = null;
+ } else if (m_motor == null) {
+ wasNull = true;
+ }
+ if (m_encoder != null) {
+ m_encoder.close();
+ m_encoder = null;
+ } else {
+ wasNull = true;
+ }
+ if (m_counters[0] != null) {
+ m_counters[0].close();
+ m_counters[0] = null;
+ } else {
+ wasNull = true;
+ }
+ if (m_counters[1] != null) {
+ m_counters[1].close();
+ m_counters[1] = null;
+ } else {
+ wasNull = true;
+ }
+ if (m_alphaSource != null) {
+ m_alphaSource.close();
+ m_alphaSource = null;
+ } else {
+ wasNull = true;
+ }
+ if (m_betaSource != null) {
+ m_betaSource.close();
+ m_betaSource = null;
+ } else {
+ wasNull = true;
+ }
+
+ m_tornDown = true;
+
+ if (wasNull) {
+ throw new NullPointerException("MotorEncoderFixture had null params at teardown");
+ }
+ } else {
+ throw new RuntimeException(type + " Motor Encoder torn down multiple times");
+ }
+
+ return true;
+ }
+
+ @Override
+ public String toString() {
+ StringBuilder string = new StringBuilder("MotorEncoderFixture<");
+ // Get the generic type as a class
+ @SuppressWarnings("unchecked")
+ Class<T> class1 =
+ (Class<T>) ((ParameterizedType) getClass().getGenericSuperclass())
+ .getActualTypeArguments()[0];
+ string.append(class1.getSimpleName());
+ string.append(">");
+ return string.toString();
+ }
+
+}
diff --git a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/RelayCrossConnectFixture.java b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/RelayCrossConnectFixture.java
new file mode 100644
index 0000000..382b4bb
--- /dev/null
+++ b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/RelayCrossConnectFixture.java
@@ -0,0 +1,97 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2018 FIRST. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project. */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.fixtures;
+
+import edu.wpi.first.wpilibj.DigitalInput;
+import edu.wpi.first.wpilibj.Relay;
+
+/**
+ * A connection between a {@link Relay} and two {@link DigitalInput DigitalInputs}.
+ */
+public abstract class RelayCrossConnectFixture implements ITestFixture {
+ private DigitalInput m_inputOne;
+ private DigitalInput m_inputTwo;
+ private Relay m_relay;
+
+ private boolean m_initialized = false;
+ private boolean m_freed = false;
+
+
+ protected abstract Relay giveRelay();
+
+ protected abstract DigitalInput giveInputOne();
+
+ protected abstract DigitalInput giveInputTwo();
+
+ private void initialize() {
+ synchronized (this) {
+ if (!m_initialized) {
+ m_relay = giveRelay();
+ m_inputOne = giveInputOne();
+ m_inputTwo = giveInputTwo();
+ m_initialized = true;
+ }
+ }
+ }
+
+ public Relay getRelay() {
+ initialize();
+ return m_relay;
+ }
+
+ public DigitalInput getInputOne() {
+ initialize();
+ return m_inputOne;
+ }
+
+ public DigitalInput getInputTwo() {
+ initialize();
+ return m_inputTwo;
+ }
+
+ /*
+ * (non-Javadoc)
+ *
+ * @see edu.wpi.first.wpilibj.fixtures.ITestFixture#setup()
+ */
+ @Override
+ public boolean setup() {
+ initialize();
+ return true;
+ }
+
+ /*
+ * (non-Javadoc)
+ *
+ * @see edu.wpi.first.wpilibj.fixtures.ITestFixture#reset()
+ */
+ @Override
+ public boolean reset() {
+ initialize();
+ return true;
+ }
+
+ /*
+ * (non-Javadoc)
+ *
+ * @see edu.wpi.first.wpilibj.fixtures.ITestFixture#teardown()
+ */
+ @Override
+ public boolean teardown() {
+ if (!m_freed) {
+ m_relay.close();
+ m_inputOne.close();
+ m_inputTwo.close();
+ m_freed = true;
+ } else {
+ throw new RuntimeException("You attempted to free the "
+ + RelayCrossConnectFixture.class.getSimpleName() + " multiple times");
+ }
+ return true;
+ }
+}
diff --git a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/SampleFixture.java b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/SampleFixture.java
new file mode 100644
index 0000000..994c6ee
--- /dev/null
+++ b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/SampleFixture.java
@@ -0,0 +1,48 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2018 FIRST. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project. */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.fixtures;
+
+
+/**
+ * This is an example of how to use the {@link ITestFixture} interface to create test fixtures for a
+ * test.
+ */
+public class SampleFixture implements ITestFixture {
+ @Override
+ public boolean setup() {
+ /*
+ * If this fixture actually accessed the hardware, here is where it would
+ * set up the starting state of the test bench. For example, reseting
+ * encoders, ensuring motors are stopped, reseting any serial communication
+ * if necessary, etc.
+ */
+ return true;
+ }
+
+ @Override
+ public boolean reset() {
+ /*
+ * This is where the fixture would reset any sensors or motors used by the
+ * fixture to test default state. This method should not worry about whether
+ * or not the sensors have been allocated correctly, that is the job of the
+ * setup function.
+ */
+ return false;
+ }
+
+ @Override
+ public boolean teardown() {
+ /*
+ * This is where the fixture would deallocate and reset back to normal
+ * conditions any necessary hardware. This includes ensuring motors are
+ * stopped, stoppable sensors are actually stopped, ensuring serial
+ * communications are ready for the next test, etc.
+ */
+ return true;
+ }
+}
diff --git a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/TiltPanCameraFixture.java b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/TiltPanCameraFixture.java
new file mode 100644
index 0000000..afeaf38
--- /dev/null
+++ b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/TiltPanCameraFixture.java
@@ -0,0 +1,116 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2018 FIRST. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project. */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.fixtures;
+
+import java.util.logging.Logger;
+
+import edu.wpi.first.wpilibj.AnalogGyro;
+import edu.wpi.first.wpilibj.Servo;
+import edu.wpi.first.wpilibj.Timer;
+
+/**
+ * A class to represent the a physical Camera with two servos (tilt and pan) designed to test to see
+ * if the gyroscope is operating normally.
+ */
+public abstract class TiltPanCameraFixture implements ITestFixture {
+ public static final Logger logger = Logger.getLogger(TiltPanCameraFixture.class.getName());
+
+ public static final double RESET_TIME = 2.0;
+ private AnalogGyro m_gyro;
+ private AnalogGyro m_gyroParam;
+ private Servo m_tilt;
+ private Servo m_pan;
+ private boolean m_initialized = false;
+
+
+ protected abstract AnalogGyro giveGyro();
+
+ protected abstract AnalogGyro giveGyroParam(int center, double offset);
+
+ protected abstract Servo giveTilt();
+
+ protected abstract Servo givePan();
+
+ /**
+ * Constructs the TiltPanCamera.
+ */
+ public TiltPanCameraFixture() {
+ }
+
+ @Override
+ public boolean setup() {
+ boolean wasSetup = false;
+ if (!m_initialized) {
+ m_initialized = true;
+ m_tilt = giveTilt();
+ m_tilt.set(0);
+ m_pan = givePan();
+ m_pan.set(0);
+ Timer.delay(RESET_TIME);
+
+ logger.fine("Initializing the gyro");
+ m_gyro = giveGyro();
+ m_gyro.reset();
+ wasSetup = true;
+ }
+ return wasSetup;
+ }
+
+ @Override
+ public boolean reset() {
+ if (m_gyro != null) {
+ m_gyro.reset();
+ }
+ return true;
+ }
+
+ public Servo getTilt() {
+ return m_tilt;
+ }
+
+ public Servo getPan() {
+ return m_pan;
+ }
+
+ public AnalogGyro getGyro() {
+ return m_gyro;
+ }
+
+ public AnalogGyro getGyroParam() {
+ return m_gyroParam;
+ }
+
+ // Do not call unless all other instances of Gyro have been deallocated
+ public void setupGyroParam(int center, double offset) {
+ m_gyroParam = giveGyroParam(center, offset);
+ m_gyroParam.reset();
+ }
+
+ public void freeGyro() {
+ m_gyro.close();
+ m_gyro = null;
+ }
+
+ @Override
+ public boolean teardown() {
+ m_tilt.close();
+ m_tilt = null;
+ m_pan.close();
+ m_pan = null;
+ if (m_gyro != null) { //in case not freed during gyro tests
+ m_gyro.close();
+ m_gyro = null;
+ }
+ if (m_gyroParam != null) { //in case gyro tests failed before getting to this point
+ m_gyroParam.close();
+ m_gyroParam = null;
+ }
+ return true;
+ }
+
+}
diff --git a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/mockhardware/FakeCounterSource.java b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/mockhardware/FakeCounterSource.java
new file mode 100644
index 0000000..d67fbdb
--- /dev/null
+++ b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/mockhardware/FakeCounterSource.java
@@ -0,0 +1,138 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2014-2019 FIRST. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project. */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.mockhardware;
+
+import edu.wpi.first.wpilibj.DigitalOutput;
+import edu.wpi.first.wpilibj.Timer;
+
+/**
+ * Simulates an encoder for testing purposes.
+ */
+public class FakeCounterSource implements AutoCloseable {
+ private Thread m_task;
+ private int m_count;
+ private int m_milliSec;
+ private DigitalOutput m_output;
+ private boolean m_allocated;
+
+ /**
+ * Thread object that allows emulation of an encoder.
+ */
+ private class EncoderThread extends Thread {
+ FakeCounterSource m_encoder;
+
+ EncoderThread(FakeCounterSource encode) {
+ m_encoder = encode;
+ }
+
+ @Override
+ public void run() {
+ m_encoder.m_output.set(false);
+ try {
+ for (int i = 0; i < m_encoder.m_count; i++) {
+ Thread.sleep(m_encoder.m_milliSec);
+ m_encoder.m_output.set(true);
+ Thread.sleep(m_encoder.m_milliSec);
+ m_encoder.m_output.set(false);
+ }
+ } catch (InterruptedException ex) {
+ Thread.currentThread().interrupt();
+ }
+ }
+ }
+
+ /**
+ * Create a fake encoder on a given port.
+ *
+ * @param output the port to output the given signal to
+ */
+ public FakeCounterSource(DigitalOutput output) {
+ m_output = output;
+ m_allocated = false;
+ initEncoder();
+ }
+
+ /**
+ * Create a fake encoder on a given port.
+ *
+ * @param port The port the encoder is supposed to be on
+ */
+ public FakeCounterSource(int port) {
+ m_output = new DigitalOutput(port);
+ m_allocated = true;
+ initEncoder();
+ }
+
+ /**
+ * Destroy Object with minimum memory leak.
+ */
+ @Override
+ public void close() {
+ m_task = null;
+ if (m_allocated) {
+ m_output.close();
+ m_output = null;
+ m_allocated = false;
+ }
+ }
+
+ /**
+ * Common initailization code.
+ */
+ private void initEncoder() {
+ m_milliSec = 1;
+ m_task = new EncoderThread(this);
+ m_output.set(false);
+ }
+
+ /**
+ * Starts the thread execution task.
+ */
+ public void start() {
+ m_task.start();
+ }
+
+ /**
+ * Waits for the thread to complete.
+ */
+ public void complete() {
+ try {
+ m_task.join();
+ } catch (InterruptedException ex) {
+ Thread.currentThread().interrupt();
+ }
+ m_task = new EncoderThread(this);
+ Timer.delay(0.01);
+ }
+
+ /**
+ * Starts and completes a task set - does not return until thred has finished its operations.
+ */
+ public void execute() {
+ start();
+ complete();
+ }
+
+ /**
+ * Sets the count to run encoder.
+ *
+ * @param count The count to emulate to the controller
+ */
+ public void setCount(int count) {
+ m_count = count;
+ }
+
+ /**
+ * Specify the rate to send pulses.
+ *
+ * @param milliSec The rate to send out pulses at
+ */
+ public void setRate(int milliSec) {
+ m_milliSec = milliSec;
+ }
+}
diff --git a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/mockhardware/FakeEncoderSource.java b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/mockhardware/FakeEncoderSource.java
new file mode 100644
index 0000000..efc69a5
--- /dev/null
+++ b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/mockhardware/FakeEncoderSource.java
@@ -0,0 +1,180 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2014-2019 FIRST. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project. */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.mockhardware;
+
+import edu.wpi.first.wpilibj.DigitalOutput;
+import edu.wpi.first.wpilibj.Timer;
+
+/**
+ * Emulates a quadrature encoder.
+ */
+public class FakeEncoderSource implements AutoCloseable {
+ private Thread m_task;
+ private int m_count;
+ private int m_milliSec;
+ private boolean m_forward;
+ private final DigitalOutput m_outputA;
+ private final DigitalOutput m_outputB;
+ private final boolean m_allocatedOutputs;
+
+ /**
+ * Thread object that allows emulation of a quadrature encoder.
+ */
+ private class QuadEncoderThread extends Thread {
+ FakeEncoderSource m_encoder;
+
+ QuadEncoderThread(FakeEncoderSource encode) {
+ m_encoder = encode;
+ }
+
+ @Override
+ public void run() {
+ final DigitalOutput lead;
+ final DigitalOutput lag;
+
+ m_encoder.m_outputA.set(false);
+ m_encoder.m_outputB.set(false);
+
+ if (m_encoder.isForward()) {
+ lead = m_encoder.m_outputA;
+ lag = m_encoder.m_outputB;
+ } else {
+ lead = m_encoder.m_outputB;
+ lag = m_encoder.m_outputA;
+ }
+
+ try {
+ for (int i = 0; i < m_encoder.m_count; i++) {
+ lead.set(true);
+ Thread.sleep(m_encoder.m_milliSec);
+ lag.set(true);
+ Thread.sleep(m_encoder.m_milliSec);
+ lead.set(false);
+ Thread.sleep(m_encoder.m_milliSec);
+ lag.set(false);
+ Thread.sleep(m_encoder.m_milliSec);
+ }
+ } catch (InterruptedException ex) {
+ Thread.currentThread().interrupt();
+ }
+ }
+ }
+
+ /**
+ * Creates an encoder source using two ports.
+ *
+ * @param portA The A port
+ * @param portB The B port
+ */
+ public FakeEncoderSource(int portA, int portB) {
+ m_outputA = new DigitalOutput(portA);
+ m_outputB = new DigitalOutput(portB);
+ m_allocatedOutputs = true;
+ initQuadEncoder();
+ }
+
+ /**
+ * Creates the fake encoder using two digital outputs.
+ *
+ * @param outputA The A digital output
+ * @param outputB The B digital output
+ */
+ public FakeEncoderSource(DigitalOutput outputA, DigitalOutput outputB) {
+ m_outputA = outputA;
+ m_outputB = outputB;
+ m_allocatedOutputs = false;
+ initQuadEncoder();
+ }
+
+ /**
+ * Frees the resource.
+ */
+ @Override
+ public void close() {
+ m_task = null;
+ if (m_allocatedOutputs) {
+ m_outputA.close();
+ m_outputB.close();
+ }
+ }
+
+ /**
+ * Common initialization code.
+ */
+ private void initQuadEncoder() {
+ m_milliSec = 1;
+ m_forward = true;
+ m_task = new QuadEncoderThread(this);
+ m_outputA.set(false);
+ m_outputB.set(false);
+ }
+
+ /**
+ * Starts the thread.
+ */
+ public void start() {
+ m_task.start();
+ }
+
+ /**
+ * Waits for thread to end.
+ */
+ public void complete() {
+ try {
+ m_task.join();
+ } catch (InterruptedException ex) {
+ Thread.currentThread().interrupt();
+ }
+ m_task = new QuadEncoderThread(this);
+ Timer.delay(0.01);
+ }
+
+ /**
+ * Runs and waits for thread to end before returning.
+ */
+ public void execute() {
+ start();
+ complete();
+ }
+
+ /**
+ * Rate of pulses to send.
+ *
+ * @param milliSec Pulse Rate
+ */
+ public void setRate(int milliSec) {
+ m_milliSec = milliSec;
+ }
+
+ /**
+ * Set the number of pulses to simulate.
+ *
+ * @param count Pulse count
+ */
+ public void setCount(int count) {
+ m_count = Math.abs(count);
+ }
+
+ /**
+ * Set which direction the encoder simulates motion in.
+ *
+ * @param isForward Whether to simulate forward motion
+ */
+ public void setForward(boolean isForward) {
+ m_forward = isForward;
+ }
+
+ /**
+ * Accesses whether the encoder is simulating forward motion.
+ *
+ * @return Whether the simulated motion is in the forward direction
+ */
+ public boolean isForward() {
+ return m_forward;
+ }
+}
diff --git a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/mockhardware/FakePotentiometerSource.java b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/mockhardware/FakePotentiometerSource.java
new file mode 100644
index 0000000..63af674
--- /dev/null
+++ b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/mockhardware/FakePotentiometerSource.java
@@ -0,0 +1,94 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2018 FIRST. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project. */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.mockhardware;
+
+import edu.wpi.first.wpilibj.AnalogOutput;
+
+/**
+ * A fake source to provide output to a {@link edu.wpi.first.wpilibj.interfaces.Potentiometer}.
+ */
+public class FakePotentiometerSource implements AutoCloseable {
+ private AnalogOutput m_output;
+ private boolean m_initOutput;
+ private double m_potMaxAngle;
+ private double m_potMaxVoltage = 5.0;
+ private final double m_defaultPotMaxAngle;
+
+ /**
+ * Constructs the fake source.
+ *
+ * @param output The analog port to output the signal on
+ * @param defaultPotMaxAngle The default maximum angle the pot supports.
+ */
+ public FakePotentiometerSource(AnalogOutput output, double defaultPotMaxAngle) {
+ m_defaultPotMaxAngle = defaultPotMaxAngle;
+ m_potMaxAngle = defaultPotMaxAngle;
+ m_output = output;
+ m_initOutput = false;
+ }
+
+ public FakePotentiometerSource(int port, double defaultPotMaxAngle) {
+ this(new AnalogOutput(port), defaultPotMaxAngle);
+ m_initOutput = true;
+ }
+
+ /**
+ * Sets the maximum voltage output. If not the default is 5.0V.
+ *
+ * @param voltage The voltage that indicates that the pot is at the max value.
+ */
+ public void setMaxVoltage(double voltage) {
+ m_potMaxVoltage = voltage;
+ }
+
+ public void setRange(double range) {
+ m_potMaxAngle = range;
+ }
+
+ public void reset() {
+ m_potMaxAngle = m_defaultPotMaxAngle;
+ m_output.setVoltage(0.0);
+ }
+
+ public void setAngle(double angle) {
+ m_output.setVoltage((m_potMaxVoltage / m_potMaxAngle) * angle);
+ }
+
+ public void setVoltage(double voltage) {
+ m_output.setVoltage(voltage);
+ }
+
+ public double getVoltage() {
+ return m_output.getVoltage();
+ }
+
+ /**
+ * Returns the currently set angle.
+ *
+ * @return the current angle
+ */
+ public double getAngle() {
+ double voltage = m_output.getVoltage();
+ if (voltage == 0) { // Removes divide by zero error
+ return 0;
+ }
+ return voltage * (m_potMaxAngle / m_potMaxVoltage);
+ }
+
+ /**
+ * Frees the resouce.
+ */
+ @Override
+ public void close() {
+ if (m_initOutput) {
+ m_output.close();
+ m_output = null;
+ m_initOutput = false;
+ }
+ }
+}
diff --git a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/AbstractComsSetup.java b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/AbstractComsSetup.java
new file mode 100644
index 0000000..7c49eef
--- /dev/null
+++ b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/AbstractComsSetup.java
@@ -0,0 +1,245 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project. */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.test;
+
+import java.util.logging.Level;
+import java.util.logging.Logger;
+
+import org.junit.BeforeClass;
+import org.junit.Rule;
+import org.junit.rules.TestWatcher;
+import org.junit.runner.Description;
+import org.junit.runners.model.MultipleFailureException;
+
+import edu.wpi.first.hal.HAL;
+import edu.wpi.first.wpilibj.DriverStation;
+import edu.wpi.first.wpilibj.MockDS;
+import edu.wpi.first.wpilibj.Timer;
+import edu.wpi.first.wpilibj.livewindow.LiveWindow;
+
+/**
+ * This class serves as a superclass for all tests that involve the hardware on the roboRIO. It uses
+ * an {@link BeforeClass} statement to initialize network communications. Any test that needs to use
+ * the hardware <b>MUST</b> extend from this class, to ensure that all of the hardware will be able
+ * to run.
+ */
+public abstract class AbstractComsSetup {
+ /**
+ * Stores whether network coms have been initialized.
+ */
+ private static boolean initialized = false;
+
+ // We have no way to stop the MockDS, so its thread is daemon.
+ private static MockDS ds;
+
+ /**
+ * This sets up the network communications library to enable the driver
+ * station. After starting network coms, it will loop until the driver station
+ * returns that the robot is enabled, to ensure that tests will be able to run
+ * on the hardware.
+ */
+ static {
+ if (!initialized) {
+ try {
+ // Set some implementations so that the static methods work properly
+ HAL.initialize(500, 0);
+ HAL.observeUserProgramStarting();
+ DriverStation.getInstance().getAlliance();
+
+ ds = new MockDS();
+ ds.start();
+
+ LiveWindow.setEnabled(false);
+ TestBench.out().println("Started coms");
+ } catch (Exception ex) {
+ TestBench.out().println("Exception during AbstractComsSetup initialization: " + ex);
+ ex.printStackTrace(TestBench.out());
+ throw ex;
+ }
+
+ // Wait until the robot is enabled before starting the tests
+ int enableCounter = 0;
+ while (!DriverStation.getInstance().isEnabled()) {
+ if (enableCounter > 50) {
+ // Robot did not enable properly after 5 seconds.
+ // Force exit
+ TestBench.err().println("Failed to enable. Aborting");
+ System.exit(1);
+ }
+ try {
+ Thread.sleep(100);
+ } catch (InterruptedException ex) {
+ ex.printStackTrace();
+ }
+ TestBench.out().println("Waiting for enable: " + enableCounter++);
+ }
+ TestBench.out().println();
+
+ // Ready to go!
+ initialized = true;
+ TestBench.out().println("Running!");
+ }
+ }
+
+
+ protected abstract Logger getClassLogger();
+
+ /**
+ * This causes a stack trace to be printed as the test is running as well as at the end.
+ */
+ @Rule
+ public final TestWatcher getTestWatcher() {
+ return getOverridenTestWatcher();
+ }
+
+ /**
+ * Given as a way to provide a custom test watcher for a test or set of tests.
+ *
+ * @return the test watcher to use
+ */
+ protected TestWatcher getOverridenTestWatcher() {
+ return new DefaultTestWatcher();
+ }
+
+ protected class DefaultTestWatcher extends TestWatcher {
+ /**
+ * Allows a failure to supply a custom status message to be displayed along with the stack
+ * trace.
+ */
+ protected void failed(Throwable throwable, Description description, String status) {
+ TestBench.out().println();
+ // Instance of is the best way I know to retrieve this data.
+ if (throwable instanceof MultipleFailureException) {
+ /*
+ * MultipleFailureExceptions hold multiple exceptions in one exception.
+ * In order to properly display these stack traces we have to cast the
+ * throwable and work with the list of thrown exceptions stored within
+ * it.
+ */
+ int exceptionCount = 1; // Running exception count
+ int failureCount = ((MultipleFailureException) throwable).getFailures().size();
+ for (Throwable singleThrown : ((MultipleFailureException) throwable).getFailures()) {
+ getClassLogger().logp(
+ Level.SEVERE,
+ description.getClassName(),
+ description.getMethodName(),
+ (exceptionCount++) + "/" + failureCount + " " + description.getDisplayName() + " "
+ + "failed " + singleThrown.getMessage() + "\n" + status, singleThrown);
+ }
+
+ } else {
+ getClassLogger().logp(Level.SEVERE, description.getClassName(),
+ description.getMethodName(),
+ description.getDisplayName() + " failed " + throwable.getMessage() + "\n" + status,
+ throwable);
+ }
+ super.failed(throwable, description);
+ }
+
+ /*
+ * (non-Javadoc)
+ *
+ * @see org.junit.rules.TestWatcher#failed(java.lang.Throwable,
+ * org.junit.runner.Description)
+ */
+ @Override
+ protected void failed(Throwable exception, Description description) {
+ failed(exception, description, "");
+ }
+
+
+ /*
+ * (non-Javadoc)
+ *
+ * @see org.junit.rules.TestWatcher#starting(org.junit.runner.Description)
+ */
+ @Override
+ protected void starting(Description description) {
+ TestBench.out().println();
+ // Wait until the robot is enabled before starting the next tests
+ int enableCounter = 0;
+ while (!DriverStation.getInstance().isEnabled()) {
+ try {
+ Thread.sleep(100);
+ } catch (InterruptedException ex) {
+ ex.printStackTrace();
+ }
+ // Prints the message on one line overwriting itself each time
+ TestBench.out().print("\rWaiting for enable: " + enableCounter++);
+ }
+ getClassLogger().logp(Level.INFO, description.getClassName(), description.getMethodName(),
+ "Starting");
+ super.starting(description);
+ }
+
+ @Override
+ protected void succeeded(Description description) {
+ simpleLog(Level.INFO, "TEST PASSED!");
+ super.succeeded(description);
+ }
+
+ }
+
+ /**
+ * Logs a simple message without the logger formatting associated with it.
+ *
+ * @param level The level to log the message at
+ * @param message The message to log
+ */
+ protected void simpleLog(Level level, String message) {
+ if (getClassLogger().isLoggable(level)) {
+ TestBench.out().println(message);
+ }
+ }
+
+ /**
+ * Provided as a replacement to lambda functions to allow for repeatable checks to see if a
+ * correct state is reached.
+ */
+ public abstract class BooleanCheck {
+ public BooleanCheck() {
+ }
+
+ /**
+ * Runs the enclosed code and evaluates it to determine what state it should return.
+ *
+ * @return true if the code provided within the method returns true
+ */
+ public abstract boolean getAsBoolean();
+ }
+
+ /**
+ * Delays until either the correct state is reached or we reach the timeout.
+ *
+ * @param level The level to log the message at.
+ * @param timeout How long the delay should run before it should timeout and allow the test
+ * to continue
+ * @param message The message to accompany the delay. The message will display 'message' took
+ * 'timeout' seconds if it passed.
+ * @param correctState A method to determine if the test has reached a state where it is valid to
+ * continue
+ * @return a double representing how long the delay took to run in seconds.
+ */
+ public double delayTillInCorrectStateWithMessage(Level level, double timeout, String message,
+ BooleanCheck correctState) {
+ int timeoutIndex;
+ // As long as we are not in the correct state and the timeout has not been
+ // reached then continue to run this loop
+ for (timeoutIndex = 0; timeoutIndex < (timeout * 100) && !correctState.getAsBoolean();
+ timeoutIndex++) {
+ Timer.delay(0.01);
+ }
+ if (correctState.getAsBoolean()) {
+ simpleLog(level, message + " took " + (timeoutIndex * 0.01) + " seconds");
+ } else {
+ simpleLog(level, message + " timed out after " + (timeoutIndex * 0.01) + " seconds");
+ }
+ return timeoutIndex * 0.01;
+ }
+
+}
diff --git a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/AbstractTestSuite.java b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/AbstractTestSuite.java
new file mode 100644
index 0000000..e4b2035
--- /dev/null
+++ b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/AbstractTestSuite.java
@@ -0,0 +1,260 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project. */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.test;
+
+import java.lang.reflect.InvocationTargetException;
+import java.lang.reflect.Method;
+import java.util.ArrayList;
+import java.util.List;
+import java.util.logging.Level;
+import java.util.logging.Logger;
+import java.util.regex.Pattern;
+
+import org.junit.Ignore;
+import org.junit.Test;
+import org.junit.runner.Request;
+import org.junit.runners.Suite.SuiteClasses;
+
+/**
+ * Allows tests suites and tests to be run selectively from the command line using a regex text
+ * pattern.
+ */
+public abstract class AbstractTestSuite {
+ private static final Logger logger = Logger.getLogger(AbstractTestSuite.class.getName());
+
+ /**
+ * Gets all of the classes listed within the SuiteClasses annotation. To use it, annotate a class
+ * with <code>@RunWith(Suite.class)</code> and <code>@SuiteClasses({TestClass1.class,
+ * ...})</code>. When you run this class, it will run all the tests in all the suite classes. When
+ * loading the tests using regex the test list will be generated from this annotation.
+ *
+ * @return the list of classes listed in the <code>@SuiteClasses({TestClass1.class, ...})</code>.
+ * @throws RuntimeException If the <code>@SuiteClasses</code> annotation is missing.
+ */
+ protected List<Class<?>> getAnnotatedTestClasses() {
+ SuiteClasses annotation = getClass().getAnnotation(SuiteClasses.class);
+ List<Class<?>> classes = new ArrayList<>();
+ if (annotation == null) {
+ throw new RuntimeException(String.format("class '%s' must have a SuiteClasses annotation",
+ getClass().getName()));
+ }
+ for (Class<?> c : annotation.value()) {
+ classes.add(c);
+ }
+ return classes;
+ }
+
+ private boolean areAnySuperClassesOfTypeAbstractTestSuite(Class<?> check) {
+ while (check != null) {
+ if (check.equals(AbstractTestSuite.class)) {
+ return true;
+ }
+ check = check.getSuperclass();
+ }
+ return false;
+ }
+
+ /**
+ * Stores a method name and method class pair. Used when searching for methods matching a given
+ * regex text.
+ */
+ protected class ClassMethodPair {
+ public final Class<?> m_methodClass;
+ public final String m_methodName;
+
+ public ClassMethodPair(Class<?> klass, Method method) {
+ m_methodClass = klass;
+ m_methodName = method.getName();
+ }
+
+ public Request getMethodRunRequest() {
+ return Request.method(m_methodClass, m_methodName);
+ }
+ }
+
+ protected List<ClassMethodPair> getMethodMatching(final String regex) {
+ List<ClassMethodPair> classMethodPairs = new ArrayList<>();
+ // Get all of the test classes
+ for (Class<?> c : getAllContainedBaseTests()) {
+ for (Method m : c.getMethods()) {
+ // If this is a test method that is not trying to be ignored and it
+ // matches the regex
+ if (m.getAnnotation(Test.class) != null && m.getAnnotation(Ignore.class) == null
+ && Pattern.matches(regex, m.getName())) {
+ ClassMethodPair pair = new ClassMethodPair(c, m);
+ classMethodPairs.add(pair);
+ }
+ }
+ }
+ return classMethodPairs;
+ }
+
+
+ /**
+ * Gets all of the test classes listed in this suite. Does not include any of the test suites. All
+ * of these classes contain tests.
+ *
+ * @param runningList the running list of classes to prevent recursion.
+ * @return The list of base test classes.
+ */
+ private List<Class<?>> getAllContainedBaseTests(List<Class<?>> runningList) {
+ for (Class<?> c : getAnnotatedTestClasses()) {
+ // Check to see if this is a test class or a suite
+ if (areAnySuperClassesOfTypeAbstractTestSuite(c)) {
+ // Create a new instance of this class so that we can retrieve its data
+ try {
+ AbstractTestSuite suite = (AbstractTestSuite) c.getDeclaredConstructor().newInstance();
+ // Add the tests from this suite that match the regex to the list of
+ // tests to run
+ runningList = suite.getAllContainedBaseTests(runningList);
+ } catch (NoSuchMethodException | InvocationTargetException | InstantiationException
+ | IllegalAccessException ex) {
+ // This shouldn't happen unless the constructor is changed in some
+ // way.
+ logger.log(Level.SEVERE, "Test suites can not take paramaters in their constructors.",
+ ex);
+ }
+ } else if (c.getAnnotation(SuiteClasses.class) != null) {
+ logger.log(Level.SEVERE,
+ String.format("class '%s' must extend %s to be searchable using regex.",
+ c.getName(), AbstractTestSuite.class.getName()));
+ } else { // This is a class containing tests
+ // so add it to the list
+ runningList.add(c);
+ }
+ }
+ return runningList;
+ }
+
+ /**
+ * Gets all of the test classes listed in this suite. Does not include any of the test suites. All
+ * of these classes contain tests.
+ *
+ * @return The list of base test classes.
+ */
+ public List<Class<?>> getAllContainedBaseTests() {
+ List<Class<?>> runningBaseTests = new ArrayList<>();
+ return getAllContainedBaseTests(runningBaseTests);
+ }
+
+
+ /**
+ * Retrieves all of the classes listed in the <code>@SuiteClasses</code> annotation that match the
+ * given regex text.
+ *
+ * @param regex the text pattern to retrieve.
+ * @param runningList the running list of classes to prevent recursion
+ * @return The list of classes matching the regex pattern
+ */
+ private List<Class<?>> getAllClassMatching(final String regex, final List<Class<?>> runningList) {
+ for (Class<?> c : getAnnotatedTestClasses()) {
+ // Compare the regex against the simple name of the class
+ if (Pattern.matches(regex, c.getName()) && !runningList.contains(c)) {
+ runningList.add(c);
+ }
+ }
+ return runningList;
+ }
+
+ /**
+ * Retrieves all of the classes listed in the <code>@SuiteClasses</code> annotation that match the
+ * given regex text.
+ *
+ * @param regex the text pattern to retrieve.
+ * @return The list of classes matching the regex pattern
+ */
+ public List<Class<?>> getAllClassMatching(final String regex) {
+ final List<Class<?>> matchingClasses = new ArrayList<>();
+ return getAllClassMatching(regex, matchingClasses);
+ }
+
+ /**
+ * Searches through all of the suites and tests and loads only the test or test suites matching
+ * the regex text. This method also prevents a single test from being loaded multiple times by
+ * loading the suite first then loading tests from all non loaded suites.
+ *
+ * @param regex the regex text to search for
+ * @return the list of suite and/or test classes matching the regex.
+ */
+ private List<Class<?>> getSuiteOrTestMatchingRegex(final String regex, List<Class<?>>
+ runningList) {
+ // Get any test suites matching the regex using the superclass methods
+ runningList = getAllClassMatching(regex, runningList);
+
+
+ // Then search any test suites not retrieved already for test classes
+ // matching the regex.
+ List<Class<?>> unCollectedSuites = getAllClasses();
+ // If we already have a test suite then we don't want to load the test twice
+ // so remove the suite from the list
+ unCollectedSuites.removeAll(runningList);
+ for (Class<?> c : unCollectedSuites) {
+ // Prevents recursively adding tests/suites that have already been added
+ if (!runningList.contains(c)) {
+ try {
+ final AbstractTestSuite suite;
+ // Check the class to make sure that it is not a test class
+ if (areAnySuperClassesOfTypeAbstractTestSuite(c)) {
+ // Create a new instance of this class so that we can retrieve its
+ // data.
+ suite = (AbstractTestSuite) c.getDeclaredConstructor().newInstance();
+ // Add the tests from this suite that match the regex to the list of
+ // tests to run
+ runningList = suite.getSuiteOrTestMatchingRegex(regex, runningList);
+ }
+
+ } catch (NoSuchMethodException | InvocationTargetException | InstantiationException
+ | IllegalAccessException ex) {
+ // This shouldn't happen unless the constructor is changed in some
+ // way.
+ logger.log(Level.SEVERE, "Test suites can not take paramaters in their constructors.",
+ ex);
+ }
+ }
+ }
+ return runningList;
+ }
+
+ /**
+ * Searches through all of the suites and tests and loads only the test or test suites matching
+ * the regex text. This method also prevents a single test from being loaded multiple times by
+ * loading the suite first then loading tests from all non loaded suites.
+ *
+ * @param regex the regex text to search for
+ * @return the list of suite and/or test classes matching the regex.
+ */
+ protected List<Class<?>> getSuiteOrTestMatchingRegex(final String regex) {
+ final List<Class<?>> matchingClasses = new ArrayList<>();
+ return getSuiteOrTestMatchingRegex(regex, matchingClasses);
+ }
+
+
+ /**
+ * Retrieves all of the classes listed in the <code>@SuiteClasses</code> annotation.
+ *
+ * @return List of SuiteClasses
+ * @throws RuntimeException If the <code>@SuiteClasses</code> annotation is missing.
+ */
+ public List<Class<?>> getAllClasses() {
+ return getAnnotatedTestClasses();
+ }
+
+ /**
+ * Gets the name of all of the classes listed within the <code>@SuiteClasses</code> annotation.
+ *
+ * @return the list of classes.
+ * @throws RuntimeException If the <code>@SuiteClasses</code> annotation is missing.
+ */
+ public List<String> getAllClassName() {
+ List<String> classNames = new ArrayList<>();
+ for (Class<?> c : getAnnotatedTestClasses()) {
+ classNames.add(c.getName());
+ }
+ return classNames;
+ }
+}
diff --git a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/AbstractTestSuiteTest.java b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/AbstractTestSuiteTest.java
new file mode 100644
index 0000000..d788b81
--- /dev/null
+++ b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/AbstractTestSuiteTest.java
@@ -0,0 +1,154 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project. */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.test;
+
+import java.util.List;
+
+import org.junit.Before;
+import org.junit.Ignore;
+import org.junit.Test;
+import org.junit.runner.RunWith;
+import org.junit.runners.Suite;
+import org.junit.runners.Suite.SuiteClasses;
+
+import edu.wpi.first.wpilibj.test.AbstractTestSuite.ClassMethodPair;
+
+import static org.hamcrest.MatcherAssert.assertThat;
+import static org.hamcrest.Matchers.hasItems;
+import static org.hamcrest.Matchers.not;
+import static org.junit.Assert.assertEquals;
+
+/**
+ * Yes, this is the test system testing itself. Functionally, this is making sure that all tests get
+ * run correctly when you use parametrized arguments.
+ */
+@SuppressWarnings("MultipleTopLevelClasses")
+public class AbstractTestSuiteTest {
+ @Ignore("Prevents ANT from trying to run these as tests")
+ @RunWith(Suite.class)
+ @SuiteClasses({FirstSampleTest.class, SecondSampleTest.class, ThirdSampleTest.class,
+ FourthSampleTest.class, UnusualTest.class, ExampleSubSuite.class, EmptySuite.class})
+ class TestForAbstractTestSuite extends AbstractTestSuite {
+ }
+
+ TestForAbstractTestSuite m_testSuite;
+
+ @Before
+ public void setUp() {
+ m_testSuite = new TestForAbstractTestSuite();
+ }
+
+ @Test
+ public void testGetTestsMatchingAll() {
+ // when
+ List<Class<?>> collectedTests = m_testSuite.getAllClassMatching(".*");
+ // then
+ assertEquals(7, collectedTests.size());
+ }
+
+ @Test
+ public void testGetTestsMatchingSample() {
+ // when
+ List<Class<?>> collectedTests = m_testSuite.getAllClassMatching(".*Sample.*");
+ // then
+ assertEquals(4, collectedTests.size());
+ }
+
+ @Test
+ public void testGetTestsMatchingUnusual() {
+ // when
+ List<Class<?>> collectedTests = m_testSuite.getAllClassMatching(".*Unusual.*");
+ // then
+ assertEquals(1, collectedTests.size());
+ assertEquals(UnusualTest.class, collectedTests.get(0));
+ }
+
+ @Test
+ public void testGetTestsFromSuiteMatchingAll() {
+ // when
+ List<Class<?>> collectedTests = m_testSuite.getSuiteOrTestMatchingRegex(".*");
+ // then
+ assertEquals(7, collectedTests.size());
+ }
+
+ @Test
+ public void testGetTestsFromSuiteMatchingTest() {
+ // when
+ List<Class<?>> collectedTests = m_testSuite.getSuiteOrTestMatchingRegex(".*Test.*");
+ // then
+ assertEquals(7, collectedTests.size());
+ assertThat(collectedTests, hasItems(FirstSubSuiteTest.class,
+ SecondSubSuiteTest.class, UnusualTest.class));
+ assertThat(collectedTests,
+ not(hasItems(new Class<?>[]{ExampleSubSuite.class, EmptySuite.class})));
+ }
+
+ @Test
+ public void testGetMethodFromTest() {
+ // when
+ List<ClassMethodPair> pairs = m_testSuite.getMethodMatching(".*Method.*");
+ // then
+ assertEquals(1, pairs.size());
+ assertEquals(FirstSubSuiteTest.class, pairs.get(0).m_methodClass);
+ assertEquals(FirstSubSuiteTest.METHODNAME, pairs.get(0).m_methodName);
+
+ }
+
+}
+
+@SuppressWarnings("OneTopLevelClass")
+class FirstSampleTest {
+}
+
+@SuppressWarnings("OneTopLevelClass")
+class SecondSampleTest {
+}
+
+@SuppressWarnings("OneTopLevelClass")
+class ThirdSampleTest {
+}
+
+@SuppressWarnings("OneTopLevelClass")
+class FourthSampleTest {
+}
+
+@SuppressWarnings("OneTopLevelClass")
+class UnusualTest {
+} // This is a member of both suites
+
+
+@Ignore("Prevents ANT from trying to run these as tests")
+@SuppressWarnings("OneTopLevelClass")
+class FirstSubSuiteTest {
+ public static final String METHODNAME = "aTestMethod";
+
+ @Test
+ @SuppressWarnings("MethodName")
+ public void aTestMethod() {
+ }
+}
+
+@SuppressWarnings("OneTopLevelClass")
+class SecondSubSuiteTest {
+}
+
+
+@RunWith(Suite.class)
+@SuiteClasses({FirstSubSuiteTest.class, SecondSubSuiteTest.class, UnusualTest.class})
+@Ignore("Prevents ANT from trying to run these as tests")
+@SuppressWarnings("OneTopLevelClass")
+class ExampleSubSuite extends AbstractTestSuite {
+}
+
+
+@Ignore("Prevents ANT from trying to run these as tests")
+@RunWith(Suite.class)
+@SuiteClasses({})
+@SuppressWarnings("OneTopLevelClass")
+class EmptySuite extends AbstractTestSuite {
+}
diff --git a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/AntJunitLanucher.java b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/AntJunitLanucher.java
new file mode 100644
index 0000000..0350ea4
--- /dev/null
+++ b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/AntJunitLanucher.java
@@ -0,0 +1,91 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2018 FIRST. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project. */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.test;
+
+import java.io.File;
+
+import org.apache.tools.ant.BuildLogger;
+import org.apache.tools.ant.DefaultLogger;
+import org.apache.tools.ant.Project;
+import org.apache.tools.ant.taskdefs.optional.junit.FormatterElement;
+import org.apache.tools.ant.taskdefs.optional.junit.JUnitTask;
+import org.apache.tools.ant.taskdefs.optional.junit.JUnitTest;
+
+/**
+ * Provides an entry point for tests to run with ANT. This allows ant to output JUnit XML test
+ * results for Jenkins.
+ */
+public class AntJunitLanucher {
+ /**
+ * Main entry point for jenkins.
+ *
+ * @param args Arguments passed to java.
+ */
+ public static void main(String... args) {
+ if (args.length == 0) {
+ String path =
+ String.format("%s/%s", System.getProperty("user.dir"), "/testResults/AntReports");
+ String pathToReports = path;
+ Project project = new Project();
+
+ try {
+ // Create the file to store the test output
+ new File(pathToReports).mkdirs();
+
+ project.setProperty("java.io.tmpdir", pathToReports);
+
+ /* Output to screen */
+ FormatterElement.TypeAttribute typeScreen = new FormatterElement.TypeAttribute();
+ typeScreen.setValue("plain");
+ FormatterElement formatToScreen = new FormatterElement();
+ formatToScreen.setType(typeScreen);
+ formatToScreen.setUseFile(false);
+ formatToScreen.setOutput(System.out);
+
+ JUnitTask task = new JUnitTask();
+ task.addFormatter(formatToScreen);
+
+ // add a build listener to the project
+ BuildLogger logger = new DefaultLogger();
+ logger.setOutputPrintStream(System.out);
+ logger.setErrorPrintStream(System.err);
+ logger.setMessageOutputLevel(Project.MSG_INFO);
+ logger.setEmacsMode(true);
+ project.addBuildListener(logger);
+
+ task.setProject(project);
+
+ // Set the output to the XML file
+ FormatterElement.TypeAttribute type = new FormatterElement.TypeAttribute();
+ type.setValue("xml");
+
+ FormatterElement formater = new FormatterElement();
+ formater.setType(type);
+ task.addFormatter(formater);
+
+ // Create the JUnitTest
+ JUnitTest test = new JUnitTest(TestSuite.class.getName());
+ test.setTodir(new File(pathToReports));
+ task.addTest(test);
+
+ TestBench.out().println("Beginning Test Execution With ANT");
+ task.execute();
+ } catch (Exception ex) {
+ ex.printStackTrace();
+ }
+ } else {
+ TestBench.out().println(
+ "Run will not output XML for Jenkins because " + "tests are not being run with ANT");
+ // This should never return as it makes its own call to
+ // System.exit();
+ TestSuite.main(args);
+ }
+ System.exit(0);
+ }
+
+}
diff --git a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/QuickTest.java b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/QuickTest.java
new file mode 100644
index 0000000..87b05d0
--- /dev/null
+++ b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/QuickTest.java
@@ -0,0 +1,37 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2018 FIRST. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project. */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.test;
+
+import java.util.logging.Logger;
+
+import org.junit.Test;
+
+/**
+ * This class is designated to allow for simple testing of the library without the overlying testing
+ * framework. This test is NOT run as a normal part of the testing process and must be explicitly
+ * selected at runtime by using the 'quick' argument. This test should never be committed with
+ * changes to it but can be used during development to aid in feature testing.
+ */
+public class QuickTest extends AbstractComsSetup {
+ private static final Logger logger = Logger.getLogger(QuickTest.class.getName());
+
+ /*
+ * (non-Javadoc)
+ *
+ * @see edu.wpi.first.wpilibj.test.AbstractComsSetup#getClassLogger()
+ */
+ @Override
+ protected Logger getClassLogger() {
+ return logger;
+ }
+
+
+ @Test
+ public void test() {
+ }
+}
diff --git a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/RepeatRule.java b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/RepeatRule.java
new file mode 100644
index 0000000..deb0da8
--- /dev/null
+++ b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/RepeatRule.java
@@ -0,0 +1,65 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2018 FIRST. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project. */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.test;
+
+import java.lang.annotation.Retention;
+import java.lang.annotation.RetentionPolicy;
+import java.lang.annotation.Target;
+
+import org.junit.rules.TestRule;
+import org.junit.runner.Description;
+import org.junit.runners.model.Statement;
+
+/**
+ * This JUnit Rule allows you to apply this rule to any test to allow it to run multiple times. This
+ * is important if you have a test that fails only "sometimes" and needs to be rerun to find the
+ * issue.
+ *
+ * <p>This code was originally found here:
+ * <a href="http://www.codeaffine.com/2013/04/10/running-junit-tests-repeatedly-without-loops/">
+ * Running JUnit Tests Repeatedly Without Loops</a>
+ */
+public class RepeatRule implements TestRule {
+ @Retention(RetentionPolicy.RUNTIME)
+ @Target({java.lang.annotation.ElementType.METHOD})
+ public @interface Repeat {
+ /**
+ * The number of times to repeat the test.
+ */
+ int times();
+ }
+
+
+ private static class RepeatStatement extends Statement {
+ private final int m_times;
+ private final Statement m_statement;
+
+ private RepeatStatement(int times, Statement statement) {
+ m_times = times;
+ m_statement = statement;
+ }
+
+ @Override
+ public void evaluate() throws Throwable {
+ for (int i = 0; i < m_times; i++) {
+ m_statement.evaluate();
+ }
+ }
+ }
+
+ @Override
+ public Statement apply(Statement statement, Description description) {
+ Statement result = statement;
+ Repeat repeat = description.getAnnotation(Repeat.class);
+ if (repeat != null) {
+ int times = repeat.times();
+ result = new RepeatStatement(times, statement);
+ }
+ return result;
+ }
+}
diff --git a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/TestBench.java b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/TestBench.java
new file mode 100644
index 0000000..afd152f
--- /dev/null
+++ b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/TestBench.java
@@ -0,0 +1,358 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project. */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.test;
+
+import java.io.PrintStream;
+import java.util.ArrayList;
+import java.util.Arrays;
+import java.util.Collection;
+import java.util.List;
+
+import edu.wpi.first.wpilibj.AnalogGyro;
+import edu.wpi.first.wpilibj.AnalogInput;
+import edu.wpi.first.wpilibj.AnalogOutput;
+import edu.wpi.first.wpilibj.DigitalInput;
+import edu.wpi.first.wpilibj.Jaguar;
+import edu.wpi.first.wpilibj.Relay;
+import edu.wpi.first.wpilibj.Servo;
+import edu.wpi.first.wpilibj.Talon;
+import edu.wpi.first.wpilibj.Victor;
+import edu.wpi.first.wpilibj.fixtures.AnalogCrossConnectFixture;
+import edu.wpi.first.wpilibj.fixtures.DIOCrossConnectFixture;
+import edu.wpi.first.wpilibj.fixtures.MotorEncoderFixture;
+import edu.wpi.first.wpilibj.fixtures.RelayCrossConnectFixture;
+import edu.wpi.first.wpilibj.fixtures.TiltPanCameraFixture;
+
+/**
+ * This class provides access to all of the elements on the test bench, for use in fixtures. This
+ * class is a singleton, you should use {@link #getInstance()} to obtain a reference to the {@code
+ * TestBench}.
+ */
+public final class TestBench {
+ /**
+ * The time that it takes to have a motor go from rotating at full speed to completely stopped.
+ */
+ public static final double MOTOR_STOP_TIME = 0.25;
+
+ public static final int kTalonChannel = 10;
+ public static final int kVictorChannel = 1;
+ public static final int kJaguarChannel = 2;
+
+ /* TiltPanCamera Channels */
+ public static final int kGyroChannel = 0;
+ public static final double kGyroSensitivity = 0.013;
+ public static final int kTiltServoChannel = 9;
+ public static final int kPanServoChannel = 8;
+
+
+ /* PowerDistributionPanel channels */
+ public static final int kJaguarPDPChannel = 6;
+ public static final int kVictorPDPChannel = 8;
+ public static final int kTalonPDPChannel = 10;
+
+ // THESE MUST BE IN INCREMENTING ORDER
+ public static final int DIOCrossConnectB2 = 9;
+ public static final int DIOCrossConnectB1 = 8;
+ public static final int DIOCrossConnectA2 = 7;
+ public static final int DIOCrossConnectA1 = 6;
+
+ /**
+ * The Singleton instance of the Test Bench.
+ */
+ private static TestBench instance = null;
+
+ /**
+ * The single constructor for the TestBench. This method is private in order to prevent multiple
+ * TestBench objects from being allocated.
+ */
+ protected TestBench() {
+ }
+
+ /**
+ * Constructs a new set of objects representing a connected set of Talon controlled Motors and an
+ * encoder.
+ *
+ * @return a freshly allocated Talon, Encoder pair
+ */
+ public MotorEncoderFixture<Talon> getTalonPair() {
+ return new MotorEncoderFixture<Talon>() {
+ @Override
+ protected Talon giveSpeedController() {
+ return new Talon(kTalonChannel);
+ }
+
+ @Override
+ protected DigitalInput giveDigitalInputA() {
+ return new DigitalInput(0);
+ }
+
+ @Override
+ protected DigitalInput giveDigitalInputB() {
+ return new DigitalInput(1);
+ }
+
+ @Override
+ public int getPDPChannel() {
+ return kTalonPDPChannel;
+ }
+ };
+ }
+
+ /**
+ * Constructs a new set of objects representing a connected set of Victor controlled Motors and an
+ * encoder.
+ *
+ * @return a freshly allocated Victor, Encoder pair
+ */
+ public MotorEncoderFixture<Victor> getVictorPair() {
+ return new MotorEncoderFixture<Victor>() {
+ @Override
+ protected Victor giveSpeedController() {
+ return new Victor(kVictorChannel);
+ }
+
+ @Override
+ protected DigitalInput giveDigitalInputA() {
+ return new DigitalInput(2);
+ }
+
+ @Override
+ protected DigitalInput giveDigitalInputB() {
+ return new DigitalInput(3);
+ }
+
+ @Override
+ public int getPDPChannel() {
+ return kVictorPDPChannel;
+ }
+ };
+ }
+
+ /**
+ * Constructs a new set of objects representing a connected set of Jaguar controlled Motors and an
+ * encoder.
+ *
+ * @return a freshly allocated Jaguar, Encoder pair
+ */
+ public MotorEncoderFixture<Jaguar> getJaguarPair() {
+ return new MotorEncoderFixture<Jaguar>() {
+ @Override
+ protected Jaguar giveSpeedController() {
+ return new Jaguar(kJaguarChannel);
+ }
+
+ @Override
+ protected DigitalInput giveDigitalInputA() {
+ return new DigitalInput(4);
+ }
+
+ @Override
+ protected DigitalInput giveDigitalInputB() {
+ return new DigitalInput(5);
+ }
+
+ @Override
+ public int getPDPChannel() {
+ return kJaguarPDPChannel;
+ }
+ };
+ }
+
+ /**
+ * Constructs a new set of two Servo's and a Gyroscope.
+ *
+ * @return a freshly allocated Servo's and a freshly allocated Gyroscope
+ */
+ public TiltPanCameraFixture getTiltPanCam() {
+
+ return new TiltPanCameraFixture() {
+ @Override
+ protected AnalogGyro giveGyro() {
+ AnalogGyro gyro = new AnalogGyro(kGyroChannel);
+ gyro.setSensitivity(kGyroSensitivity);
+ return gyro;
+ }
+
+ @Override
+ protected AnalogGyro giveGyroParam(int center, double offset) {
+ AnalogGyro gyro = new AnalogGyro(kGyroChannel, center, offset);
+ gyro.setSensitivity(kGyroSensitivity);
+ return gyro;
+ }
+
+ @Override
+ protected Servo giveTilt() {
+ return new Servo(kTiltServoChannel);
+ }
+
+ @Override
+ protected Servo givePan() {
+ return new Servo(kPanServoChannel);
+ }
+ };
+ }
+
+ public DIOCrossConnectFixture getDIOCrossConnectFixture(int inputPort, int outputPort) {
+ return new DIOCrossConnectFixture(inputPort, outputPort);
+ }
+
+ /**
+ * Gets two lists of possible DIO pairs for the two pairs.
+ */
+ private List<List<Integer[]>> getDIOCrossConnect() {
+ List<List<Integer[]>> pairs = new ArrayList<List<Integer[]>>();
+ List<Integer[]> setA =
+ Arrays.asList(new Integer[][]{
+ {DIOCrossConnectA1, DIOCrossConnectA2},
+ {DIOCrossConnectA2, DIOCrossConnectA1}});
+ pairs.add(setA);
+
+ List<Integer[]> setB =
+ Arrays.asList(new Integer[][]{
+ {DIOCrossConnectB1, DIOCrossConnectB2},
+ {DIOCrossConnectB2, DIOCrossConnectB1}});
+ pairs.add(setB);
+ // NOTE: IF MORE DIOCROSSCONNECT PAIRS ARE ADDED ADD THEM HERE
+ return pairs;
+ }
+
+ @SuppressWarnings("JavadocMethod")
+ public static AnalogCrossConnectFixture getAnalogCrossConnectFixture() {
+ return new AnalogCrossConnectFixture() {
+ @Override
+ protected AnalogOutput giveAnalogOutput() {
+ return new AnalogOutput(0);
+ }
+
+ @Override
+ protected AnalogInput giveAnalogInput() {
+ return new AnalogInput(2);
+ }
+ };
+ }
+
+ @SuppressWarnings("JavadocMethod")
+ public static RelayCrossConnectFixture getRelayCrossConnectFixture() {
+ return new RelayCrossConnectFixture() {
+ @Override
+ protected Relay giveRelay() {
+ return new Relay(0);
+ }
+
+ @Override
+ protected DigitalInput giveInputTwo() {
+ return new DigitalInput(18);
+ }
+
+ @Override
+ protected DigitalInput giveInputOne() {
+ return new DigitalInput(19);
+ }
+ };
+ }
+
+ /**
+ * Return a single Collection containing all of the DIOCrossConnectFixtures in all two pair
+ * combinations.
+ *
+ * @return pairs of DIOCrossConnectFixtures
+ */
+ public Collection<Integer[]> getDIOCrossConnectCollection() {
+ Collection<Integer[]> pairs = new ArrayList<Integer[]>();
+ for (Collection<Integer[]> collection : getDIOCrossConnect()) {
+ pairs.addAll(collection);
+ }
+ return pairs;
+ }
+
+ /**
+ * Gets an array of pairs for the encoder to use using two different lists.
+ *
+ * @param flip whether this encoder needs to be flipped
+ * @return A list of different inputs to use for the tests
+ */
+ private Collection<Integer[]> getPairArray(List<Integer[]> listA, List<Integer[]> listB,
+ boolean flip) {
+ Collection<Integer[]> encoderPortPairs = new ArrayList<Integer[]>();
+ for (Integer[] portPairsA : listA) {
+ Integer[] inputs = new Integer[5];
+ inputs[0] = portPairsA[0]; // InputA
+ inputs[1] = portPairsA[1]; // InputB
+
+ for (Integer[] portPairsB : listB) {
+ inputs[2] = portPairsB[0]; // OutputA
+ inputs[3] = portPairsB[1]; // OutputB
+ inputs[4] = flip ? 0 : 1; // The flip bit
+ }
+
+ ArrayList<Integer[]> construtorInput = new ArrayList<Integer[]>();
+ construtorInput.add(inputs);
+
+ inputs = inputs.clone();
+ for (Integer[] portPairsB : listB) {
+ inputs[2] = portPairsB[1]; // OutputA
+ inputs[3] = portPairsB[0]; // OutputB
+ inputs[4] = flip ? 0 : 1; // The flip bit
+ }
+ construtorInput.add(inputs);
+ encoderPortPairs.addAll(construtorInput);
+ }
+ return encoderPortPairs;
+ }
+
+ /**
+ * Constructs the list of inputs to be used for the encoder test.
+ *
+ * @return A collection of different input pairs to use for the encoder
+ */
+ public Collection<Integer[]> getEncoderDIOCrossConnectCollection() {
+ Collection<Integer[]> encoderPortPairs = new ArrayList<Integer[]>();
+ assert getDIOCrossConnect().size() == 2;
+ encoderPortPairs.addAll(getPairArray(getDIOCrossConnect().get(0), getDIOCrossConnect().get(1),
+ false));
+ encoderPortPairs.addAll(getPairArray(getDIOCrossConnect().get(1), getDIOCrossConnect().get(0),
+ false));
+ assert encoderPortPairs.size() == 8;
+ return encoderPortPairs;
+ }
+
+ /**
+ * Gets the singleton of the TestBench. If the TestBench is not already allocated in constructs an
+ * new instance of it. Otherwise it returns the existing instance.
+ *
+ * @return The Singleton instance of the TestBench
+ */
+ public static TestBench getInstance() {
+ if (instance == null) {
+ instance = new TestBench();
+ }
+ return instance;
+ }
+
+ /**
+ * Provides access to the output stream for the test system. This should be used instead of
+ * System.out This is gives us a way to implement changes to where the output text of this test
+ * system is sent.
+ *
+ * @return The test bench global print stream.
+ */
+ public static PrintStream out() {
+ return System.out;
+ }
+
+ /**
+ * Provides access to the error stream for the test system. This should be used instead of
+ * System.err This is gives us a way to implement changes to where the output text of this test
+ * system is sent.
+ *
+ * @return The test bench global print stream.
+ */
+ public static PrintStream err() {
+ return System.err;
+ }
+}
diff --git a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/TestSuite.java b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/TestSuite.java
new file mode 100644
index 0000000..31b3b0d
--- /dev/null
+++ b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/TestSuite.java
@@ -0,0 +1,378 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project. */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.test;
+
+import java.io.IOException;
+import java.io.InputStream;
+import java.util.ArrayList;
+import java.util.Arrays;
+import java.util.List;
+import java.util.Objects;
+import java.util.logging.LogManager;
+import java.util.logging.Logger;
+import java.util.regex.Pattern;
+
+import org.junit.runner.JUnitCore;
+import org.junit.runner.Result;
+import org.junit.runner.RunWith;
+import org.junit.runner.notification.Failure;
+import org.junit.runners.Suite;
+import org.junit.runners.Suite.SuiteClasses;
+
+import junit.framework.JUnit4TestAdapter;
+import junit.runner.Version;
+
+import edu.wpi.first.wpilibj.WpiLibJTestSuite;
+
+/**
+ * The WPILibJ Integeration Test Suite collects all of the tests to be run by junit. In order for a
+ * test to be run, it must be added the list of suite classes below. The tests will be run in the
+ * order they are listed in the suite classes annotation.
+ */
+@RunWith(Suite.class)
+@SuiteClasses(WpiLibJTestSuite.class)
+public class TestSuite extends AbstractTestSuite {
+ static {
+ // Sets up the logging output
+ final InputStream inputStream = TestSuite.class.getResourceAsStream("/logging.properties");
+ try {
+ Objects.requireNonNull(inputStream, "./logging.properties was not loaded");
+ LogManager.getLogManager().readConfiguration(inputStream);
+ Logger.getAnonymousLogger().info("Loaded");
+ } catch (final IOException | NullPointerException ex) {
+ Logger.getAnonymousLogger().severe("Could not load default logging.properties file");
+ Logger.getAnonymousLogger().severe(ex.getMessage());
+ }
+
+ TestBench.out().println("Starting Tests");
+ }
+
+ private static final Logger WPILIBJ_ROOT_LOGGER = Logger.getLogger("edu.wpi.first.wpilibj");
+ private static final Logger WPILIBJ_COMMAND_ROOT_LOGGER = Logger
+ .getLogger("edu.wpi.first.wpilibj.command");
+
+
+ private static final Class<?> QUICK_TEST = QuickTest.class;
+ private static final String QUICK_TEST_FLAG = "--quick";
+ private static final String HELP_FLAG = "--help";
+ private static final String METHOD_NAME_FILTER = "--methodFilter=";
+ private static final String METHOD_REPEAT_FILTER = "--repeat=";
+ private static final String CLASS_NAME_FILTER = "--filter=";
+
+ private static TestSuite instance = null;
+
+ /**
+ * Get the singleton instance of the test suite.
+ */
+ public static TestSuite getInstance() {
+ if (instance == null) {
+ instance = new TestSuite();
+ }
+ return instance;
+ }
+
+ /**
+ * This has to be public so that the JUnit4.
+ */
+ public TestSuite() {
+ }
+
+ /**
+ * Displays a help message for the user when they use the --help flag at runtime.
+ */
+ protected static void displayHelp() {
+ StringBuilder helpMessage = new StringBuilder("Test Parameters help: \n");
+ helpMessage.append("\t" + QUICK_TEST_FLAG
+ + " will cause the quick test to be run. Ignores other flags except for "
+ + METHOD_REPEAT_FILTER + "\n");
+ helpMessage.append("\t" + CLASS_NAME_FILTER
+ + " will use the supplied regex text to search for suite/test class names "
+ + "matching the regex and run them.\n");
+ helpMessage.append("\t" + METHOD_NAME_FILTER
+ + " will use the supplied regex text to search for test methods (excluding methods "
+ + "with the @Ignore annotation) and run only those methods. Can be paired with "
+ + METHOD_REPEAT_FILTER + " to " + "repeat the selected tests multiple times.\n");
+ helpMessage.append("\t" + METHOD_REPEAT_FILTER + " will repeat the tests selected with either "
+ + QUICK_TEST_FLAG + " or " + CLASS_NAME_FILTER
+ + " and run them the given number of times.\n");
+ helpMessage
+ .append("[NOTE] All regex uses the syntax defined by java.util.regex.Pattern. This "
+ + "documentation can be found at "
+ + "http://docs.oracle.com/javase/7/docs/api/java/util/regex/Pattern.html\n");
+ helpMessage.append("\n");
+ helpMessage.append("\n");
+
+ TestBench.out().println(helpMessage);
+ }
+
+ /**
+ * Lets the user know that they used the TestSuite improperly and gives details about how to use
+ * it correctly in the future.
+ */
+ protected static void displayInvalidUsage(String message, String... args) {
+ StringBuilder invalidMessage = new StringBuilder("Invalid Usage: " + message + "\n");
+ invalidMessage.append("Params received: ");
+ for (String a : args) {
+ invalidMessage.append(a + " ");
+ }
+ invalidMessage.append("\n");
+ invalidMessage
+ .append("For details on proper usage of the runtime flags please run again with the "
+ + HELP_FLAG + " flag.\n\n");
+
+ TestBench.out().println(invalidMessage);
+
+ }
+
+ /**
+ * Prints the loaded tests before they are run.
+ *
+ * @param classes the classes that were loaded.
+ */
+ protected static void printLoadedTests(final Class<?>... classes) {
+ StringBuilder loadedTestsMessage = new StringBuilder("The following tests were loaded:\n");
+ Package packagE = null;
+ for (Class<?> c : classes) {
+ if (c.getPackage().equals(packagE)) {
+ packagE = c.getPackage();
+ loadedTestsMessage.append(packagE.getName() + "\n");
+ }
+ loadedTestsMessage.append("\t" + c.getSimpleName() + "\n");
+ }
+ TestBench.out().println(loadedTestsMessage);
+ }
+
+
+ /**
+ * Parses the arguments passed at runtime and runs the appropriate tests based upon these
+ * arguments.
+ *
+ * @param args the args passed into the program at runtime
+ * @return the restults of the tests that have run. If no tests were run then null is returned.
+ */
+ protected static Result parseArgsRunAndGetResult(final String[] args) {
+ if (args.length == 0) { // If there are no args passed at runtime then just
+ // run all of the tests.
+ printLoadedTests(TestSuite.class);
+ return JUnitCore.runClasses(TestSuite.class);
+ }
+
+ // The method filter was passed
+ boolean methodFilter = false;
+ String methodRegex = "";
+ // The class filter was passed
+ boolean classFilter = false;
+ String classRegex = "";
+ int repeatCount = 1;
+
+ for (String s : args) {
+ if (Pattern.matches(METHOD_NAME_FILTER + ".*", s)) {
+ methodFilter = true;
+ methodRegex = new String(s).replace(METHOD_NAME_FILTER, "");
+ }
+ if (Pattern.matches(METHOD_REPEAT_FILTER + ".*", s)) {
+ try {
+ repeatCount = Integer.parseInt(new String(s).replace(METHOD_REPEAT_FILTER, ""));
+ } catch (NumberFormatException ex) {
+ displayInvalidUsage("The argument passed to the repeat rule was not a valid integer.",
+ args);
+ }
+ }
+ if (Pattern.matches(CLASS_NAME_FILTER + ".*", s)) {
+ classFilter = true;
+ classRegex = s.replace(CLASS_NAME_FILTER, "");
+ }
+ }
+
+
+ ArrayList<String> argsParsed = new ArrayList<String>(Arrays.asList(args));
+ if (argsParsed.contains(HELP_FLAG)) {
+ // If the user inputs the help flag then return the help message and exit
+ // without running any tests
+ displayHelp();
+ return null;
+ }
+ if (argsParsed.contains(QUICK_TEST_FLAG)) {
+ printLoadedTests(QUICK_TEST);
+ return JUnitCore.runClasses(QUICK_TEST);
+ }
+
+ /**
+ * Stores the data from multiple {@link Result}s in one class that can be
+ * returned to display the results.
+ */
+ class MultipleResult extends Result {
+ private static final long serialVersionUID = 1L;
+ private final List<Failure> m_failures = new ArrayList<>();
+ private int m_runCount = 0;
+ private int m_ignoreCount = 0;
+ private long m_runTime = 0;
+
+ @Override
+ public int getRunCount() {
+ return m_runCount;
+ }
+
+ @Override
+ public int getFailureCount() {
+ return m_failures.size();
+ }
+
+ @Override
+ public long getRunTime() {
+ return m_runTime;
+ }
+
+ @Override
+ public List<Failure> getFailures() {
+ return m_failures;
+ }
+
+ @Override
+ public int getIgnoreCount() {
+ return m_ignoreCount;
+ }
+
+ /**
+ * Adds the given result's data to this result.
+ *
+ * @param result the result to add to this result
+ */
+ void addResult(Result result) {
+ m_failures.addAll(result.getFailures());
+ m_runCount += result.getRunCount();
+ m_ignoreCount += result.getIgnoreCount();
+ m_runTime += result.getRunTime();
+ }
+ }
+
+ // If a specific method has been requested
+ if (methodFilter) {
+ List<ClassMethodPair> pairs = (new TestSuite()).getMethodMatching(methodRegex);
+ if (pairs.size() == 0) {
+ displayInvalidUsage("None of the arguments passed to the method name filter matched.",
+ args);
+ return null;
+ }
+ // Print out the list of tests before we run them
+ TestBench.out().println("Running the following tests:");
+ Class<?> classListing = null;
+ for (ClassMethodPair p : pairs) {
+ if (!p.m_methodClass.equals(classListing)) {
+ // Only display the class name every time it changes
+ classListing = p.m_methodClass;
+ TestBench.out().println(classListing);
+ }
+ TestBench.out().println("\t" + p.m_methodName);
+ }
+
+
+ // The test results will be saved here
+ MultipleResult results = new MultipleResult();
+ // Runs tests multiple times if the repeat rule is used
+ for (int i = 0; i < repeatCount; i++) {
+ // Now run all of the tests
+ for (ClassMethodPair p : pairs) {
+ Result result = (new JUnitCore()).run(p.getMethodRunRequest());
+ // Store the given results in one cohesive result
+ results.addResult(result);
+ }
+ }
+
+ return results;
+ }
+
+ // If a specific class has been requested
+ if (classFilter) {
+ List<Class<?>> testClasses = (new TestSuite()).getSuiteOrTestMatchingRegex(classRegex);
+ if (testClasses.size() == 0) {
+ displayInvalidUsage("None of the arguments passed to the filter matched.", args);
+ return null;
+ }
+ printLoadedTests(testClasses.toArray(new Class[0]));
+ MultipleResult results = new MultipleResult();
+ // Runs tests multiple times if the repeat rule is used
+ for (int i = 0; i < repeatCount; i++) {
+ Result result = (new JUnitCore()).run(testClasses.toArray(new Class[0]));
+ // Store the given results in one cohesive result
+ results.addResult(result);
+ }
+ return results;
+ }
+ displayInvalidUsage(
+ "None of the parameters that you passed matched any of the accepted flags.", args);
+
+ return null;
+ }
+
+ protected static void displayResults(Result result) {
+ // Results are collected and displayed here
+ TestBench.out().println("\n");
+ if (!result.wasSuccessful()) {
+ // Prints out a list of stack traces for the failed tests
+ TestBench.out().println("Failure List: ");
+ for (Failure f : result.getFailures()) {
+ TestBench.out().println(f.getDescription());
+ TestBench.out().println(f.getTrace());
+ }
+ TestBench.out().println();
+ TestBench.out().println("FAILURES!!!");
+ // Print the test statistics
+ TestBench.out().println(
+ "Tests run: " + result.getRunCount() + ", Failures: " + result.getFailureCount()
+ + ", Ignored: " + result.getIgnoreCount() + ", In " + result.getRunTime() + "ms");
+
+ // Prints out a list of test that failed
+ TestBench.out().println("Failure List (short):");
+ String failureClass = result.getFailures().get(0).getDescription().getClassName();
+ TestBench.out().println(failureClass);
+ for (Failure f : result.getFailures()) {
+ if (!failureClass.equals(f.getDescription().getClassName())) {
+ failureClass = f.getDescription().getClassName();
+ TestBench.out().println(failureClass);
+ }
+ TestBench.err().println("\t" + f.getDescription());
+ }
+ } else {
+ TestBench.out().println("SUCCESS!");
+ TestBench.out().println(
+ "Tests run: " + result.getRunCount() + ", Ignored: " + result.getIgnoreCount() + ", In "
+ + result.getRunTime() + "ms");
+ }
+ TestBench.out().println();
+ }
+
+ /**
+ * This is used by ant to get the Junit tests. This is required because the tests try to load
+ * using a JUnit 3 framework. JUnit4 uses annotations to load tests. This method allows JUnit3 to
+ * load JUnit4 tests.
+ */
+ public static junit.framework.Test suite() {
+ return new JUnit4TestAdapter(TestSuite.class);
+ }
+
+
+ /**
+ * The method called at runtime.
+ *
+ * @param args The test suites to run
+ */
+ public static void main(String[] args) {
+ TestBench.out().println("JUnit version " + Version.id());
+
+ // Tests are run here
+ Result result = parseArgsRunAndGetResult(args);
+ if (result != null) {
+ // Results are collected and displayed here
+ displayResults(result);
+
+ System.exit(result.wasSuccessful() ? 0 : 1);
+ }
+ System.exit(1);
+ }
+}
diff --git a/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/package-info.java b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/package-info.java
new file mode 100644
index 0000000..481cb08
--- /dev/null
+++ b/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/package-info.java
@@ -0,0 +1,18 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-2018 FIRST. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project. */
+/*----------------------------------------------------------------------------*/
+
+/**
+ * This is the starting point for the integration testing framework. This package should contain
+ * classes that are not explicitly for testing the library but instead provide the framework that
+ * the tests can extend from. Every test should extend from
+ * {@link edu.wpi.first.wpilibj.test.AbstractComsSetup}
+ * to ensure that Network Communications is properly instantiated before the test is run. The
+ * {@link edu.wpi.first.wpilibj.test.TestBench} should contain the port numbers for all of the
+ * hardware and these values should not be explicitly defined anywhere else in the testing
+ * framework.
+ */
+package edu.wpi.first.wpilibj.test;
diff --git a/wpilibjIntegrationTests/src/main/resources/logging.properties b/wpilibjIntegrationTests/src/main/resources/logging.properties
new file mode 100644
index 0000000..b15c534
--- /dev/null
+++ b/wpilibjIntegrationTests/src/main/resources/logging.properties
@@ -0,0 +1,25 @@
+# "handlers" specifies a comma separated list of log Handler
+# classes. These handlers will be installed during VM startup.
+# By default we only configure a ConsoleHandler, which will only
+# show messages at the INFO and above levels.
+handlers=java.util.logging.ConsoleHandler
+# Default global logging level.
+# This specifies which kinds of events are logged across
+# all loggers. For any given facility this global level
+# can be overriden by a facility specific level
+# Note that the ConsoleHandler also has a separate level
+# setting to limit messages printed to the console.
+#.level= INFO
+.level=INFO
+############################################################
+# Handler specific properties.
+# Describes specific configuration info for Handlers.
+############################################################
+java.util.logging.ConsoleHandler.level=FINER
+java.util.logging.ConsoleHandler.formatter=java.util.logging.SimpleFormatter
+############################################################
+# Facility specific properties.
+# Provides extra control for each logger.
+############################################################
+edu.wpi.first.wpilibj.level=INFO
+edu.wpi.first.wpilibj.command.level=INFO