diff --git a/wpilibj/wpilibJavaIntegrationTests/src/main/java/edu/wpi/first/wpilibj/AnalogCrossConnectTest.java b/wpilibj/wpilibJavaIntegrationTests/src/main/java/edu/wpi/first/wpilibj/AnalogCrossConnectTest.java new file mode 100644 index 0000000000..b6f08d04b6 --- /dev/null +++ b/wpilibj/wpilibJavaIntegrationTests/src/main/java/edu/wpi/first/wpilibj/AnalogCrossConnectTest.java @@ -0,0 +1,84 @@ +/*----------------------------------------------------------------------------*/ +/* Copyright (c) FIRST 2008-2014. 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 static org.junit.Assert.*; + +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 edu.wpi.first.wpilibj.fixtures.AnalogCrossConnectFixture; +import edu.wpi.first.wpilibj.test.AbstractComsSetup; +import edu.wpi.first.wpilibj.test.TestBench; + +/** + * @author jonathanleitschuh + * + */ +public class AnalogCrossConnectTest extends AbstractComsSetup { + private static final Logger logger = Logger.getLogger(AnalogCrossConnectTest.class.getName()); + + private static AnalogCrossConnectFixture analogIO; + + static final double kDelayTime = 0.05; + + @Override + protected Logger getClassLogger() { + return logger; + } + + + /** + * @throws java.lang.Exception + */ + @BeforeClass + public static void setUpBeforeClass() throws Exception { + analogIO = TestBench.getAnalogCrossConnectFixture(); + } + + /** + * @throws java.lang.Exception + */ + @AfterClass + public static void tearDownAfterClass() throws Exception { + analogIO.teardown(); + } + + /** + * @throws java.lang.Exception + */ + @Before + public void setUp() throws Exception { + analogIO.setup(); + } + + /** + * @throws java.lang.Exception + */ + @After + public void tearDown() throws Exception { + } + + @Test + public void testAnalogOuput() { + for(int i = 0; i < 50; i++) { + analogIO.getOutput().setVoltage(i / 10.0f); + Timer.delay(kDelayTime); + assertEquals(analogIO.getOutput().getVoltage(), analogIO.getInput().getVoltage(), 0.01); + } + } + + @Test(expected=RuntimeException.class) + public void testRuntimeExceptionOnInvalidAccumulatorPort(){ + analogIO.getInput().getAccumulatorCount(); + } +} diff --git a/wpilibj/wpilibJavaIntegrationTests/src/main/java/edu/wpi/first/wpilibj/PIDTest.java b/wpilibj/wpilibJavaIntegrationTests/src/main/java/edu/wpi/first/wpilibj/PIDTest.java index 41f287159e..4c73652e49 100644 --- a/wpilibj/wpilibJavaIntegrationTests/src/main/java/edu/wpi/first/wpilibj/PIDTest.java +++ b/wpilibj/wpilibJavaIntegrationTests/src/main/java/edu/wpi/first/wpilibj/PIDTest.java @@ -76,7 +76,7 @@ public class PIDTest extends AbstractComsSetup { double kp = 0.003; double ki = 0.0015; double kd = 0.0; - for(int i = 0; i < 5; i++){ + 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()}, diff --git a/wpilibj/wpilibJavaIntegrationTests/src/main/java/edu/wpi/first/wpilibj/RelayCrossConnectTest.java b/wpilibj/wpilibJavaIntegrationTests/src/main/java/edu/wpi/first/wpilibj/RelayCrossConnectTest.java new file mode 100644 index 0000000000..53483158f4 --- /dev/null +++ b/wpilibj/wpilibJavaIntegrationTests/src/main/java/edu/wpi/first/wpilibj/RelayCrossConnectTest.java @@ -0,0 +1,114 @@ +/*----------------------------------------------------------------------------*/ +/* Copyright (c) FIRST 2008-2014. 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 static org.junit.Assert.assertEquals; +import static org.junit.Assert.assertFalse; +import static org.junit.Assert.assertTrue; + +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 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.RelayCrossConnectFxiture; +import edu.wpi.first.wpilibj.networktables.NetworkTable; +import edu.wpi.first.wpilibj.test.AbstractComsSetup; +import edu.wpi.first.wpilibj.test.TestBench; + +/** + * @author jonathanleitschuh + * + */ +public class RelayCrossConnectTest extends AbstractComsSetup { + private static final Logger logger = Logger.getLogger(RelayCrossConnectTest.class.getName()); + private static final NetworkTable table = NetworkTable.getTable("_RELAY_CROSS_CONNECT_TEST_"); + private RelayCrossConnectFxiture relayFixture; + + + /** + * @throws java.lang.Exception + */ + @Before + public void setUp() throws Exception { + relayFixture = TestBench.getRelayCrossConnectFixture(); + relayFixture.setup(); + relayFixture.getRelay().initTable(table); + } + + /** + * @throws java.lang.Exception + */ + @After + public void tearDown() throws Exception { + relayFixture.reset(); + relayFixture.teardown(); + } + + @Test + public void testBothHigh() { + relayFixture.getRelay().setDirection(Direction.kBoth); + relayFixture.getRelay().set(Value.kOn); + relayFixture.getRelay().updateTable(); + assertTrue("Input one was not high when relay set both high", relayFixture.getInputOne().get()); + assertTrue("Input two was not high when relay set both high", relayFixture.getInputTwo().get()); + assertEquals("On", table.getString("Value")); + } + + @Test + public void testFirstHigh() { + relayFixture.getRelay().setDirection(Direction.kBoth); + relayFixture.getRelay().set(Value.kForward); + relayFixture.getRelay().updateTable(); + assertFalse("Input one was not low when relay set Value.kForward", relayFixture.getInputOne().get()); + assertTrue("Input two was not high when relay set Value.kForward", relayFixture.getInputTwo().get()); + assertEquals("Forward", table.getString("Value")); + } + + @Test + public void testSecondHigh() { + relayFixture.getRelay().setDirection(Direction.kBoth); + relayFixture.getRelay().set(Value.kReverse); + relayFixture.getRelay().updateTable(); + assertTrue("Input one was not high when relay set Value.kReverse", relayFixture.getInputOne().get()); + assertFalse("Input two was not low when relay set Value.kReverse", relayFixture.getInputTwo().get()); + assertEquals("Reverse", table.getString("Value")); + } + + @Test(expected=InvalidValueException.class) + public void testSetValueForwardWithDirectionReverseThrowingException(){ + relayFixture.getRelay().setDirection(Direction.kForward); + relayFixture.getRelay().set(Value.kReverse); + } + + @Test(expected=InvalidValueException.class) + public void testSetValueReverseWithDirectionForwardThrowingException(){ + relayFixture.getRelay().setDirection(Direction.kReverse); + relayFixture.getRelay().set(Value.kForward); + } + + @Test + public void testInitialSettings(){ + assertEquals(Value.kOff, relayFixture.getRelay().get()); + //Initially both outputs should be off + assertFalse(relayFixture.getInputOne().get()); + assertFalse(relayFixture.getInputTwo().get()); + assertEquals("Off", table.getString("Value")); + } + + @Override + protected Logger getClassLogger() { + return logger; + } + +} diff --git a/wpilibj/wpilibJavaIntegrationTests/src/main/java/edu/wpi/first/wpilibj/WpiLibJTestSuite.java b/wpilibj/wpilibJavaIntegrationTests/src/main/java/edu/wpi/first/wpilibj/WpiLibJTestSuite.java new file mode 100644 index 0000000000..cd8754f1d5 --- /dev/null +++ b/wpilibj/wpilibJavaIntegrationTests/src/main/java/edu/wpi/first/wpilibj/WpiLibJTestSuite.java @@ -0,0 +1,33 @@ +/*----------------------------------------------------------------------------*/ +/* Copyright (c) FIRST 2008-2014. 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; + +/** + * @author jonathanleitschuh + * + */ +@RunWith(Suite.class) +@SuiteClasses({ + AnalogCrossConnectTest.class, + CounterTest.class, + DIOCrossConnectTest.class, + EncoderTest.class, + MotorEncoderTest.class, + PIDTest.class, + PrefrencesTest.class, + RelayCrossConnectTest.class, + SampleTest.class, + TiltPanCameraTest.class, + TimerTest.class + }) +public class WpiLibJTestSuite { + +} diff --git a/wpilibj/wpilibJavaIntegrationTests/src/main/java/edu/wpi/first/wpilibj/command/CommandTestSuite.java b/wpilibj/wpilibJavaIntegrationTests/src/main/java/edu/wpi/first/wpilibj/command/CommandTestSuite.java new file mode 100644 index 0000000000..02fdf091d0 --- /dev/null +++ b/wpilibj/wpilibJavaIntegrationTests/src/main/java/edu/wpi/first/wpilibj/command/CommandTestSuite.java @@ -0,0 +1,29 @@ +/*----------------------------------------------------------------------------*/ +/* Copyright (c) FIRST 2008-2014. 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.command; + +import org.junit.runner.RunWith; +import org.junit.runners.Suite; +import org.junit.runners.Suite.SuiteClasses; + +/** + * @author jonathanleitschuh + * + */ +@RunWith(Suite.class) +@SuiteClasses({ + ButtonTest.class, + CommandParallelGroupTest.class, + CommandScheduleTest.class, + CommandSequentialGroupTest.class, + CommandSupersedeTest.class, + CommandTimeoutTest.class, + DefaultCommandTest.class + }) +public class CommandTestSuite { + +} diff --git a/wpilibj/wpilibJavaIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/AnalogCrossConnectFixture.java b/wpilibj/wpilibJavaIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/AnalogCrossConnectFixture.java new file mode 100644 index 0000000000..d9680e4174 --- /dev/null +++ b/wpilibj/wpilibJavaIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/AnalogCrossConnectFixture.java @@ -0,0 +1,76 @@ +/*----------------------------------------------------------------------------*/ +/* Copyright (c) FIRST 2008-2014. 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; + +/** + * @author jonathanleitschuh + * + */ +public abstract class AnalogCrossConnectFixture implements ITestFixture{ + private boolean initialized = false; + + private AnalogInput input; + private AnalogOutput output; + + abstract protected AnalogInput giveAnalogInput(); + abstract protected AnalogOutput giveAnalogOutput(); + + + private void initialize(){ + synchronized(this){ + if(!initialized){ + input = giveAnalogInput(); + output = giveAnalogOutput(); + initialized = true; + } + } + } + /* (non-Javadoc) + * @see edu.wpi.first.wpilibj.fixtures.ITestFixture#setup() + */ + @Override + public boolean setup() { + initialize(); + 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() { + input.free(); + output.free(); + return true; + } + + /** + * @return + */ + final public AnalogOutput getOutput() { + initialize(); + return output; + } + + final public AnalogInput getInput() { + initialize(); + return input; + } + + +} diff --git a/wpilibj/wpilibJavaIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/MotorEncoderFixture.java b/wpilibj/wpilibJavaIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/MotorEncoderFixture.java index fe2120fee1..056bb32bf8 100644 --- a/wpilibj/wpilibJavaIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/MotorEncoderFixture.java +++ b/wpilibj/wpilibJavaIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/MotorEncoderFixture.java @@ -62,19 +62,21 @@ public abstract class MotorEncoderFixture implements ITestFixture { abstract protected DigitalInput giveDigitalInputB(); final private void initialize(){ - if(!initialized){ - aSource = giveDigitalInputA(); - bSource = giveDigitalInputB(); - - motor = giveSpeedController(); - - encoder = new Encoder(aSource, bSource); - counters[0] = new Counter(aSource); - counters[1] = new Counter(bSource); - for(Counter c: counters){ - c.start(); + synchronized(this){ + if(!initialized){ + aSource = giveDigitalInputA(); + bSource = giveDigitalInputB(); + + motor = giveSpeedController(); + + encoder = new Encoder(aSource, bSource); + counters[0] = new Counter(aSource); + counters[1] = new Counter(bSource); + for(Counter c: counters){ + c.start(); + } + initialized = true; } - initialized = true; } } @@ -122,8 +124,7 @@ public abstract class MotorEncoderFixture implements ITestFixture { * This is used instead of equals() because doubles can have inaccuracies. * @param value The value to compare against * @param acuracy The accuracy range to check against to see if the - * @return true if the range of values between motors speed accuracy contains the 'value'
- * {@code Math.abs((Math.abs(motor.get()) - Math.abs(value))) < Math.abs(accuracy)} + * @return true if the range of values between motors speed accuracy contains the 'value'. */ public boolean isMotorSpeedWithinRange(double value, double accuracy){ initialize(); diff --git a/wpilibj/wpilibJavaIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/RelayCrossConnectFxiture.java b/wpilibj/wpilibJavaIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/RelayCrossConnectFxiture.java new file mode 100644 index 0000000000..f33db992d8 --- /dev/null +++ b/wpilibj/wpilibJavaIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/RelayCrossConnectFxiture.java @@ -0,0 +1,94 @@ +/*----------------------------------------------------------------------------*/ +/* Copyright (c) FIRST 2008-2014. 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; +import edu.wpi.first.wpilibj.Relay.Direction; +import edu.wpi.first.wpilibj.Relay.Value; + +/** + * @author jonathanleitschuh + * + */ +public abstract class RelayCrossConnectFxiture implements ITestFixture { + + private DigitalInput inputOne; + private DigitalInput inputTwo; + private Relay relay; + + private boolean initialized = false; + private boolean freed = false; + + + + protected abstract Relay giveRelay(); + + protected abstract DigitalInput giveInputOne(); + + protected abstract DigitalInput giveInputTwo(); + + private void initialize(){ + synchronized(this){ + if(!initialized){ + relay = giveRelay(); + inputOne = giveInputOne(); + inputTwo = giveInputTwo(); + initialized = true; + } + } + } + + public Relay getRelay(){ + initialize(); + return relay; + } + + public DigitalInput getInputOne(){ + initialize(); + return inputOne; + } + + public DigitalInput getInputTwo(){ + initialize(); + return 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(!freed){ + relay.free(); + inputOne.free(); + inputTwo.free(); + freed = true; + } else { + throw new RuntimeException("You attempted to free the " + RelayCrossConnectFxiture.class.getSimpleName() + " multiple times"); + } + return true; + } +} diff --git a/wpilibj/wpilibJavaIntegrationTests/src/main/java/edu/wpi/first/wpilibj/smartdashboard/SmartDashboardTestSuite.java b/wpilibj/wpilibJavaIntegrationTests/src/main/java/edu/wpi/first/wpilibj/smartdashboard/SmartDashboardTestSuite.java new file mode 100644 index 0000000000..6d516c0353 --- /dev/null +++ b/wpilibj/wpilibJavaIntegrationTests/src/main/java/edu/wpi/first/wpilibj/smartdashboard/SmartDashboardTestSuite.java @@ -0,0 +1,26 @@ +/*----------------------------------------------------------------------------*/ +/* Copyright (c) FIRST 2008-2014. 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.smartdashboard; + +import org.junit.runner.RunWith; +import org.junit.runners.Suite; +import org.junit.runners.Suite.SuiteClasses; + +import junit.framework.Test; +import junit.framework.TestCase; +import junit.framework.TestSuite; + +/** + * @author jonathanleitschuh + * + */ +@RunWith(Suite.class) +@SuiteClasses({ + SmartDashboardTest.class +}) +public class SmartDashboardTestSuite { +} diff --git a/wpilibj/wpilibJavaIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/TestBench.java b/wpilibj/wpilibJavaIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/TestBench.java index 5ecf2d1a31..8ee7e1634e 100644 --- a/wpilibj/wpilibJavaIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/TestBench.java +++ b/wpilibj/wpilibJavaIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/TestBench.java @@ -12,18 +12,23 @@ import java.util.Collection; import java.util.Iterator; import java.util.List; +import edu.wpi.first.wpilibj.AnalogInput; +import edu.wpi.first.wpilibj.AnalogOutput; import edu.wpi.first.wpilibj.CANJaguar; import edu.wpi.first.wpilibj.DigitalInput; import edu.wpi.first.wpilibj.DigitalOutput; import edu.wpi.first.wpilibj.Gyro; import edu.wpi.first.wpilibj.Jaguar; +import edu.wpi.first.wpilibj.Relay; import edu.wpi.first.wpilibj.Servo; import edu.wpi.first.wpilibj.SpeedController; import edu.wpi.first.wpilibj.Talon; import edu.wpi.first.wpilibj.Victor; import edu.wpi.first.wpilibj.can.CANTimeoutException; +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.RelayCrossConnectFxiture; import edu.wpi.first.wpilibj.fixtures.TiltPanCameraFixture; /** @@ -221,6 +226,42 @@ public final class TestBench { //NOTE: IF MORE DIOCROSSCONNECT PAIRS ARE ADDED ADD THEM HERE return pairs; } + + public static AnalogCrossConnectFixture getAnalogCrossConnectFixture(){ + AnalogCrossConnectFixture analogIO = new AnalogCrossConnectFixture() { + @Override + protected AnalogOutput giveAnalogOutput() { + return new AnalogOutput(0); + } + + @Override + protected AnalogInput giveAnalogInput() { + return new AnalogInput(2); + } + }; + return analogIO; + } + + public static RelayCrossConnectFxiture getRelayCrossConnectFixture(){ + RelayCrossConnectFxiture relay = new RelayCrossConnectFxiture() { + + @Override + protected Relay giveRelay() { + return new Relay(0); + } + + @Override + protected DigitalInput giveInputTwo() { + return new DigitalInput(14); + } + + @Override + protected DigitalInput giveInputOne() { + return new DigitalInput(15); + } + }; + return relay; + } /** * Return a single Collection containing all of the DIOCrossConnectFixtures in all two pair combinations diff --git a/wpilibj/wpilibJavaIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/TestSuite.java b/wpilibj/wpilibJavaIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/TestSuite.java index b651db33bc..64872d612a 100644 --- a/wpilibj/wpilibJavaIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/TestSuite.java +++ b/wpilibj/wpilibJavaIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/TestSuite.java @@ -16,23 +16,28 @@ import org.junit.runner.RunWith; import org.junit.runners.Suite; import org.junit.runners.Suite.SuiteClasses; +import edu.wpi.first.wpilibj.AnalogCrossConnectTest; import edu.wpi.first.wpilibj.CounterTest; import edu.wpi.first.wpilibj.DIOCrossConnectTest; import edu.wpi.first.wpilibj.EncoderTest; import edu.wpi.first.wpilibj.MotorEncoderTest; import edu.wpi.first.wpilibj.PIDTest; import edu.wpi.first.wpilibj.PrefrencesTest; +import edu.wpi.first.wpilibj.RelayCrossConnectTest; import edu.wpi.first.wpilibj.SampleTest; import edu.wpi.first.wpilibj.TiltPanCameraTest; import edu.wpi.first.wpilibj.TimerTest; +import edu.wpi.first.wpilibj.WpiLibJTestSuite; import edu.wpi.first.wpilibj.command.ButtonTest; import edu.wpi.first.wpilibj.command.CommandParallelGroupTest; import edu.wpi.first.wpilibj.command.CommandScheduleTest; import edu.wpi.first.wpilibj.command.CommandSequentialGroupTest; import edu.wpi.first.wpilibj.command.CommandSupersedeTest; +import edu.wpi.first.wpilibj.command.CommandTestSuite; import edu.wpi.first.wpilibj.command.CommandTimeoutTest; import edu.wpi.first.wpilibj.command.DefaultCommandTest; import edu.wpi.first.wpilibj.smartdashboard.SmartDashboardTest; +import edu.wpi.first.wpilibj.smartdashboard.SmartDashboardTestSuite; /** * The WPILibJ Integeration Test Suite collects all of the tests to be run by @@ -41,25 +46,13 @@ import edu.wpi.first.wpilibj.smartdashboard.SmartDashboardTest; * suite classes annotation. */ @RunWith(Suite.class) -@SuiteClasses({ SampleTest.class, - SmartDashboardTest.class, - DIOCrossConnectTest.class, - CounterTest.class, - EncoderTest.class, - PIDTest.class, - TiltPanCameraTest.class, - MotorEncoderTest.class, - PrefrencesTest.class, - ButtonTest.class, - CommandParallelGroupTest.class, - CommandScheduleTest.class, - CommandSequentialGroupTest.class, - CommandSupersedeTest.class, - CommandTimeoutTest.class, - DefaultCommandTest.class, - TimerTest.class +@SuiteClasses({ + WpiLibJTestSuite.class, + CommandTestSuite.class, + SmartDashboardTestSuite.class }) //NOTE: THESE ARE EACH LISTED ON SEPERATE LINES TO PREVENT GIT MERGE CONFLICTS! +@SuppressWarnings("unused") public class TestSuite { static{ final InputStream inputStream = TestSuite.class.getResourceAsStream("/logging.properties");