From dff5023d9c5cb5c08ddbd667ecee49b0d5efe654 Mon Sep 17 00:00:00 2001 From: Noah Gleason Date: Tue, 31 Oct 2017 13:55:55 -0400 Subject: [PATCH] Use fields everywhere. --- .../jacksonWrappers/MappedDigitalInput.java | 7 ++- .../robot/oi/unidirectional/OIOutreach.java | 6 ++ .../oi/unidirectional/arcade/OIArcade.java | 6 ++ .../arcade/OIArcadeWithDPad.java | 52 ++++----------- .../robot/oi/unidirectional/tank/OITank.java | 3 + .../other/UnidirectionalPoseEstimator.java | 63 ++++++++++--------- .../climber/ClimberCurrentLimited.java | 3 + .../complex/shooter/LoggingShooter.java | 2 +- 8 files changed, 70 insertions(+), 72 deletions(-) diff --git a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/jacksonWrappers/MappedDigitalInput.java b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/jacksonWrappers/MappedDigitalInput.java index d093b33f..40249105 100644 --- a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/jacksonWrappers/MappedDigitalInput.java +++ b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/jacksonWrappers/MappedDigitalInput.java @@ -18,6 +18,11 @@ public class MappedDigitalInput { */ @JsonIgnore private final List digitalInputs; + + /** + * Value of the inputs. Field to avoid garbage collection. + */ + private List digitalValues; /** * Construct a MappedDigitalInput. @@ -41,7 +46,7 @@ public MappedDigitalInput(@NotNull @JsonProperty(required = true) int[] ports) { @JsonIgnore @NotNull public List getStatus() { - List digitalValues = new ArrayList<>(); + digitalValues = new ArrayList<>(); for (DigitalInput digitalInput : digitalInputs) { //Negated because, by default, false means signal and true means no signal, and that's dumb. digitalValues.add(!digitalInput.get()); diff --git a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/oi/unidirectional/OIOutreach.java b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/oi/unidirectional/OIOutreach.java index 53d4dfa8..c0073b9e 100644 --- a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/oi/unidirectional/OIOutreach.java +++ b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/oi/unidirectional/OIOutreach.java @@ -30,8 +30,14 @@ public class OIOutreach implements OIUnidirectional { @NotNull private final Button button; + /** + * The cached outputs for the left and right sides of the drive. + */ private double cachedLeftOutput, cachedRightOutput; + /** + * Whether the driver was trying to drive straight when values were cached. + */ private boolean cachedCommandingStraight; @JsonCreator diff --git a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/oi/unidirectional/arcade/OIArcade.java b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/oi/unidirectional/arcade/OIArcade.java index 28814847..1cfb45c3 100644 --- a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/oi/unidirectional/arcade/OIArcade.java +++ b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/oi/unidirectional/arcade/OIArcade.java @@ -9,8 +9,14 @@ @JsonTypeInfo(use = JsonTypeInfo.Id.CLASS, include = JsonTypeInfo.As.WRAPPER_OBJECT, property = "@class") public abstract class OIArcade implements OIUnidirectional { + /** + * Cached output values. + */ private double rotCached, fwdCached, leftCached, rightCached; + /** + * Whether the driver was trying to drive straight when values were cached. + */ private boolean commandingStraightCached; /** diff --git a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/oi/unidirectional/arcade/OIArcadeWithDPad.java b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/oi/unidirectional/arcade/OIArcadeWithDPad.java index 4d35b5c6..c00e57d4 100644 --- a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/oi/unidirectional/arcade/OIArcadeWithDPad.java +++ b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/oi/unidirectional/arcade/OIArcadeWithDPad.java @@ -55,16 +55,6 @@ public class OIArcadeWithDPad extends OIArcade implements Loggable { */ private final double turnInPlaceRotScale; - /** - * Cached forwards and rotation values. - */ - private double cachedFwd, cachedRot; - - /** - * The time velocity and rotation were cached at. - */ - private long timeLastCached; - /** * Default constructor * @@ -95,31 +85,7 @@ public OIArcadeWithDPad( this.turnInPlaceRotScale = turnInPlaceRotScale; timeLastCached = 0; } - - /** - * Calculate and cache the values of fwd and rot. - */ - private void cacheValues() { - if (Clock.currentTimeMillis() > timeLastCached) { - timeLastCached = Clock.currentTimeMillis(); - - //Forwards is simple - cachedFwd = fwdThrottle.getValue(); - - //If the gamepad is being pushed to the left or right - if (gamepad != null && !(gamepad.getPOV() == -1 || gamepad.getPOV() % 180 == 0)) { - //Output the shift value - cachedRot = gamepad.getPOV() < 180 ? dPadShift : -dPadShift; - } else if (cachedFwd == 0) { //Turning in place - cachedRot = rotThrottle.getValue() * turnInPlaceRotScale; - } else if (scaleRotByFwdPoly != null) { //If we're using Cheezy Drive - cachedRot = rotThrottle.getValue() * scaleRotByFwdPoly.get(Math.abs(cachedFwd)); - } else { //Plain and simple - cachedRot = rotThrottle.getValue(); - } - } - } - + /** * The output of the throttle controlling linear velocity, smoothed and adjusted according to what type of joystick * it is. @@ -128,8 +94,7 @@ private void cacheValues() { */ @Override public double getFwd() { - cacheValues(); - return cachedFwd; + return fwdThrottle.getValue(); } /** @@ -140,8 +105,17 @@ public double getFwd() { */ @Override public double getRot() { - cacheValues(); - return cachedRot; + //If the gamepad is being pushed to the left or right + if (gamepad != null && !(gamepad.getPOV() == -1 || gamepad.getPOV() % 180 == 0)) { + //Output the shift value + return gamepad.getPOV() < 180 ? dPadShift : -dPadShift; + } else if (getFwd() == 0) { //Turning in place + return rotThrottle.getValue() * turnInPlaceRotScale; + } else if (scaleRotByFwdPoly != null) { //If we're using Cheezy Drive + return rotThrottle.getValue() * scaleRotByFwdPoly.get(Math.abs(getFwd())); + } else { //Plain and simple + return rotThrottle.getValue(); + } } /** diff --git a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/oi/unidirectional/tank/OITank.java b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/oi/unidirectional/tank/OITank.java index be59983d..1aa1dc93 100644 --- a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/oi/unidirectional/tank/OITank.java +++ b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/oi/unidirectional/tank/OITank.java @@ -9,6 +9,9 @@ @JsonTypeInfo(use = JsonTypeInfo.Id.CLASS, include = JsonTypeInfo.As.WRAPPER_OBJECT, property = "@class") public abstract class OITank implements OIUnidirectional { + /** + * Cached left and right throttle values. + */ private double leftThrottleCached, rightThrottleCached; /** diff --git a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/other/UnidirectionalPoseEstimator.java b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/other/UnidirectionalPoseEstimator.java index 19e8eb0f..99d8ce01 100644 --- a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/other/UnidirectionalPoseEstimator.java +++ b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/other/UnidirectionalPoseEstimator.java @@ -103,6 +103,22 @@ public class UnidirectionalPoseEstimator 0) { percentChanged = ((deltaRight + robotDiameter * deltaTheta) - deltaLeft) / deltaLeft; diff --git a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/subsystem/complex/climber/ClimberCurrentLimited.java b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/subsystem/complex/climber/ClimberCurrentLimited.java index 039e9584..f64ea714 100644 --- a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/subsystem/complex/climber/ClimberCurrentLimited.java +++ b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/subsystem/complex/climber/ClimberCurrentLimited.java @@ -48,6 +48,9 @@ public class ClimberCurrentLimited extends YamlSubsystem implements Loggable, Su */ private boolean motorSpinning; + /** + * Whether the condition was met last time caching was done. + */ private boolean conditionMetCached; diff --git a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/subsystem/complex/shooter/LoggingShooter.java b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/subsystem/complex/shooter/LoggingShooter.java index a2125160..42d2fbff 100644 --- a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/subsystem/complex/shooter/LoggingShooter.java +++ b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/subsystem/complex/shooter/LoggingShooter.java @@ -120,7 +120,7 @@ public Object[] getData() { @NotNull @Override public String getName() { - return "multiSubsystem"; + return "loggingShooter"; } /**