mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-20 00:51:42 +00:00
Updates the MotorEncoder and TestBench to clarify where setup/teardown methods are called
Change-Id: I71fd69e03b2d336297aa6769238d3e422fe38dc4
This commit is contained in:
@@ -23,13 +23,14 @@ import edu.wpi.first.wpilibj.test.TestBench;
|
||||
* @author Jonathan Leitschuh
|
||||
*
|
||||
*/
|
||||
public class MotorEncoderFixture implements ITestFixture {
|
||||
|
||||
private final SpeedController motor;
|
||||
private final Encoder encoder;
|
||||
private final Counter counters[] = new Counter[2];
|
||||
private final DigitalInput aSource; //Stored so it can be freed at tear down
|
||||
private final DigitalInput bSource;
|
||||
public abstract class MotorEncoderFixture implements ITestFixture {
|
||||
private boolean initialized = false;
|
||||
private boolean tornDown = false;
|
||||
protected SpeedController motor;
|
||||
private Encoder encoder;
|
||||
private Counter counters[] = new Counter[2];
|
||||
protected DigitalInput aSource; //Stored so it can be freed at tear down
|
||||
protected DigitalInput bSource;
|
||||
|
||||
/**
|
||||
* Default constructor for a MotorEncoderFixture
|
||||
@@ -37,24 +38,51 @@ public class MotorEncoderFixture implements ITestFixture {
|
||||
* @param aSource One of the inputs for the encoder
|
||||
* @param bSource The other input for the encoder
|
||||
*/
|
||||
public MotorEncoderFixture(SpeedController motor, DigitalInput aSource, DigitalInput bSource){
|
||||
this.aSource = aSource;
|
||||
this.bSource = bSource;
|
||||
|
||||
this.motor = motor;
|
||||
|
||||
this.encoder = new Encoder(aSource, bSource);
|
||||
counters[0] = new Counter(aSource);
|
||||
counters[1] = new Counter(bSource);
|
||||
for(Counter c: counters){
|
||||
c.start();
|
||||
public MotorEncoderFixture(){
|
||||
}
|
||||
|
||||
/**
|
||||
* 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
|
||||
*/
|
||||
abstract protected SpeedController giveSpeedController();
|
||||
/**
|
||||
* Where the implementer of this class should pass one of the digital inputs<br>
|
||||
* CONSTRUCTOR SHOULD NOT BE CALLED FROM OUTSIDE THIS CLASS!
|
||||
* @return
|
||||
*/
|
||||
abstract protected DigitalInput giveDigitalInputA();
|
||||
/**
|
||||
* Where the implementer fo this class should pass the other digital input<br>
|
||||
* CONSTRUCTOR SHOULD NOT BE CALLED FROM OUTSIDE THIS CLASS!
|
||||
* @return Input B to be used when this class is instantiated
|
||||
*/
|
||||
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();
|
||||
}
|
||||
initialized = true;
|
||||
}
|
||||
encoder.start();
|
||||
}
|
||||
|
||||
@Override
|
||||
public boolean setup() {
|
||||
return reset();
|
||||
initialize();
|
||||
encoder.start();
|
||||
return true;
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -62,6 +90,7 @@ public class MotorEncoderFixture implements ITestFixture {
|
||||
* @return the motor this object refers too
|
||||
*/
|
||||
public SpeedController getMotor(){
|
||||
initialize();
|
||||
return motor;
|
||||
}
|
||||
|
||||
@@ -70,10 +99,12 @@ public class MotorEncoderFixture implements ITestFixture {
|
||||
* @return the encoder that this object refers too
|
||||
*/
|
||||
public Encoder getEncoder(){
|
||||
initialize();
|
||||
return encoder;
|
||||
}
|
||||
|
||||
public Counter[] getCounters(){
|
||||
initialize();
|
||||
return counters;
|
||||
}
|
||||
|
||||
@@ -82,6 +113,7 @@ public class MotorEncoderFixture implements ITestFixture {
|
||||
* @return The simple name of the motor {@link Class#getSimpleName()}
|
||||
*/
|
||||
public String getType(){
|
||||
initialize();
|
||||
return motor.getClass().getSimpleName();
|
||||
}
|
||||
|
||||
@@ -94,11 +126,13 @@ public class MotorEncoderFixture implements ITestFixture {
|
||||
* {@code Math.abs((Math.abs(motor.get()) - Math.abs(value))) < Math.abs(accuracy)}
|
||||
*/
|
||||
public boolean isMotorSpeedWithinRange(double value, double accuracy){
|
||||
initialize();
|
||||
return Math.abs((Math.abs(motor.get()) - Math.abs(value))) < Math.abs(accuracy);
|
||||
}
|
||||
|
||||
@Override
|
||||
public boolean reset(){
|
||||
initialize();
|
||||
boolean wasReset = true;
|
||||
|
||||
motor.set(0);
|
||||
@@ -121,17 +155,25 @@ public class MotorEncoderFixture implements ITestFixture {
|
||||
|
||||
@Override
|
||||
public boolean teardown() {
|
||||
reset();
|
||||
if(motor instanceof PWM){
|
||||
((PWM) motor).free();
|
||||
if(!tornDown){
|
||||
initialize();
|
||||
reset();
|
||||
if(motor instanceof PWM){
|
||||
((PWM) motor).free();
|
||||
}
|
||||
motor = null;
|
||||
encoder.free();
|
||||
counters[0].free();
|
||||
counters[0] = null;
|
||||
counters[1].free();
|
||||
counters[1] = null;
|
||||
|
||||
aSource.free();
|
||||
aSource = null;
|
||||
bSource.free();
|
||||
bSource = null;
|
||||
tornDown = true;
|
||||
}
|
||||
encoder.free();
|
||||
for(Counter c : counters){
|
||||
c.free();
|
||||
}
|
||||
|
||||
aSource.free();
|
||||
bSource.free();
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
@@ -18,6 +18,7 @@ import edu.wpi.first.wpilibj.DigitalOutput;
|
||||
import edu.wpi.first.wpilibj.Gyro;
|
||||
import edu.wpi.first.wpilibj.Jaguar;
|
||||
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;
|
||||
@@ -40,7 +41,7 @@ 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.15;
|
||||
public static final double MOTOR_STOP_TIME = 0.20;
|
||||
|
||||
|
||||
//THESE MUST BE IN INCREMENTING ORDER
|
||||
@@ -69,12 +70,20 @@ public final class TestBench {
|
||||
* @return a freshly allocated Talon, Encoder pair
|
||||
*/
|
||||
public MotorEncoderFixture getTalonPair() {
|
||||
Talon talon = new Talon(0);
|
||||
DigitalInput encA1 = new DigitalInput(0);
|
||||
DigitalInput encB1 = new DigitalInput(1);
|
||||
|
||||
MotorEncoderFixture talonPair = new MotorEncoderFixture(talon, encA1,
|
||||
encB1);
|
||||
MotorEncoderFixture talonPair = new MotorEncoderFixture(){
|
||||
@Override
|
||||
protected SpeedController giveSpeedController() {
|
||||
return new Talon(1);
|
||||
}
|
||||
@Override
|
||||
protected DigitalInput giveDigitalInputA() {
|
||||
return new DigitalInput(0);
|
||||
}
|
||||
@Override
|
||||
protected DigitalInput giveDigitalInputB() {
|
||||
return new DigitalInput(1);
|
||||
}
|
||||
};
|
||||
return talonPair;
|
||||
}
|
||||
|
||||
@@ -85,10 +94,23 @@ public final class TestBench {
|
||||
* @return a freshly allocated Victor, Encoder pair
|
||||
*/
|
||||
public MotorEncoderFixture getVictorPair() {
|
||||
Victor vic = new Victor(1);
|
||||
DigitalInput encA2 = new DigitalInput(2);
|
||||
DigitalInput encB2 = new DigitalInput(3);
|
||||
MotorEncoderFixture vicPair = new MotorEncoderFixture(vic, encA2, encB2);
|
||||
|
||||
MotorEncoderFixture vicPair = new MotorEncoderFixture(){
|
||||
@Override
|
||||
protected SpeedController giveSpeedController() {
|
||||
return new Victor(1);
|
||||
}
|
||||
|
||||
@Override
|
||||
protected DigitalInput giveDigitalInputA() {
|
||||
return new DigitalInput(2);
|
||||
}
|
||||
|
||||
@Override
|
||||
protected DigitalInput giveDigitalInputB() {
|
||||
return new DigitalInput(3);
|
||||
}
|
||||
};
|
||||
return vicPair;
|
||||
}
|
||||
|
||||
@@ -99,10 +121,22 @@ public final class TestBench {
|
||||
* @return a freshly allocated Jaguar, Encoder pair
|
||||
*/
|
||||
public MotorEncoderFixture getJaguarPair() {
|
||||
Jaguar jag = new Jaguar(2);
|
||||
DigitalInput encA3 = new DigitalInput(4);
|
||||
DigitalInput encB3 = new DigitalInput(5);
|
||||
MotorEncoderFixture jagPair = new MotorEncoderFixture(jag, encA3, encB3);
|
||||
MotorEncoderFixture jagPair = new MotorEncoderFixture(){
|
||||
@Override
|
||||
protected SpeedController giveSpeedController() {
|
||||
return new Jaguar(2);
|
||||
}
|
||||
|
||||
@Override
|
||||
protected DigitalInput giveDigitalInputA() {
|
||||
return new DigitalInput(4);
|
||||
}
|
||||
|
||||
@Override
|
||||
protected DigitalInput giveDigitalInputB() {
|
||||
return new DigitalInput(5);
|
||||
}
|
||||
};
|
||||
return jagPair;
|
||||
}
|
||||
|
||||
@@ -115,9 +149,6 @@ public final class TestBench {
|
||||
* @return an existing CANJaguar and a freshly allocated Encoder
|
||||
*/
|
||||
public MotorEncoderFixture getCanJaguarPair() {
|
||||
|
||||
DigitalInput encA4 = new DigitalInput(6);
|
||||
DigitalInput encB4 = new DigitalInput(7);
|
||||
MotorEncoderFixture canPair;
|
||||
if (canJag == null) { // Again this is because the CanJaguar does not
|
||||
// have a free method
|
||||
@@ -127,7 +158,20 @@ public final class TestBench {
|
||||
e.printStackTrace();
|
||||
}
|
||||
}
|
||||
canPair = new MotorEncoderFixture(canJag, encA4, encB4);
|
||||
canPair = new MotorEncoderFixture(){
|
||||
@Override
|
||||
protected SpeedController giveSpeedController() {
|
||||
return canJag;
|
||||
}
|
||||
@Override
|
||||
protected DigitalInput giveDigitalInputA() {
|
||||
return new DigitalInput(6);
|
||||
}
|
||||
@Override
|
||||
protected DigitalInput giveDigitalInputB() {
|
||||
return new DigitalInput(7);
|
||||
}
|
||||
};
|
||||
assert canPair != null;
|
||||
return canPair;
|
||||
}
|
||||
|
||||
Reference in New Issue
Block a user