diff --git a/wpilibj/wpilibJavaSim/src/main/java/edu/wpi/first/wpilibj/AnalogInput.java b/wpilibj/wpilibJavaSim/src/main/java/edu/wpi/first/wpilibj/AnalogInput.java index f25f23b143..31feefa41e 100644 --- a/wpilibj/wpilibJavaSim/src/main/java/edu/wpi/first/wpilibj/AnalogInput.java +++ b/wpilibj/wpilibJavaSim/src/main/java/edu/wpi/first/wpilibj/AnalogInput.java @@ -31,7 +31,7 @@ public class AnalogInput extends SensorBase implements PIDSource, private SimFloatInput m_impl; private int m_channel; - protected PIDSourceParameter m_pidSource = PIDSourceParameter.kDistance; + protected PIDSourceType m_pidSource = PIDSourceType.kDisplacement; /** * Construct an analog channel. @@ -91,14 +91,14 @@ public class AnalogInput extends SensorBase implements PIDSource, /** * {@inheritDoc} */ - public void setPIDSourceParameter(PIDSourceParameter pidSource) { + public void setPIDSourceType(PIDSourceType pidSource) { m_pidSource = pidSource; } /** * {@inheritDoc} */ - public PIDSourceParameter getPIDSourceParameter() { + public PIDSourceType getPIDSourceType() { return m_pidSource; } diff --git a/wpilibj/wpilibJavaSim/src/main/java/edu/wpi/first/wpilibj/AnalogPotentiometer.java b/wpilibj/wpilibJavaSim/src/main/java/edu/wpi/first/wpilibj/AnalogPotentiometer.java index 460ad8c2c4..a039304462 100644 --- a/wpilibj/wpilibJavaSim/src/main/java/edu/wpi/first/wpilibj/AnalogPotentiometer.java +++ b/wpilibj/wpilibJavaSim/src/main/java/edu/wpi/first/wpilibj/AnalogPotentiometer.java @@ -21,7 +21,7 @@ public class AnalogPotentiometer implements Potentiometer, LiveWindowSendable { private double m_scale, m_offset; private AnalogInput m_analog_input; private boolean m_init_analog_input; - protected PIDSourceParameter m_pidSource = PIDSourceParameter.kDistance; + protected PIDSourceType m_pidSource = PIDSourceType.kDisplacement; /** * Common initialization code called by all constructors. @@ -138,14 +138,14 @@ public class AnalogPotentiometer implements Potentiometer, LiveWindowSendable { /** * {@inheritDoc} */ - public void setPIDSourceParameter(PIDSourceParameter pidSource) { + public void setPIDSourceType(PIDSourceType pidSource) { m_pidSource = pidSource; } /** * {@inheritDoc} */ - public PIDSourceParameter getPIDSourceParameter() { + public PIDSourceType getPIDSourceType() { return m_pidSource; } diff --git a/wpilibj/wpilibJavaSim/src/main/java/edu/wpi/first/wpilibj/CounterBase.java b/wpilibj/wpilibJavaSim/src/main/java/edu/wpi/first/wpilibj/CounterBase.java index 29216391ba..566c5ba1ab 100644 --- a/wpilibj/wpilibJavaSim/src/main/java/edu/wpi/first/wpilibj/CounterBase.java +++ b/wpilibj/wpilibJavaSim/src/main/java/edu/wpi/first/wpilibj/CounterBase.java @@ -20,31 +20,28 @@ public interface CounterBase { /** * The number of edges for the counterbase to increment or decrement on */ - public static class EncodingType { + public enum EncodingType { + /** + * Count only the rising edge + */ + k1X(0), + /** + * Count both the rising and falling edge + */ + k2X(1), + /** + * Count rising and falling on both channels + */ + k4X(2); - /** - * The integer value representing this enumeration - */ - public final int value; - static final int k1X_val = 0; - static final int k2X_val = 1; - static final int k4X_val = 2; - /** - * Count only the rising edge - */ - public static final EncodingType k1X = new EncodingType(k1X_val); - /** - * Count both the rising and falling edge - */ - public static final EncodingType k2X = new EncodingType(k2X_val); - /** - * Count rising and falling on both channels - */ - public static final EncodingType k4X = new EncodingType(k4X_val); + /** + * The integer value representing this enumeration + */ + public final int value; - private EncodingType(int value) { - this.value = value; - } + private EncodingType(int value) { + this.value = value; + } } /** diff --git a/wpilibj/wpilibJavaSim/src/main/java/edu/wpi/first/wpilibj/Encoder.java b/wpilibj/wpilibJavaSim/src/main/java/edu/wpi/first/wpilibj/Encoder.java index 4553ad1943..80e1196509 100644 --- a/wpilibj/wpilibJavaSim/src/main/java/edu/wpi/first/wpilibj/Encoder.java +++ b/wpilibj/wpilibJavaSim/src/main/java/edu/wpi/first/wpilibj/Encoder.java @@ -10,7 +10,6 @@ import edu.wpi.first.wpilibj.livewindow.LiveWindow; import edu.wpi.first.wpilibj.livewindow.LiveWindowSendable; import edu.wpi.first.wpilibj.simulation.SimEncoder; import edu.wpi.first.wpilibj.tables.ITable; -import edu.wpi.first.wpilibj.util.BoundaryException; /** * Class to read quad encoders. Quadrature encoders are devices that count shaft @@ -34,7 +33,7 @@ public class Encoder extends SensorBase implements CounterBase, PIDSource, LiveW private boolean m_allocatedB; private boolean m_allocatedI; private boolean m_reverseDirection; - private PIDSourceParameter m_pidSource; + private PIDSourceType m_pidSource; private SimEncoder impl; /** @@ -56,7 +55,7 @@ public class Encoder extends SensorBase implements CounterBase, PIDSource, LiveW */ private void initEncoder(int aChannel, int bChannel, boolean reverseDirection) { m_distancePerPulse = 1.0; - m_pidSource = PIDSourceParameter.kDistance; + m_pidSource = PIDSourceType.kDisplacement; m_encodingScale = m_encodingType == EncodingType.k4X ? 4 : m_encodingType == EncodingType.k2X ? 2 : 1; @@ -275,15 +274,14 @@ public class Encoder extends SensorBase implements CounterBase, PIDSource, LiveW * @param pidSource * An enum to select the parameter. */ - public void setPIDSourceParameter(PIDSourceParameter pidSource) { - BoundaryException.assertWithinBounds(pidSource.value, 0, 1); + public void setPIDSourceType(PIDSourceType pidSource) { m_pidSource = pidSource; } /** * {@inheritDoc} */ - public PIDSourceParameter getPIDSourceParameter() { + public PIDSourceType getPIDSourceType() { return m_pidSource; } @@ -293,10 +291,10 @@ public class Encoder extends SensorBase implements CounterBase, PIDSource, LiveW * @return The current value of the selected source parameter. */ public double pidGet() { - switch (m_pidSource.value) { - case PIDSourceParameter.kDistance_val: + switch (m_pidSource) { + case kDisplacement: return getDistance(); - case PIDSourceParameter.kRate_val: + case kRate: return getRate(); default: return 0.0; @@ -307,8 +305,8 @@ public class Encoder extends SensorBase implements CounterBase, PIDSource, LiveW * Live Window code, only does anything if live window is activated. */ public String getSmartDashboardType() { - switch (m_encodingType.value) { - case EncodingType.k4X_val: + switch (m_encodingType) { + case k4X: return "Quadrature Encoder"; default: return "Encoder"; diff --git a/wpilibj/wpilibJavaSim/src/main/java/edu/wpi/first/wpilibj/Gyro.java b/wpilibj/wpilibJavaSim/src/main/java/edu/wpi/first/wpilibj/Gyro.java index bfe13be102..023044497e 100644 --- a/wpilibj/wpilibJavaSim/src/main/java/edu/wpi/first/wpilibj/Gyro.java +++ b/wpilibj/wpilibJavaSim/src/main/java/edu/wpi/first/wpilibj/Gyro.java @@ -10,7 +10,6 @@ import edu.wpi.first.wpilibj.livewindow.LiveWindow; import edu.wpi.first.wpilibj.livewindow.LiveWindowSendable; import edu.wpi.first.wpilibj.simulation.SimGyro; import edu.wpi.first.wpilibj.tables.ITable; -import edu.wpi.first.wpilibj.util.BoundaryException; /** * Use a rate gyro to return the robots heading relative to a starting position. @@ -23,7 +22,7 @@ import edu.wpi.first.wpilibj.util.BoundaryException; */ public class Gyro extends SensorBase implements PIDSource, LiveWindowSendable { - private PIDSourceParameter m_pidSource; + private PIDSourceType m_pidSource; private SimGyro impl; /** @@ -38,7 +37,7 @@ public class Gyro extends SensorBase implements PIDSource, LiveWindowSendable { impl = new SimGyro("simulator/analog/"+channel); reset(); - setPIDSourceParameter(PIDSourceParameter.kAngle); + setPIDSourceType(PIDSourceType.kDisplacement); LiveWindow.addSensor("Gyro", channel, this); } @@ -113,15 +112,14 @@ public class Gyro extends SensorBase implements PIDSource, LiveWindowSendable { * @param pidSource * An enum to select the parameter. */ - public void setPIDSourceParameter(PIDSourceParameter pidSource) { - BoundaryException.assertWithinBounds(pidSource.value, 1, 2); + public void setPIDSourceType(PIDSourceType pidSource) { m_pidSource = pidSource; } /** * {@inheritDoc} */ - public PIDSourceParameter getPIDSourceParameter() { + public PIDSourceType getPIDSourceType() { return m_pidSource; } @@ -131,10 +129,10 @@ public class Gyro extends SensorBase implements PIDSource, LiveWindowSendable { * @return the current angle according to the gyro */ public double pidGet() { - switch (m_pidSource.value) { - case PIDSourceParameter.kRate_val: + switch (m_pidSource) { + case kRate: return getRate(); - case PIDSourceParameter.kAngle_val: + case kDisplacement: return getAngle(); default: return 0.0;