diff --git a/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/PIDController.java b/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/PIDController.java
index 7ccfe71d47..c705079d3b 100644
--- a/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/PIDController.java
+++ b/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/PIDController.java
@@ -103,16 +103,10 @@ public class PIDController implements IUtility, LiveWindowSendable, Controller {
}
public void run() {
- boolean freed;
- synchronized (this){
- freed = m_freed;
- }
- if(!freed){
+ if(!m_freed){
m_controller.calculate();
} else {
cancel();
- m_controlLoop.cancel();
- m_controlLoop.purge();
}
}
}
diff --git a/wpilibj/wpilibJavaIntegrationTests/pom.xml b/wpilibj/wpilibJavaIntegrationTests/pom.xml
index b92a5f47bd..b13f2e5a33 100644
--- a/wpilibj/wpilibJavaIntegrationTests/pom.xml
+++ b/wpilibj/wpilibJavaIntegrationTests/pom.xml
@@ -29,6 +29,11 @@
hamcrest-core
1.3
+
@@ -109,6 +114,12 @@
1.3
jar
+
${project.build.directory}/classes
diff --git a/wpilibj/wpilibJavaIntegrationTests/src/main/java/edu/wpi/first/wpilibj/DIOCrossConnectTest.java b/wpilibj/wpilibJavaIntegrationTests/src/main/java/edu/wpi/first/wpilibj/DIOCrossConnectTest.java
index dec1933eac..7403f97f4a 100644
--- a/wpilibj/wpilibJavaIntegrationTests/src/main/java/edu/wpi/first/wpilibj/DIOCrossConnectTest.java
+++ b/wpilibj/wpilibJavaIntegrationTests/src/main/java/edu/wpi/first/wpilibj/DIOCrossConnectTest.java
@@ -95,7 +95,7 @@ public class DIOCrossConnectTest extends AbstractComsSetup {
public void testSetHigh() {
dio.getOutput().set(true);
assertTrue("DIO Not High after no delay", dio.getInput().get());
- Timer.delay(.05);
+ Timer.delay(.02);
assertTrue("DIO Not High after .05s delay", dio.getInput().get());
}
@@ -106,7 +106,7 @@ public class DIOCrossConnectTest extends AbstractComsSetup {
public void testSetLow() {
dio.getOutput().set(false);
assertFalse("DIO Not Low after no delay", dio.getInput().get());
- Timer.delay(.05);
+ Timer.delay(.02);
assertFalse("DIO Not Low after .05s delay", dio.getInput().get());
}
}
diff --git a/wpilibj/wpilibJavaIntegrationTests/src/main/java/edu/wpi/first/wpilibj/MotorEncoderTest.java b/wpilibj/wpilibJavaIntegrationTests/src/main/java/edu/wpi/first/wpilibj/MotorEncoderTest.java
index d9fedd2cb3..02af5960f5 100644
--- a/wpilibj/wpilibJavaIntegrationTests/src/main/java/edu/wpi/first/wpilibj/MotorEncoderTest.java
+++ b/wpilibj/wpilibJavaIntegrationTests/src/main/java/edu/wpi/first/wpilibj/MotorEncoderTest.java
@@ -9,36 +9,47 @@ package edu.wpi.first.wpilibj;
import static org.junit.Assert.assertFalse;
import static org.junit.Assert.assertTrue;
-import java.util.ArrayList;
-import java.util.List;
+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.wpilibj.fixtures.MotorEncoderFixture;
import edu.wpi.first.wpilibj.test.AbstractComsSetup;
import edu.wpi.first.wpilibj.test.TestBench;
+
+@RunWith(Parameterized.class)
public class MotorEncoderTest extends AbstractComsSetup {
+ private static final Logger logger = Logger.getLogger(MotorEncoderTest.class.getName());
private static final double MOTOR_RUNTIME = .25;
- private static final List pairs = new ArrayList();
+ //private static final List pairs = new ArrayList();
+ private static MotorEncoderFixture me = null;
-
- @BeforeClass
- public static void classSetup() {
- // Set up the fixture before the test is created
- pairs.add(TestBench.getInstance().getTalonPair());
- pairs.add(TestBench.getInstance().getVictorPair());
- pairs.add(TestBench.getInstance().getJaguarPair());
- //pairs.add(TestBench.getInstance().getCanJaguarPair());
-
- for(MotorEncoderFixture me : pairs){
- me.reset();
- }
+ public MotorEncoderTest(MotorEncoderFixture mef){
+ logger.fine("Constructor with: " + mef.getType());
+ if(me != null && !me.equals(mef)) me.teardown();
+ me = mef;
+ }
+
+ @Parameters
+ public static Collection generateData(){
+ //logger.fine("Loading the MotorList");
+ return Arrays.asList(new MotorEncoderFixture[][]{
+ {TestBench.getInstance().getTalonPair()},
+ {TestBench.getInstance().getVictorPair()},
+ {TestBench.getInstance().getJaguarPair()}
+ // TestBench.getInstance().getCanJaguarPair()
+ });
}
/**
@@ -52,21 +63,23 @@ public class MotorEncoderTest extends AbstractComsSetup {
@Before
public void setUp() {
- for(MotorEncoderFixture me : pairs){
- double initialSpeed = me.getMotor().get();
- assertTrue(me.getType() + " Did not start with an initial speeed of 0 instead got: " + initialSpeed, Math.abs(initialSpeed) < 0.001);
- me.setup();
- }
-
+ double initialSpeed = me.getMotor().get();
+ assertTrue(me.getType()
+ + " Did not start with an initial speeed of 0 instead got: "
+ + initialSpeed, Math.abs(initialSpeed) < 0.001);
+ me.setup();
+
+ }
+
+ @After
+ public void tearDown() throws Exception {
+ me.reset();
}
@AfterClass
- public static void tearDown() {
+ public static void tearDownAfterClass() {
// Clean up the fixture after the test
- for(MotorEncoderFixture me : pairs){
- me.teardown();
- }
- pairs.clear();
+ me.teardown();
}
/**
@@ -75,13 +88,12 @@ public class MotorEncoderTest extends AbstractComsSetup {
*/
@Test
public void testIsMotorWithinRange(){
- for(MotorEncoderFixture me: pairs){
- 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));
- }
+ 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));
}
/**
@@ -89,37 +101,39 @@ public class MotorEncoderTest extends AbstractComsSetup {
*/
@Test
public void testIncrement() {
- for(MotorEncoderFixture me: pairs){
- int startValue = me.getEncoder().get();
-
- me.getMotor().set(.75);
- Timer.delay(MOTOR_RUNTIME);
- int currentValue = me.getEncoder().get();
- if(shouldRunTest(me)){ //TODO REMOVE THIS WHEN ALL ENCODERS ARE PROPERLY ATTACHED
- assertTrue(me.getType() + " Encoder not incremented: start: " + startValue + "; current: " + currentValue, startValue < currentValue);
- }
- me.reset();
- encodersResetCheck(me);
+ int startValue = me.getEncoder().get();
+
+ me.getMotor().set(.75);
+ Timer.delay(MOTOR_RUNTIME);
+ int currentValue = me.getEncoder().get();
+ if (shouldRunTest(me)) { // TODO REMOVE THIS WHEN ALL ENCODERS ARE
+ // PROPERLY ATTACHED
+ assertTrue(me.getType() + " Encoder not incremented: start: "
+ + startValue + "; current: " + currentValue,
+ startValue < currentValue);
}
+ me.reset();
+ encodersResetCheck(me);
}
-
+
/**
* This test is designed to see if the values of different motors will decrement when spun in reverse
*/
@Test
public void testDecrement(){
- for(MotorEncoderFixture me: pairs){
- int startValue = me.getEncoder().get();
-
- me.getMotor().set(-.75);
- Timer.delay(MOTOR_RUNTIME);
- int currentValue = me.getEncoder().get();
- if(shouldRunTest(me)){ //TODO REMOVE THIS WHEN ALL ENCODERS ARE PROPERLY ATTACHED
- assertTrue(me.getType() + " Encoder not decremented: start: " + startValue + "; current: " + currentValue, startValue > currentValue);
- }
- me.reset();
- encodersResetCheck(me);
+ int startValue = me.getEncoder().get();
+
+ me.getMotor().set(-.75);
+ Timer.delay(MOTOR_RUNTIME);
+ int currentValue = me.getEncoder().get();
+ if (shouldRunTest(me)) { // TODO REMOVE THIS WHEN ALL ENCODERS ARE
+ // PROPERLY ATTACHED
+ assertTrue(me.getType() + " Encoder not decremented: start: "
+ + startValue + "; current: " + currentValue,
+ startValue > currentValue);
}
+ me.reset();
+ encodersResetCheck(me);
}
/**
@@ -127,21 +141,24 @@ public class MotorEncoderTest extends AbstractComsSetup {
*/
@Test
public void testCouter(){
- for(MotorEncoderFixture me: pairs){
- int counter1Start = me.getCounters()[0].get();
- int counter2Start = me.getCounters()[1].get();
-
- me.getMotor().set(.75);
- Timer.delay(MOTOR_RUNTIME);
- int counter1End = me.getCounters()[0].get();
- int counter2End = me.getCounters()[1].get();
- if(shouldRunTest(me)){ //TODO REMOVE THIS WHEN ALL ENCODERS ARE PROPERLY ATTACHED
- 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);
+ int counter1Start = me.getCounters()[0].get();
+ int counter2Start = me.getCounters()[1].get();
+
+ me.getMotor().set(.75);
+ Timer.delay(MOTOR_RUNTIME);
+ int counter1End = me.getCounters()[0].get();
+ int counter2End = me.getCounters()[1].get();
+ if (shouldRunTest(me)) { // TODO REMOVE THIS WHEN ALL ENCODERS ARE
+ // PROPERLY ATTACHED
+ 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);
}
/**
@@ -149,25 +166,42 @@ public class MotorEncoderTest extends AbstractComsSetup {
*/
@Test
public void testSetHighForwardSpeed(){
- for(MotorEncoderFixture me:pairs){
- 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));
- me.reset();
- }
+ 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));
+ me.reset();
}
/**
* Tests to see if you set the speed to something not >= -1.0 if the code appropriately throttles the value
*/
@Test
- public void testSetHighReverseSpeed(){
- for(MotorEncoderFixture me:pairs){
- 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));
- me.reset();
- }
+ 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));
+ me.reset();
}
+
+ @Test
+ public void testPIDController() {
+ PIDController pid = new PIDController(0.003, 0.001, 0, me.getEncoder(),
+ me.getMotor());
+ pid.setAbsoluteTolerance(15);
+ pid.setOutputRange(-0.2, 0.2);
+ pid.setSetpoint(2500);
+
+ pid.enable();
+ Timer.delay(5.0);
+ pid.disable();
+
+ assertTrue("PID loop did not reach setpoint within 5 seconds. The error was: " + pid.getError(),
+ pid.onTarget());
+
+ pid.free();
+ me.reset();
+ }
@@ -186,6 +220,8 @@ public class MotorEncoderTest extends AbstractComsSetup {
assertTrue(me.getType() + " Motor value: " + motorVal + " when it should be 0", motorVal == 0);
assertTrue(me.getType() + " Counter value " + counterVal[0] + " when is should be 0", counterVal[0] == 0);
assertTrue(me.getType() + " Counter value " + counterVal[1] + " when is should be 0", counterVal[1] == 0);
+ Timer.delay(.1);
+ assertTrue(me.getType() + " Encoder.getStopped() returned false", me.getEncoder().getStopped());
}
}
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 30b9ef770c..2751dc559b 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
@@ -115,7 +115,7 @@ public class PIDTest extends AbstractComsSetup {
@Test (timeout = 6000)
public void testRotateToTarget() {
- double setpoint = 2500;
+ double setpoint = 2500.0;
System.out.println("Entering testRotateToTarget");
assertEquals("PID did not start at 0", 0, controller.get(), 0);
controller.setSetpoint(setpoint);
@@ -123,7 +123,7 @@ public class PIDTest extends AbstractComsSetup {
controller.enable();
Timer.delay(5);
controller.disable();
- assertTrue(controller.onTarget());
+ assertTrue("PID Controller Error: " + controller.getError(), controller.onTarget());
}
}
diff --git a/wpilibj/wpilibJavaIntegrationTests/src/main/java/edu/wpi/first/wpilibj/PrefrencesTest.java b/wpilibj/wpilibJavaIntegrationTests/src/main/java/edu/wpi/first/wpilibj/PrefrencesTest.java
new file mode 100644
index 0000000000..9cf3d0a629
--- /dev/null
+++ b/wpilibj/wpilibJavaIntegrationTests/src/main/java/edu/wpi/first/wpilibj/PrefrencesTest.java
@@ -0,0 +1,135 @@
+/*----------------------------------------------------------------------------*/
+/* 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.io.File;
+import java.io.FileOutputStream;
+import java.io.IOException;
+import java.io.OutputStream;
+
+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.command.AbstractCommandTest;
+import edu.wpi.first.wpilibj.networktables.NetworkTable;
+
+/**
+ * @author jonathanleitschuh
+ *
+ */
+public class PrefrencesTest extends AbstractCommandTest {
+
+ private NetworkTable prefTable;
+ private Preferences pref;
+ private long check;
+
+ /**
+ * @throws java.lang.Exception
+ */
+ @BeforeClass
+ public static void setUpBeforeClass() throws Exception {
+ }
+
+ /**
+ * @throws java.lang.Exception
+ */
+ @AfterClass
+ public static void tearDownAfterClass() throws Exception {
+ }
+
+ /**
+ * @throws java.lang.Exception
+ */
+ @Before
+ public void setUp() throws Exception {
+ try {
+ File file = new File("wpilib-preferences.ini");
+ file.mkdirs();
+ if (file.exists()) {
+ file.delete();
+ }
+ file.createNewFile();
+ OutputStream output = new FileOutputStream(file);
+ output.write("checkedValueInt = 2\ncheckedValueDouble = .2\ncheckedValueFloat = 3.14\ncheckedValueLong = 172\ncheckedValueString =\"hello \nHow are you ?\"\ncheckedValueBoolean = false"
+ .getBytes());
+
+ } catch (IOException e) {
+ e.printStackTrace();
+ }
+
+ pref = Preferences.getInstance();
+ prefTable = NetworkTable.getTable("Preferences");
+ check = System.currentTimeMillis();
+ }
+
+ /**
+ * @throws java.lang.Exception
+ */
+ @After
+ public void tearDown() throws Exception {
+ }
+
+ public void remove() {
+ pref.remove("checkedValueLong");
+ pref.remove("checkedValueDouble");
+ pref.remove("checkedValueString");
+ pref.remove("checkedValueInt");
+ pref.remove("checkedValueFloat");
+ pref.remove("checkedValueBoolean");
+ }
+
+ public void addCheckedValue() {
+ pref.putLong("checkedValueLong", check);
+ pref.putDouble("checkedValueDouble", 1);
+ pref.putString("checkedValueString", "checked");
+ pref.putInt("checkedValueInt", 1);
+ pref.putFloat("checkedValueFloat", 1);
+ pref.putBoolean("checkedValueBoolean", true);
+ }
+
+ @Test
+ public void testAddRemoveSave() {
+ assertEquals(pref.getLong("checkedValueLong", 0), 172L);
+ assertEquals(pref.getDouble("checkedValueDouble", 0), .2, 0);
+ assertEquals(pref.getString("checkedValueString", ""),
+ "hello \nHow are you ?");
+ assertEquals(pref.getInt("checkedValueInt", 0), 2);
+ assertEquals(pref.getFloat("checkedValueFloat", 0), 3.14, .001);
+ assertFalse(pref.getBoolean("checkedValueBoolean", true));
+ remove();
+ assertEquals(pref.getLong("checkedValueLong", 0), 0);
+ assertEquals(pref.getDouble("checkedValueDouble", 0), 0, 0);
+ assertEquals(pref.getString("checkedValueString", ""), "");
+ assertEquals(pref.getInt("checkedValueInt", 0), 0);
+ assertEquals(pref.getFloat("checkedValueFloat", 0), 0, 0);
+ assertFalse(pref.getBoolean("checkedValueBoolean", false));
+ addCheckedValue();
+ pref.save();
+ assertEquals(check, pref.getLong("checkedValueLong", 0));
+ assertEquals(pref.getDouble("checkedValueDouble", 0), 1, 0);
+ assertEquals(pref.getString("checkedValueString", ""),
+ "checked");
+ assertEquals(pref.getInt("checkedValueInt", 0), 1);
+ assertEquals(pref.getFloat("checkedValueFloat", 0), 1, 0);
+ assertTrue(pref.getBoolean("checkedValueBoolean", false));
+ }
+
+ @Test
+ public void testPreferencesToNetworkTables(){
+ String networkedNumber = "networkCheckedValue";
+ int networkNumberValue = 100;
+ pref.putInt(networkedNumber, networkNumberValue);
+ assertEquals((new Integer(networkNumberValue).toString()), prefTable.getString(networkedNumber));
+ pref.remove(networkedNumber);
+ }
+
+}
diff --git a/wpilibj/wpilibJavaIntegrationTests/src/main/java/edu/wpi/first/wpilibj/TiltPanCameraTest.java b/wpilibj/wpilibJavaIntegrationTests/src/main/java/edu/wpi/first/wpilibj/TiltPanCameraTest.java
index 19ac8506fd..04a07f358b 100644
--- a/wpilibj/wpilibJavaIntegrationTests/src/main/java/edu/wpi/first/wpilibj/TiltPanCameraTest.java
+++ b/wpilibj/wpilibJavaIntegrationTests/src/main/java/edu/wpi/first/wpilibj/TiltPanCameraTest.java
@@ -8,6 +8,8 @@ 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;
@@ -20,12 +22,15 @@ import edu.wpi.first.wpilibj.test.TestBench;
public class TiltPanCameraTest extends AbstractComsSetup {
- public static final double TEST_ANGLE = 180.0;
+ private static final Logger logger = Logger.getLogger(TiltPanCameraTest.class.getName());
+
+ public static final double TEST_ANGLE = 185.0;
private static TiltPanCameraFixture tpcam;
@BeforeClass
public static void setUpBeforeClass() throws Exception {
+ logger.fine("Setup: TiltPan camera");
tpcam = TestBench.getInstance().getTiltPanCam();
}
@@ -48,7 +53,7 @@ public class TiltPanCameraTest extends AbstractComsSetup {
@Test
public void testInitial(){
double angle = tpcam.getGyro().getAngle();
- assertTrue(errorMessage(angle, 0), Math.abs(angle) < 0.5);
+ assertEquals(errorMessage(angle, 0), 0, angle, .5);
}
/**
@@ -58,11 +63,11 @@ public class TiltPanCameraTest extends AbstractComsSetup {
public void testGyroAngle() {
for(double i = 0; i < 1.0; i+=.01){
//System.out.println("i: " + i);
- System.out.println("Angle " + tpcam.getGyro().getAngle());
+ //System.out.println("Angle " + tpcam.getGyro().getAngle());
tpcam.getPan().set(i);
Timer.delay(.05);
}
- Timer.delay(TiltPanCameraFixture.RESET_TIME);
+ //Timer.delay(TiltPanCameraFixture.RESET_TIME);
double angle = tpcam.getGyro().getAngle();
double difference = TEST_ANGLE - angle;
@@ -70,7 +75,7 @@ public class TiltPanCameraTest extends AbstractComsSetup {
double diff = Math.abs(difference);
- assertTrue(errorMessage(diff, TEST_ANGLE), diff < 4.0);
+ assertEquals(errorMessage(diff, TEST_ANGLE), TEST_ANGLE, angle, 8);
}
private String errorMessage(double difference, double target){
diff --git a/wpilibj/wpilibJavaIntegrationTests/src/main/java/edu/wpi/first/wpilibj/TimerTest.java b/wpilibj/wpilibJavaIntegrationTests/src/main/java/edu/wpi/first/wpilibj/TimerTest.java
index e5eee20099..c499caf3fc 100644
--- a/wpilibj/wpilibJavaIntegrationTests/src/main/java/edu/wpi/first/wpilibj/TimerTest.java
+++ b/wpilibj/wpilibJavaIntegrationTests/src/main/java/edu/wpi/first/wpilibj/TimerTest.java
@@ -6,6 +6,7 @@
/*----------------------------------------------------------------------------*/
package edu.wpi.first.wpilibj;
+import static org.junit.Assert.assertEquals;
import static org.junit.Assert.assertTrue;
import org.junit.AfterClass;
@@ -18,12 +19,11 @@ import edu.wpi.first.wpilibj.test.AbstractComsSetup;
public class TimerTest extends AbstractComsSetup {
- private static double TIMER_TOLARANCE = 0.005;
- private static double TIMER_RUNTIME = 5.0;
+ private static final long TIMER_TOLARANCE = 5 * 1000;
+ private static final long TIMER_RUNTIME = 5 * 1000000;
@BeforeClass
public static void classSetup() {
-
}
@Before
@@ -39,16 +39,15 @@ public class TimerTest extends AbstractComsSetup {
@Test
public void delayTest(){
- double startTime = Timer.getFPGATimestamp();
- Timer.delay(TIMER_RUNTIME);
- double endTime =Timer.getFPGATimestamp();
+ long startTime = Utility.getFPGATime();
+ Timer.delay(TIMER_RUNTIME/1000000);
+ long endTime = Utility.getFPGATime();
- double difference = endTime - startTime;
+ long difference = endTime - startTime;
- double offset = difference - TIMER_RUNTIME;
-
- assertTrue("Timer.delay ran " + offset + " seconds too long", Math.abs(offset) < TIMER_TOLARANCE);
+ long offset = difference - TIMER_RUNTIME;
+ assertEquals("Timer.delay ran " + offset + " seconds too long", 0, Math.abs(offset), TIMER_TOLARANCE);
}
}
diff --git a/wpilibj/wpilibJavaIntegrationTests/src/main/java/edu/wpi/first/wpilibj/command/ButtonTest.java b/wpilibj/wpilibJavaIntegrationTests/src/main/java/edu/wpi/first/wpilibj/command/ButtonTest.java
new file mode 100644
index 0000000000..4afd2df7b1
--- /dev/null
+++ b/wpilibj/wpilibJavaIntegrationTests/src/main/java/edu/wpi/first/wpilibj/command/ButtonTest.java
@@ -0,0 +1,145 @@
+/*----------------------------------------------------------------------------*/
+/* 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.After;
+import org.junit.AfterClass;
+import org.junit.Before;
+import org.junit.BeforeClass;
+import org.junit.Test;
+
+import edu.wpi.first.wpilibj.buttons.InternalButton;
+import edu.wpi.first.wpilibj.mocks.MockCommand;
+
+
+/**
+ * @author Mitchell
+ * @author jonathanleitschuh
+ *
+ */
+public class ButtonTest extends AbstractCommandTest {
+
+ private InternalButton button1;
+ private InternalButton button2;
+
+ /**
+ * @throws java.lang.Exception
+ */
+ @BeforeClass
+ public static void setUpBeforeClass() throws Exception {
+ }
+
+ /**
+ * @throws java.lang.Exception
+ */
+ @AfterClass
+ public static void tearDownAfterClass() throws Exception {
+ }
+
+ /**
+ * @throws java.lang.Exception
+ */
+ @Before
+ public void setUp() throws Exception {
+ button1 = new InternalButton();
+ button2 = new InternalButton();
+ }
+
+ /**
+ * @throws java.lang.Exception
+ */
+ @After
+ public void tearDown() throws Exception {
+ }
+
+ /**
+ * Simple Button Test
+ */
+ @Test
+ public void test() {
+ MockCommand command1 = new MockCommand();
+ MockCommand command2 = new MockCommand();
+ MockCommand command3 = new MockCommand();
+ MockCommand command4 = new MockCommand();
+
+ button1.whenPressed(command1);
+ button1.whenReleased(command2);
+ button1.whileHeld(command3);
+ button2.whileHeld(command4);
+
+ assertCommandState(command1, 0, 0, 0, 0, 0);
+ assertCommandState(command2, 0, 0, 0, 0, 0);
+ assertCommandState(command3, 0, 0, 0, 0, 0);
+ assertCommandState(command4, 0, 0, 0, 0, 0);
+ button1.setPressed(true);
+ assertCommandState(command1, 0, 0, 0, 0, 0);
+ assertCommandState(command2, 0, 0, 0, 0, 0);
+ assertCommandState(command3, 0, 0, 0, 0, 0);
+ assertCommandState(command4, 0, 0, 0, 0, 0);
+ Scheduler.getInstance().run();
+ assertCommandState(command1, 0, 0, 0, 0, 0);
+ assertCommandState(command2, 0, 0, 0, 0, 0);
+ assertCommandState(command3, 0, 0, 0, 0, 0);
+ assertCommandState(command4, 0, 0, 0, 0, 0);
+ Scheduler.getInstance().run();
+ assertCommandState(command1, 1, 1, 1, 0, 0);
+ assertCommandState(command2, 0, 0, 0, 0, 0);
+ assertCommandState(command3, 1, 1, 1, 0, 0);
+ assertCommandState(command4, 0, 0, 0, 0, 0);
+ Scheduler.getInstance().run();
+ assertCommandState(command1, 1, 2, 2, 0, 0);
+ assertCommandState(command2, 0, 0, 0, 0, 0);
+ assertCommandState(command3, 1, 2, 2, 0, 0);
+ assertCommandState(command4, 0, 0, 0, 0, 0);
+ button2.setPressed(true);
+ Scheduler.getInstance().run();
+ assertCommandState(command1, 1, 3, 3, 0, 0);
+ assertCommandState(command2, 0, 0, 0, 0, 0);
+ assertCommandState(command3, 1, 3, 3, 0, 0);
+ assertCommandState(command4, 0, 0, 0, 0, 0);
+ Scheduler.getInstance().run();
+ assertCommandState(command1, 1, 4, 4, 0, 0);
+ assertCommandState(command2, 0, 0, 0, 0, 0);
+ assertCommandState(command3, 1, 4, 4, 0, 0);
+ assertCommandState(command4, 1, 1, 1, 0, 0);
+ button1.setPressed(false);
+ Scheduler.getInstance().run();
+ assertCommandState(command1, 1, 5, 5, 0, 0);
+ assertCommandState(command2, 0, 0, 0, 0, 0);
+ assertCommandState(command3, 1, 4, 4, 0, 1);
+ assertCommandState(command4, 1, 2, 2, 0, 0);
+ Scheduler.getInstance().run();
+ assertCommandState(command1, 1, 6, 6, 0, 0);
+ assertCommandState(command2, 1, 1, 1, 0, 0);
+ assertCommandState(command3, 1, 4, 4, 0, 1);
+ assertCommandState(command4, 1, 3, 3, 0, 0);
+ button2.setPressed(false);
+ Scheduler.getInstance().run();
+ assertCommandState(command1, 1, 7, 7, 0, 0);
+ assertCommandState(command2, 1, 2, 2, 0, 0);
+ assertCommandState(command3, 1, 4, 4, 0, 1);
+ assertCommandState(command4, 1, 3, 3, 0, 1);
+ command1.cancel();
+ Scheduler.getInstance().run();
+ assertCommandState(command1, 1, 7, 7, 0, 1);
+ assertCommandState(command2, 1, 3, 3, 0, 0);
+ assertCommandState(command3, 1, 4, 4, 0, 1);
+ assertCommandState(command4, 1, 3, 3, 0, 1);
+ command2.setHasFinished(true);
+ Scheduler.getInstance().run();
+ assertCommandState(command1, 1, 7, 7, 0, 1);
+ assertCommandState(command2, 1, 4, 4, 1, 0);
+ assertCommandState(command3, 1, 4, 4, 0, 1);
+ assertCommandState(command4, 1, 3, 3, 0, 1);
+ Scheduler.getInstance().run();
+ assertCommandState(command1, 1, 7, 7, 0, 1);
+ assertCommandState(command2, 1, 4, 4, 1, 0);
+ assertCommandState(command3, 1, 4, 4, 0, 1);
+ assertCommandState(command4, 1, 3, 3, 0, 1);
+ }
+
+}
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 d930bc8918..1f375d84f6 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
@@ -155,6 +155,7 @@ public abstract class MotorEncoderFixture implements ITestFixture {
@Override
public boolean teardown() {
+ String type = getType();
if(!tornDown){
initialize();
reset();
@@ -173,6 +174,8 @@ public abstract class MotorEncoderFixture implements ITestFixture {
bSource.free();
bSource = null;
tornDown = true;
+ } else {
+ throw new RuntimeException(type + " Motor Encoder torn down multiple times");
}
return true;
diff --git a/wpilibj/wpilibJavaIntegrationTests/src/main/java/edu/wpi/first/wpilibj/mockhardware/FakeCounterSource.java b/wpilibj/wpilibJavaIntegrationTests/src/main/java/edu/wpi/first/wpilibj/mockhardware/FakeCounterSource.java
index 7f934245e1..19311afa5c 100644
--- a/wpilibj/wpilibJavaIntegrationTests/src/main/java/edu/wpi/first/wpilibj/mockhardware/FakeCounterSource.java
+++ b/wpilibj/wpilibJavaIntegrationTests/src/main/java/edu/wpi/first/wpilibj/mockhardware/FakeCounterSource.java
@@ -131,7 +131,7 @@ public class FakeCounterSource
{
}
m_task = new EncoderThread(this);
- Timer.delay(.1);
+ Timer.delay(.01);
}
/**
diff --git a/wpilibj/wpilibJavaIntegrationTests/src/main/java/edu/wpi/first/wpilibj/mockhardware/FakeEncoderSource.java b/wpilibj/wpilibJavaIntegrationTests/src/main/java/edu/wpi/first/wpilibj/mockhardware/FakeEncoderSource.java
index b5287f4560..0ca000f791 100644
--- a/wpilibj/wpilibJavaIntegrationTests/src/main/java/edu/wpi/first/wpilibj/mockhardware/FakeEncoderSource.java
+++ b/wpilibj/wpilibJavaIntegrationTests/src/main/java/edu/wpi/first/wpilibj/mockhardware/FakeEncoderSource.java
@@ -139,7 +139,7 @@ public class FakeEncoderSource
{
}
m_task = new QuadEncoderThread(this);
- Timer.delay(.1);
+ Timer.delay(.01);
}
/**
diff --git a/wpilibj/wpilibJavaIntegrationTests/src/main/java/edu/wpi/first/wpilibj/smartdashboard/SmartDashboardTest.java b/wpilibj/wpilibJavaIntegrationTests/src/main/java/edu/wpi/first/wpilibj/smartdashboard/SmartDashboardTest.java
new file mode 100644
index 0000000000..3f49271720
--- /dev/null
+++ b/wpilibj/wpilibJavaIntegrationTests/src/main/java/edu/wpi/first/wpilibj/smartdashboard/SmartDashboardTest.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.smartdashboard;
+
+import static org.junit.Assert.assertEquals;
+
+import org.junit.After;
+import org.junit.AfterClass;
+import org.junit.Before;
+import org.junit.BeforeClass;
+import org.junit.Ignore;
+import org.junit.Test;
+
+import edu.wpi.first.wpilibj.networktables.NetworkTable;
+import edu.wpi.first.wpilibj.networktables.NetworkTableKeyNotDefined;
+import edu.wpi.first.wpilibj.test.AbstractComsSetup;
+
+/**
+ * @author jonathanleitschuh
+ *
+ */
+public class SmartDashboardTest extends AbstractComsSetup {
+ private static final NetworkTable table = NetworkTable.getTable("SmartDashboard");
+
+ /**
+ * @throws java.lang.Exception
+ */
+ @BeforeClass
+ public static void setUpBeforeClass() throws Exception {
+ }
+
+ /**
+ * @throws java.lang.Exception
+ */
+ @AfterClass
+ public static void tearDownAfterClass() throws Exception {
+ }
+
+ /**
+ * @throws java.lang.Exception
+ */
+ @Before
+ public void setUp() throws Exception {
+ }
+
+ /**
+ * @throws java.lang.Exception
+ */
+ @After
+ public void tearDown() throws Exception {
+ }
+
+ @Test(expected=NetworkTableKeyNotDefined.class)
+ public void testGetBadValue(){
+ SmartDashboard.getString("_404_STRING_KEY_SHOULD_NOT_BE_FOUND_");
+ }
+
+ @Test
+ public void testPutString() {
+ String key = "testPutString";
+ String value = "thisIsAValue";
+ SmartDashboard.putString(key, value);
+ assertEquals(value, SmartDashboard.getString(key));
+ assertEquals(value, table.getString(key));
+ }
+
+ @Test
+ public void testPutNumber(){
+ String key = "testPutNumber";
+ int value = 2147483647;
+ SmartDashboard.putNumber(key, value);
+ assertEquals(value, SmartDashboard.getNumber(key), 0.01);
+ assertEquals(value, table.getNumber(key), 0.01);
+ }
+
+ @Test
+ public void testPutBoolean(){
+ String key = "testPutBoolean";
+ boolean value = true;
+ SmartDashboard.putBoolean(key, value);
+ assertEquals(value, SmartDashboard.getBoolean(key));
+ assertEquals(value, table.getBoolean(key));
+ }
+
+ @Test
+ public void testReplaceString(){
+ String key = "testReplaceString";
+ String valueOld = "oldValue";
+ String valueNew = "newValue";
+ SmartDashboard.putString(key, valueOld);
+ assertEquals(valueOld, SmartDashboard.getString(key));
+ assertEquals(valueOld, table.getString(key));
+
+ SmartDashboard.putString(key, valueNew);
+ assertEquals(valueNew, SmartDashboard.getString(key));
+ assertEquals(valueNew, table.getString(key));
+ }
+
+ @Ignore
+ @Test(expected=IllegalArgumentException.class)
+ public void testPutStringNullKey(){
+ SmartDashboard.putString(null, "This should not work");
+ }
+
+ @Ignore
+ @Test(expected=IllegalArgumentException.class)
+ public void testPutStringNullValue(){
+ SmartDashboard.putString("KEY_SHOULD_NOT_BE_STORED", null);
+ }
+}
diff --git a/wpilibj/wpilibJavaIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/AbstractComsSetup.java b/wpilibj/wpilibJavaIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/AbstractComsSetup.java
index b0b5a63f81..5aba857847 100644
--- a/wpilibj/wpilibJavaIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/AbstractComsSetup.java
+++ b/wpilibj/wpilibJavaIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/AbstractComsSetup.java
@@ -21,22 +21,17 @@ import edu.wpi.first.wpilibj.livewindow.LiveWindow;
* @author Fredric Silberberg
*/
public abstract class AbstractComsSetup {
-
/** Stores whether network coms have been initialized */
private static boolean initialized = false;
-
+
/**
* 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.
*
- * @throws InterruptedException
- * If we failed to sleep while waiting for the driver station to
- * enable.
*/
- @BeforeClass
- public static void setupNetworkComs() throws InterruptedException {
+ static{
if (!initialized) {
// Start up the network communications
FRCNetworkCommunicationsLibrary.FRCNetworkCommunicationReserve();
@@ -47,7 +42,11 @@ public abstract class AbstractComsSetup {
// Wait until the robot is enabled before starting the tests
while (!DriverStation.getInstance().isEnabled()) {
- Thread.sleep(100);
+ try {
+ Thread.sleep(100);
+ } catch (InterruptedException e) {
+ e.printStackTrace();
+ }
System.out.println("Waiting for enable");
}
@@ -56,4 +55,5 @@ public abstract class AbstractComsSetup {
System.out.println("Running!");
}
}
+
}
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 306b9adcee..fe50fde308 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
@@ -70,10 +70,11 @@ public final class TestBench {
* @return a freshly allocated Talon, Encoder pair
*/
public MotorEncoderFixture getTalonPair() {
+
MotorEncoderFixture talonPair = new MotorEncoderFixture(){
@Override
protected SpeedController giveSpeedController() {
- return new Talon(1);
+ return new Talon(0);
}
@Override
protected DigitalInput giveDigitalInputA() {
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 3636f5b8d5..b651db33bc 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
@@ -20,15 +20,19 @@ 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.SampleTest;
import edu.wpi.first.wpilibj.TiltPanCameraTest;
import edu.wpi.first.wpilibj.TimerTest;
+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.CommandTimeoutTest;
import edu.wpi.first.wpilibj.command.DefaultCommandTest;
+import edu.wpi.first.wpilibj.smartdashboard.SmartDashboardTest;
/**
* The WPILibJ Integeration Test Suite collects all of the tests to be run by
@@ -38,11 +42,15 @@ import edu.wpi.first.wpilibj.command.DefaultCommandTest;
*/
@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,
@@ -57,10 +65,11 @@ public class TestSuite {
final InputStream inputStream = TestSuite.class.getResourceAsStream("/logging.properties");
try
{
+ if(inputStream == null ) throw new NullPointerException("./logging.properties was not loaded");
LogManager.getLogManager().readConfiguration(inputStream);
Logger.getAnonymousLogger().info("Loaded");
}
- catch (final IOException e)
+ catch (final IOException | NullPointerException e)
{
Logger.getAnonymousLogger().severe("Could not load default logging.properties file");
Logger.getAnonymousLogger().severe(e.getMessage());
diff --git a/wpilibj/wpilibJavaIntegrationTests/src/main/java/logging.properties b/wpilibj/wpilibJavaIntegrationTests/src/main/java/logging.properties
index 2cc0626744..3081004405 100644
--- a/wpilibj/wpilibJavaIntegrationTests/src/main/java/logging.properties
+++ b/wpilibj/wpilibJavaIntegrationTests/src/main/java/logging.properties
@@ -12,7 +12,7 @@ handlers = java.util.logging.ConsoleHandler
# Note that the ConsoleHandler also has a separate level
# setting to limit messages printed to the console.
#.level= INFO
-.level= FINEST
+.level= INFO
############################################################
# Handler specific properties.
@@ -26,7 +26,7 @@ java.util.logging.ConsoleHandler.formatter=java.util.logging.SimpleFormatter
# Provides extra control for each logger.
############################################################
edu.wpi.first.wpilibj.level=INFO
-edu.wpi.first.wpilibj.command.level=FINEST
+edu.wpi.first.wpilibj.command.level=INFO