diff --git a/.github/linters/checkstyle.xml b/.github/linters/checkstyle.xml index dbf17fcf..5212262a 100644 --- a/.github/linters/checkstyle.xml +++ b/.github/linters/checkstyle.xml @@ -74,12 +74,12 @@ - + @@ -90,8 +90,9 @@ - + + @@ -123,7 +124,7 @@ - + @@ -151,7 +152,7 @@ - + @@ -160,10 +161,12 @@ - - + + + + - + @@ -173,7 +176,9 @@ - + + + @@ -181,8 +186,8 @@ - - + + @@ -192,6 +197,12 @@ + + + + + + \ No newline at end of file diff --git a/.github/workflows/linter.yml b/.github/workflows/linter.yml index 06becda8..02541e4c 100644 --- a/.github/workflows/linter.yml +++ b/.github/workflows/linter.yml @@ -28,4 +28,7 @@ jobs: DEFAULT_BRANCH: master GITHUB_TOKEN: ${{ secrets.GITHUB_TOKEN }} IGNORE_GITIGNORED_FILES: true - VALIDATE_JAVA_CHECKSTYLE: true \ No newline at end of file + VALIDATE_GOOGLE_JAVA_FORMAT: false + VALIDATE_JSCPD: false + VALIDATE_MARKDOWN: false + JAVA_FILE_NAME: 'checkstyle.xml' \ No newline at end of file diff --git a/src/main/java/com/team766/config/AbstractConfigMultiValue.java b/src/main/java/com/team766/config/AbstractConfigMultiValue.java index c3a769c1..7ba96a12 100644 --- a/src/main/java/com/team766/config/AbstractConfigMultiValue.java +++ b/src/main/java/com/team766/config/AbstractConfigMultiValue.java @@ -8,16 +8,16 @@ abstract class AbstractConfigMultiValue extends AbstractConfigValue { private final IntFunction m_arrayFactory; @SuppressWarnings("unchecked") - protected AbstractConfigMultiValue(String key, Class elementClass) { + protected AbstractConfigMultiValue(final String key, final Class elementClass) { super(key); - m_arrayFactory = (int length) -> (E[])Array.newInstance(elementClass, length); + m_arrayFactory = (int length) -> (E[]) Array.newInstance(elementClass, length); } @Override - protected final E[] parseJsonValue(Object configValue) { + protected final E[] parseJsonValue(final Object configValue) { JSONArray jsonArray; try { - jsonArray = (JSONArray)configValue; + jsonArray = (JSONArray) configValue; } catch (ClassCastException ex) { final E[] valueArray = m_arrayFactory.apply(1); valueArray[0] = parseJsonElement(configValue); diff --git a/src/main/java/com/team766/config/AbstractConfigValue.java b/src/main/java/com/team766/config/AbstractConfigValue.java index 78d470f7..2d02351d 100644 --- a/src/main/java/com/team766/config/AbstractConfigValue.java +++ b/src/main/java/com/team766/config/AbstractConfigValue.java @@ -14,9 +14,9 @@ public abstract class AbstractConfigValue implements SettableValueProvider private E m_cachedValue; private boolean m_cachedHasValue; private int m_cachedGeneration = -1; - + private static ArrayList> c_accessedValues = new ArrayList>(); - + static Collection> accessedValues() { return Collections.unmodifiableCollection(c_accessedValues); } @@ -24,15 +24,15 @@ static Collection> accessedValues() { static void resetStatics() { c_accessedValues.clear(); } - - protected AbstractConfigValue(String key) { + + protected AbstractConfigValue(final String key) { m_key = key; c_accessedValues.add(this); // Querying for this config setting's key will add a placeholder entry // in the config file if this setting does not already exist there. ConfigFileReader.instance.getRawValue(m_key); } - + private void sync() { if (ConfigFileReader.instance.getGeneration() != m_cachedGeneration) { m_cachedGeneration = ConfigFileReader.instance.getGeneration(); @@ -42,7 +42,9 @@ private void sync() { try { m_cachedValue = parseJsonValue(rawValue); } catch (Exception ex) { - Logger.get(Category.CONFIGURATION).logRaw(Severity.ERROR, "Failed to parse " + m_key + " from the config file: " + LoggerExceptionUtils.exceptionToString(ex)); + Logger.get(Category.CONFIGURATION).logRaw(Severity.ERROR, + "Failed to parse " + m_key + " from the config file: " + + LoggerExceptionUtils.exceptionToString(ex)); m_cachedValue = null; m_cachedHasValue = false; } @@ -53,13 +55,13 @@ private void sync() { public String getKey() { return m_key; } - + @Override public boolean hasValue() { sync(); return m_cachedHasValue; } - + @Override public E get() { sync(); @@ -69,16 +71,16 @@ public E get() { return m_cachedValue; } - public void set(E value) { + public void set(final E value) { ConfigFileReader.instance.setValue(m_key, value); } public void clear() { ConfigFileReader.instance.setValue(m_key, null); } - + protected abstract E parseJsonValue(Object configValue); - + @Override public String toString() { sync(); diff --git a/src/main/java/com/team766/config/ConfigFileReader.java b/src/main/java/com/team766/config/ConfigFileReader.java index 60b12606..ad260994 100755 --- a/src/main/java/com/team766/config/ConfigFileReader.java +++ b/src/main/java/com/team766/config/ConfigFileReader.java @@ -17,31 +17,31 @@ /** * Class for loading in config from the Config file. * Constants that need to be tuned / changed - * + * * Data is read from a file in JSON format - * + * * @author Brett Levenson */ public class ConfigFileReader { // this.getClass().getClassLoader().getResource(fileName).getPath() - + public static ConfigFileReader instance; private static final String KEY_DELIMITER = "."; - + // This is incremented each time the config file is reloaded to ensure that ConfigValues use the most recent setting. private int m_generation = 0; - + private String m_fileName; private JSONObject m_values = new JSONObject(); - + public static ConfigFileReader getInstance() { return instance; } - - public ConfigFileReader(String fileName) { + + public ConfigFileReader(final String fileName) { m_fileName = fileName; - + try { reloadFromFile(); } catch (Exception e) { @@ -50,14 +50,14 @@ public ConfigFileReader(String fileName) { LoggerExceptionUtils.logException(new IOException("Failed to load config file!", e)); } } - + public void reloadFromFile() throws IOException { System.out.println("Loading config file: " + m_fileName); String jsonString = Files.readString(Paths.get(m_fileName)); reloadFromJson(jsonString); } - public void reloadFromJson(String jsonString) { + public void reloadFromJson(final String jsonString) { JSONObject newValues; try (StringReader reader = new StringReader(jsonString)) { newValues = new JSONObject(new JSONTokener(reader)); @@ -70,70 +70,69 @@ public void reloadFromJson(String jsonString) { try { param.parseJsonValue(rawValue); } catch (Exception ex) { - throw new ConfigValueParseException("Could not parse config value for " + param.getKey(), ex); + throw new ConfigValueParseException( + "Could not parse config value for " + param.getKey(), ex); } } m_values = newValues; ++m_generation; } - + public int getGeneration() { return m_generation; } - - public boolean containsKey(String key) { + + public boolean containsKey(final String key) { return getRawValue(key) != null; } - - public SettableValueProvider getInts(String key) { + + public SettableValueProvider getInts(final String key) { return new IntegerConfigMultiValue(key); } - - public SettableValueProvider getInt(String key) { + + public SettableValueProvider getInt(final String key) { return new IntegerConfigValue(key); } - - public SettableValueProvider getDoubles(String key) { + + public SettableValueProvider getDoubles(final String key) { return new DoubleConfigMultiValue(key); } - - public SettableValueProvider getDouble(String key) { + + public SettableValueProvider getDouble(final String key) { return new DoubleConfigValue(key); } - - public SettableValueProvider getBoolean(String key) { + + public SettableValueProvider getBoolean(final String key) { return new BooleanConfigValue(key); } - - public SettableValueProvider getString(String key) { + + public SettableValueProvider getString(final String key) { return new StringConfigValue(key); } - public > SettableValueProvider getEnum(Class enumClass, String key) { + public > SettableValueProvider getEnum(final Class enumClass, + final String key) { return new EnumConfigValue(enumClass, key); } - public void setValue(String key, E value) { + public void setValue(final String key, final E value) { String[] keyParts = splitKey(key); JSONObject parentObj = getParent(m_values, keyParts); - parentObj.putOpt( - keyParts[keyParts.length - 1], - value == null ? JSONObject.NULL : value); + parentObj.putOpt(keyParts[keyParts.length - 1], value == null ? JSONObject.NULL : value); } - Object getRawValue(String key) { + Object getRawValue(final String key) { return getRawValue(m_values, key); } - private static Object getRawValue(JSONObject obj, String key) { + private static Object getRawValue(final JSONObject obj, final String key) { String[] keyParts = splitKey(key); JSONObject parentObj = getParent(obj, keyParts); var rawValue = parentObj.opt(keyParts[keyParts.length - 1]); if (rawValue instanceof JSONObject) { - throw new IllegalArgumentException( - "The config file cannot store both a single config " + - "setting and a group of config settings with the name " + - key + " Please pick a different name"); + throw new IllegalArgumentException("The config file cannot store both a single config " + + "setting and a group of config settings with the name " + key + + " Please pick a different name"); } if (rawValue == null) { parentObj.put(keyParts[keyParts.length - 1], JSONObject.NULL); @@ -144,21 +143,21 @@ private static Object getRawValue(JSONObject obj, String key) { return rawValue; } - private static String[] splitKey(String key) { + private static String[] splitKey(final String key) { return key.split(Pattern.quote(KEY_DELIMITER)); } - private static JSONObject getParent(JSONObject obj, String[] keyParts) { + private static JSONObject getParent(JSONObject obj, final String[] keyParts) { for (int i = 0; i < keyParts.length - 1; ++i) { JSONObject subObj; try { - subObj = (JSONObject)obj.opt(keyParts[i]); + subObj = (JSONObject) obj.opt(keyParts[i]); } catch (ClassCastException ex) { throw new IllegalArgumentException( - "The config file cannot store both a single config " + - "setting and a group of config settings with the name " + - String.join(KEY_DELIMITER, keyParts) + - " Please pick a different name for one of them."); + "The config file cannot store both a single config " + + "setting and a group of config settings with the name " + + String.join(KEY_DELIMITER, keyParts) + + " Please pick a different name for one of them."); } if (subObj == null) { subObj = new JSONObject(); @@ -172,9 +171,9 @@ private static JSONObject getParent(JSONObject obj, String[] keyParts) { public String getJsonString() { return m_values.toString(2); } - - public void saveFile(String jsonString) throws IOException { - try(FileWriter writer = new FileWriter(m_fileName)) { + + public void saveFile(final String jsonString) throws IOException { + try (FileWriter writer = new FileWriter(m_fileName)) { writer.write(jsonString); } Logger.get(Category.CONFIGURATION).logRaw(Severity.INFO, "Config file written to " + m_fileName); diff --git a/src/main/java/com/team766/config/ConfigValue.java b/src/main/java/com/team766/config/ConfigValue.java index c6e876f8..68d9ef28 100644 --- a/src/main/java/com/team766/config/ConfigValue.java +++ b/src/main/java/com/team766/config/ConfigValue.java @@ -4,82 +4,88 @@ import java.util.stream.Collectors; class DoubleConfigValue extends AbstractConfigValue { - protected DoubleConfigValue(String key) { + protected DoubleConfigValue(final String key) { super(key); } @Override - public Double parseJsonValue(Object configValue) { - return ((Number)configValue).doubleValue(); + public Double parseJsonValue(final Object configValue) { + return ((Number) configValue).doubleValue(); } } + class IntegerConfigValue extends AbstractConfigValue { - protected IntegerConfigValue(String key) { + protected IntegerConfigValue(final String key) { super(key); } @Override - public Integer parseJsonValue(Object configValue) { - return ((Number)configValue).intValue(); + public Integer parseJsonValue(final Object configValue) { + return ((Number) configValue).intValue(); } } + class DoubleConfigMultiValue extends AbstractConfigMultiValue { - protected DoubleConfigMultiValue(String key) { + protected DoubleConfigMultiValue(final String key) { super(key, Double.class); } @Override - public Double parseJsonElement(Object configElement) { - return ((Number)configElement).doubleValue(); + public Double parseJsonElement(final Object configElement) { + return ((Number) configElement).doubleValue(); } } + class IntegerConfigMultiValue extends AbstractConfigMultiValue { - protected IntegerConfigMultiValue(String key) { + protected IntegerConfigMultiValue(final String key) { super(key, Integer.class); } @Override - public Integer parseJsonElement(Object configElement) { - return ((Number)configElement).intValue(); + public Integer parseJsonElement(final Object configElement) { + return ((Number) configElement).intValue(); } } + class BooleanConfigValue extends AbstractConfigValue { - protected BooleanConfigValue(String key) { + protected BooleanConfigValue(final String key) { super(key); } @Override - public Boolean parseJsonValue(Object configValue) { - return (Boolean)configValue; + public Boolean parseJsonValue(final Object configValue) { + return (Boolean) configValue; } } + class StringConfigValue extends AbstractConfigValue { - protected StringConfigValue(String key) { + protected StringConfigValue(final String key) { super(key); } @Override - public String parseJsonValue(Object configValue) { - return (String)configValue; + public String parseJsonValue(final Object configValue) { + return (String) configValue; } } + class EnumConfigValue> extends AbstractConfigValue { Class enumClass; - protected EnumConfigValue(Class enumClass, String key) { + protected EnumConfigValue(final Class enumClass_, final String key) { super(key); - this.enumClass = enumClass; + this.enumClass = enumClass_; } @Override - public E parseJsonValue(Object configValue) { - String enumName = (String)configValue; + public E parseJsonValue(final Object configValue) { + String enumName = (String) configValue; for (E each : enumClass.getEnumConstants()) { if (each.name().compareToIgnoreCase(enumName) == 0) { return each; diff --git a/src/main/java/com/team766/config/ConfigValueParseException.java b/src/main/java/com/team766/config/ConfigValueParseException.java index c07709d5..8299e926 100644 --- a/src/main/java/com/team766/config/ConfigValueParseException.java +++ b/src/main/java/com/team766/config/ConfigValueParseException.java @@ -2,12 +2,12 @@ public class ConfigValueParseException extends RuntimeException { private static final long serialVersionUID = -3235627203813966130L; - - public ConfigValueParseException(String message) { + + public ConfigValueParseException(final String message) { super(message); } - public ConfigValueParseException(String message, Throwable cause) { + public ConfigValueParseException(final String message, final Throwable cause) { super(message, cause); } } \ No newline at end of file diff --git a/src/main/java/com/team766/controllers/MotionLockout.java b/src/main/java/com/team766/controllers/MotionLockout.java index 04646e69..8eab98d7 100644 --- a/src/main/java/com/team766/controllers/MotionLockout.java +++ b/src/main/java/com/team766/controllers/MotionLockout.java @@ -13,7 +13,7 @@ public class MotionLockout { private ValueProvider m_maxPosition; private ValueProvider m_minCommand; private ValueProvider m_maxCommand; - + public static MotionLockout loadFromConfig(String configPrefix) { if (!configPrefix.endsWith(".")) { configPrefix += "."; @@ -24,26 +24,25 @@ public static MotionLockout loadFromConfig(String configPrefix) { ConfigFileReader.getInstance().getDouble(configPrefix + "minCommand"), ConfigFileReader.getInstance().getDouble(configPrefix + "maxCommand")); } - - public MotionLockout(double minPosition, double maxPosition, double minCommand, double maxCommand) { + + public MotionLockout(final double minPosition, final double maxPosition, + final double minCommand, final double maxCommand) { m_minPosition = new SetValueProvider(minPosition); m_maxPosition = new SetValueProvider(maxPosition); m_minCommand = new SetValueProvider(minCommand); m_maxCommand = new SetValueProvider(maxCommand); } - - public MotionLockout( - ValueProvider minPosition, - ValueProvider maxPosition, - ValueProvider minCommand, - ValueProvider maxCommand) { + + public MotionLockout(final ValueProvider minPosition, + final ValueProvider maxPosition, final ValueProvider minCommand, + final ValueProvider maxCommand) { m_minPosition = minPosition; m_maxPosition = maxPosition; m_minCommand = minCommand; m_maxCommand = maxCommand; } - - public double filter(double inputCommand, double sensorPosition) { + + public double filter(final double inputCommand, final double sensorPosition) { if (sensorPosition >= m_minPosition.get() && sensorPosition <= m_maxPosition.get()) { if (inputCommand < m_minCommand.get()) { return m_minCommand.get(); diff --git a/src/main/java/com/team766/controllers/PIDController.java b/src/main/java/com/team766/controllers/PIDController.java index 93fd4e86..463252c1 100755 --- a/src/main/java/com/team766/controllers/PIDController.java +++ b/src/main/java/com/team766/controllers/PIDController.java @@ -10,20 +10,20 @@ import com.team766.logging.Severity; /** - * When attempting to move something with a control loop, a PID controller can + * When attempting to move something with a control loop, a PID controller can * smoothly decrease the error. This class is used for the elevator, driving during * autonmous, and angle correction with the gyro during the tele-operated period of the * match. - * + * * Because FRC's PID only supports a narrow range of things - you have to send * the output directly to a motor controller, etc. - * + * *

* Possibly later we may create a second class that allows for different PID * constants depending on which direction - this might be useful for things like * arms where behavior is different depending on direction. - * - * + * + * * @author Blevenson * */ @@ -50,7 +50,7 @@ public class PIDController { private double total_error = 0; private double output_value = 0; - + TimeProviderI timeProvider; private double lastTime; @@ -58,33 +58,26 @@ public static PIDController loadFromConfig(String configPrefix) { if (!configPrefix.endsWith(".")) { configPrefix += "."; } - return new PIDController( - ConfigFileReader.getInstance().getDouble(configPrefix + "pGain"), - ConfigFileReader.getInstance().getDouble(configPrefix + "iGain"), - ConfigFileReader.getInstance().getDouble(configPrefix + "dGain"), - ConfigFileReader.getInstance().getDouble(configPrefix + "ffGain"), - ConfigFileReader.getInstance().getDouble(configPrefix + "outputMaxLow"), - ConfigFileReader.getInstance().getDouble(configPrefix + "outputMaxHigh"), - ConfigFileReader.getInstance().getDouble(configPrefix + "threshold")); + return new PIDController(ConfigFileReader.getInstance().getDouble(configPrefix + "pGain"), + ConfigFileReader.getInstance().getDouble(configPrefix + "iGain"), + ConfigFileReader.getInstance().getDouble(configPrefix + "dGain"), + ConfigFileReader.getInstance().getDouble(configPrefix + "ffGain"), + ConfigFileReader.getInstance().getDouble(configPrefix + "outputMaxLow"), + ConfigFileReader.getInstance().getDouble(configPrefix + "outputMaxHigh"), + ConfigFileReader.getInstance().getDouble(configPrefix + "threshold")); } - + /** - * - * @param P - * P constant - * @param I - * I constant - * @param D - * D constant - * @param outputmax_low - * Largest output in the negative direction - * @param outputmax_high - * Largest output in the positive direction - * @param threshold - * threshold for declaring the PID 'done' + * + * @param P P constant + * @param I I constant + * @param D D constant + * @param outputmax_low Largest output in the negative direction + * @param outputmax_high Largest output in the positive direction + * @param threshold threshold for declaring the PID 'done' */ - public PIDController(double P, double I, double D, double outputmax_low, - double outputmax_high, double threshold) { + public PIDController(final double P, final double I, final double D, final double outputmax_low, + final double outputmax_high, final double threshold) { Kp = new SetValueProvider(P); Ki = new SetValueProvider(I); Kd = new SetValueProvider(D); @@ -95,25 +88,21 @@ public PIDController(double P, double I, double D, double outputmax_low, setTimeProvider(RobotProvider.getTimeProvider()); } - public PIDController(double P, double I, double D, double FF, double outputmax_low, - double outputmax_high, double threshold) { - this(P,I,D,outputmax_low,outputmax_high,threshold); - ((SetValueProvider)Kff).set(FF); + public PIDController(final double P, final double I, final double D, final double FF, + final double outputmax_low, final double outputmax_high, final double threshold) { + this(P, I, D, outputmax_low, outputmax_high, threshold); + ((SetValueProvider) Kff).set(FF); } - private void setTimeProvider(TimeProviderI timeProvider) { - this.timeProvider = timeProvider; + private void setTimeProvider(final TimeProviderI timeProvider_) { + this.timeProvider = timeProvider_; lastTime = timeProvider.get(); } - public PIDController( - ValueProvider P, - ValueProvider I, - ValueProvider D, - ValueProvider FF, - ValueProvider outputmax_low, - ValueProvider outputmax_high, - ValueProvider threshold) { + public PIDController(final ValueProvider P, final ValueProvider I, + final ValueProvider D, final ValueProvider FF, + final ValueProvider outputmax_low, final ValueProvider outputmax_high, + final ValueProvider threshold) { Kp = P; Ki = I; Kd = D; @@ -126,13 +115,15 @@ public PIDController( /** * Constructs a PID controller, with the specified P,I,D values, along with the end threshold. + * * @param P Proportional value used in the PID controller * @param I Integral value used in the PID controller * @param D Derivative value used in the PID controller * @param threshold the end threshold for declaring the PID 'done' * @param timeProvider */ - public PIDController(double P, double I, double D, double threshold, TimeProviderI timeProvider) { + public PIDController(final double P, final double I, final double D, final double threshold, + final TimeProviderI timeProvider_) { Kp = new SetValueProvider(P); Ki = new SetValueProvider(I); Kd = new SetValueProvider(D); @@ -140,10 +131,11 @@ public PIDController(double P, double I, double D, double threshold, TimeProvide maxoutput_low = new SetValueProvider(); maxoutput_high = new SetValueProvider(); endthreshold = new SetValueProvider(threshold); - setTimeProvider(timeProvider); + setTimeProvider(timeProvider_); } - public PIDController(double P, double I, double D, double FF, double threshold, TimeProviderI timeProvider) { + public PIDController(final double P, final double I, final double D, final double FF, + final double threshold, final TimeProviderI timeProvider_) { Kp = new SetValueProvider(P); Ki = new SetValueProvider(I); Kd = new SetValueProvider(D); @@ -151,17 +143,16 @@ public PIDController(double P, double I, double D, double FF, double threshold, maxoutput_low = new SetValueProvider(); maxoutput_high = new SetValueProvider(); endthreshold = new SetValueProvider(threshold); - setTimeProvider(timeProvider); + setTimeProvider(timeProvider_); } /** - * We may want to use same PID object, but with different setpoints, so this - * is separated from constructor - * - * @param set - * Target point to match + * We may want to use same PID object, but with different setpoints, so this is separated from + * constructor + * + * @param set Target point to match */ - public void setSetpoint(double set) { + public void setSetpoint(final double set) { setpoint = set; needsUpdate = true; } @@ -174,54 +165,55 @@ public void disable() { /** * If we want to set values, such as with SmartDash - * + * * @param P Proportional value used in the PID controller - * @param I Integral value used in the PID controller + * @param I Integral value used in the PID controller * @param D Derivative value used in the PID controller */ - public void setConstants(double P, double I, double D) { - ((SettableValueProvider)Kp).set(P); - ((SettableValueProvider)Ki).set(I); - ((SettableValueProvider)Kd).set(D); + public void setConstants(final double P, final double I, final double D) { + ((SettableValueProvider) Kp).set(P); + ((SettableValueProvider) Ki).set(I); + ((SettableValueProvider) Kd).set(D); needsUpdate = true; } - public void setP(double P) { - ((SettableValueProvider)Kp).set(P); + public void setP(final double P) { + ((SettableValueProvider) Kp).set(P); needsUpdate = true; } - public void setI(double I) { - ((SettableValueProvider)Ki).set(I); + public void setI(final double I) { + ((SettableValueProvider) Ki).set(I); needsUpdate = true; } - public void setD(double D) { - ((SettableValueProvider)Kd).set(D); + public void setD(final double D) { + ((SettableValueProvider) Kd).set(D); needsUpdate = true; } - public void setFF(double FF) { - ((SettableValueProvider)Kff).set(FF); + public void setFF(final double FF) { + ((SettableValueProvider) Kff).set(FF); needsUpdate = true; } - - /** Same as calculate() except that it prints debugging information - * + + /** + * Same as calculate() except that it prints debugging information + * * @param cur_input The current input to be plugged into the PID controller * @param smart True if you want the output to be dynamically adjusted to the motor controller */ - public void calculateDebug(double cur_input) { + public void calculateDebug(final double cur_input) { print = true; calculate(cur_input); } /** * Calculate PID value. Run only once per loop. Use getOutput to get output. - * + * * @param cur_input Input value from sensor */ - public void calculate(double cur_input) { + public void calculate(final double cur_input) { if (Double.isNaN(setpoint)) { // Setpoint has not been set yet. output_value = 0; @@ -230,13 +222,9 @@ public void calculate(double cur_input) { cur_error = (setpoint - cur_input); /* - if (isDone()) { - output_value = 0; - pr("pid done"); - return; - } - */ - + * if (isDone()) { output_value = 0; pr("pid done"); return; } + */ + double delta_time = timeProvider.get() - lastTime; if (delta_time > 0) { // This condition basically only false in the simulator @@ -252,23 +240,20 @@ public void calculate(double cur_input) { total_error = -1 / ki; } - double out = - Kp.valueOr(0.0) * cur_error + - Ki.valueOr(0.0) * total_error + - Kd.valueOr(0.0) * error_rate + - Kff.valueOr(0.0) * setpoint; + double out = Kp.valueOr(0.0) * cur_error + Ki.valueOr(0.0) * total_error + + Kd.valueOr(0.0) * error_rate + Kff.valueOr(0.0) * setpoint; prev_error = cur_error; pr("Pre-clip output: " + out); - + output_value = clip(out); - + needsUpdate = false; lastTime = timeProvider.get(); - - pr(" Total Error: " + total_error + " Current Error: " + cur_error + - " Output: " + output_value + " Setpoint: " + setpoint); + + pr(" Total Error: " + total_error + " Current Error: " + cur_error + + " Output: " + output_value + " Setpoint: " + setpoint); } public double getOutput() { @@ -277,9 +262,8 @@ public double getOutput() { public boolean isDone() { final double TIME_HORIZON = 0.5; - return !needsUpdate && - Math.abs(cur_error) < endthreshold.get() && - Math.abs(cur_error + error_rate * TIME_HORIZON) < endthreshold.get(); + return !needsUpdate && Math.abs(cur_error) < endthreshold.get() + && Math.abs(cur_error + error_rate * TIME_HORIZON) < endthreshold.get(); } /** @@ -294,13 +278,13 @@ public void reset() { } /** - * Clips value for sending to motor controllers. This deals with if you - * don't want to run an arm or wheels at full speed under PID. - * + * Clips value for sending to motor controllers. This deals with if you don't want to run an arm + * or wheels at full speed under PID. + * * @param clipped * @return clipped value, safe for setting to controllers */ - private double clip(double clipped) { + private double clip(final double clipped) { double out = clipped; if (maxoutput_high.hasValue() && out > maxoutput_high.get()) { out = maxoutput_high.get(); @@ -319,28 +303,28 @@ public double getCurrentError() { return cur_error; } - public void setMaxoutputHigh(Double in) { + public void setMaxoutputHigh(final Double in) { if (in == null) { - ((SettableValueProvider)maxoutput_high).clear(); + ((SettableValueProvider) maxoutput_high).clear(); } else { - ((SettableValueProvider)maxoutput_high).set(in); + ((SettableValueProvider) maxoutput_high).set(in); } } - public void setMaxoutputLow(Double in) { + public void setMaxoutputLow(final Double in) { if (in == null) { - ((SettableValueProvider)maxoutput_low).clear(); + ((SettableValueProvider) maxoutput_low).clear(); } else { - ((SettableValueProvider)maxoutput_low).set(in); + ((SettableValueProvider) maxoutput_low).set(in); } } - - public double getSetpoint(){ + + public double getSetpoint() { return setpoint; } - private void pr(Object text) { - if (print && printCounter > 0){ + private void pr(final Object text) { + if (print && printCounter > 0) { Logger.get(Category.PID_CONTROLLER).logRaw(Severity.DEBUG, "PID: " + text); printCounter = 0; } diff --git a/src/main/java/com/team766/controllers/RangeBound.java b/src/main/java/com/team766/controllers/RangeBound.java index ed732fa8..0aca1fcb 100644 --- a/src/main/java/com/team766/controllers/RangeBound.java +++ b/src/main/java/com/team766/controllers/RangeBound.java @@ -10,27 +10,26 @@ public class RangeBound { private ValueProvider m_min; private ValueProvider m_max; - + public static RangeBound loadFromConfig(String configPrefix) { if (!configPrefix.endsWith(".")) { configPrefix += "."; } - return new RangeBound( - ConfigFileReader.getInstance().getDouble(configPrefix + "min"), + return new RangeBound(ConfigFileReader.getInstance().getDouble(configPrefix + "min"), ConfigFileReader.getInstance().getDouble(configPrefix + "max")); } - - public RangeBound(double min, double max) { + + public RangeBound(final double min, final double max) { m_min = new SetValueProvider(min); m_max = new SetValueProvider(max); } - - public RangeBound(ValueProvider min, ValueProvider max) { + + public RangeBound(final ValueProvider min, final ValueProvider max) { m_min = min; m_max = max; } - - public double filter(double input) { + + public double filter(final double input) { return Math.min(Math.max(input, m_min.get()), m_max.get()); } } diff --git a/src/main/java/com/team766/controllers/RangeOfMotionMotorCommandBound.java b/src/main/java/com/team766/controllers/RangeOfMotionMotorCommandBound.java index 619133ca..be63356a 100644 --- a/src/main/java/com/team766/controllers/RangeOfMotionMotorCommandBound.java +++ b/src/main/java/com/team766/controllers/RangeOfMotionMotorCommandBound.java @@ -12,7 +12,7 @@ public class RangeOfMotionMotorCommandBound { private ValueProvider m_minPosition; private ValueProvider m_maxPosition; private ValueProvider m_sensorInverted; - + public static RangeOfMotionMotorCommandBound loadFromConfig(String configPrefix) { if (!configPrefix.endsWith(".")) { configPrefix += "."; @@ -22,23 +22,23 @@ public static RangeOfMotionMotorCommandBound loadFromConfig(String configPrefix) ConfigFileReader.getInstance().getDouble(configPrefix + "maxPosition"), ConfigFileReader.getInstance().getBoolean(configPrefix + "sensorInverted")); } - - public RangeOfMotionMotorCommandBound(double minPosition, double maxPosition, boolean sensorInverted) { + + public RangeOfMotionMotorCommandBound(final double minPosition, final double maxPosition, final boolean sensorInverted) { m_minPosition = new SetValueProvider(minPosition); m_maxPosition = new SetValueProvider(maxPosition); m_sensorInverted = new SetValueProvider(sensorInverted); } - + public RangeOfMotionMotorCommandBound( - ValueProvider minPosition, - ValueProvider maxPosition, - ValueProvider sensorInverted) { + final ValueProvider minPosition, + final ValueProvider maxPosition, + final ValueProvider sensorInverted) { m_minPosition = minPosition; m_maxPosition = maxPosition; m_sensorInverted = sensorInverted; } - - public double filter(double inputCommand, double sensorPosition) { + + public double filter(double inputCommand, final double sensorPosition) { double normalizedCommand = inputCommand; if (m_sensorInverted.get()) { normalizedCommand *= -1; diff --git a/src/main/java/com/team766/framework/AutonomousMode.java b/src/main/java/com/team766/framework/AutonomousMode.java index d29337be..c3201634 100644 --- a/src/main/java/com/team766/framework/AutonomousMode.java +++ b/src/main/java/com/team766/framework/AutonomousMode.java @@ -6,7 +6,7 @@ public class AutonomousMode { private final Supplier m_constructor; private final String m_name; - public AutonomousMode(String name, Supplier constructor) { + public AutonomousMode(final String name, final Supplier constructor) { m_constructor = constructor; m_name = name; } diff --git a/src/main/java/com/team766/framework/Context.java b/src/main/java/com/team766/framework/Context.java index 367134c3..5c9c07d8 100644 --- a/src/main/java/com/team766/framework/Context.java +++ b/src/main/java/com/team766/framework/Context.java @@ -13,7 +13,7 @@ /** * Context is the framework's representation of a single thread of execution. - * + * * We may want to have multiple procedures running at the same time on a robot. * For example, the robot could be raising an arm mechanism while also driving. * Each of those procedures would have a separate Context. Each of those @@ -22,7 +22,7 @@ * time. If a procedure wants to call multiple other procedures at the same * time, it has to create new Contexts for them (using the {@link #startAsync} * method). - * + * * Use the Context instance passed to your procedure whenever you want your * procedure to wait for something. For example, to have your procedure pause * for a certain amount of time, call context.waitForSeconds. Multiple Contexts @@ -33,7 +33,7 @@ * (this often happens if your procedure has a while loop), then it should * periodically call context.yield() (for example, at the start of each * iteration of the while loop) to still allow other Contexts to run. - * + * * This cooperative multitasking paradigm is used by the framework to ensure * that only one Context is actually running at a time, which allows us to avoid * needing to deal with concurrency issues like data race conditions. Even @@ -44,7 +44,7 @@ * model execution of the program as a sequence of imperative commands"), rather * than as state machines or in continuation-passing style, which can be much * more complicated to reason about, especially for new programmers. - * + * * Currently, threads of execution are implemented using OS threads, but this * should be considered an implementation detail and may change in the future. * Even though the framework creates multiple OS threads, it uses Java's @@ -61,14 +61,14 @@ public final class Context implements Runnable, LaunchedContext { * the number of OS context switches required), it makes the code simpler * and more modular. */ - private static enum ControlOwner { + private enum ControlOwner { MAIN_THREAD, SUBROUTINE, } /** * Indicates the lifetime state of this Context. */ - private static enum State { + private enum State { /** * The Context has been started (a Context is started immediately upon * construction). @@ -89,7 +89,7 @@ private static enum State { /** * Returns the currently-executing Context. - * + * * This is maintained for things like checking Mechanism ownership, but * intentionally only has package-private visibility - code outside of the * framework should ideally pass around references to the current context @@ -145,17 +145,18 @@ static Context currentContext() { * finishes executing. */ private Set m_ownedMechanisms = new HashSet(); - + /* * Constructors are intentionally private or package-private. New contexts * should be created with {@link Context#startAsync} or * {@link Scheduler#startAsync}. */ - private Context(RunnableWithContext func, Context parentContext) { + private Context(final RunnableWithContext func, final Context parentContext) { m_func = func; m_parentContext = parentContext; - Logger.get(Category.FRAMEWORK).logRaw(Severity.INFO, "Starting context " + getContextName() + " for " + func.toString()); + Logger.get(Category.FRAMEWORK).logRaw(Severity.INFO, + "Starting context " + getContextName() + " for " + func.toString()); m_threadSync = new Object(); m_previousWaitPoint = null; m_controlOwner = ControlOwner.MAIN_THREAD; @@ -164,20 +165,21 @@ private Context(RunnableWithContext func, Context parentContext) { m_thread.start(); Scheduler.getInstance().add(this); } - Context(RunnableWithContext func) { + + Context(final RunnableWithContext func) { this(func, null); } - private Context(Runnable func, Context parentContext) { + private Context(final Runnable func, final Context parentContext) { this((context) -> func.run()); } - Context(Runnable func) { + + Context(final Runnable func) { this(func, null); } - + /** - * Returns a string meant to uniquely identify this Context (e.g. for use in - * logging). + * Returns a string meant to uniquely identify this Context (e.g. for use in logging). */ public String getContextName() { return "Context/" + Integer.toHexString(hashCode()) + "/" + m_func.toString(); @@ -195,31 +197,26 @@ public String toString() { } /** - * Walks up the call stack until it reaches a frame that isn't from the - * Context class, then returns a string representation of that frame. This - * is used to generate a concise string representation of from where the - * user called into framework code. + * Walks up the call stack until it reaches a frame that isn't from the Context class, then + * returns a string representation of that frame. This is used to generate a concise string + * representation of from where the user called into framework code. */ private String getExecutionPoint() { StackWalker walker = StackWalker.getInstance(); return walker .walk(s -> s.dropWhile(f -> f.getClassName() != Context.this.getClass().getName()) .filter(f -> f.getClassName() != Context.this.getClass().getName()) - .findFirst() - .map(StackFrame::toString) - .orElse(null)); + .findFirst().map(StackFrame::toString).orElse(null)); } - + /** - * Wait until the baton (see the class comments) has been passed to this - * thread. - * - * @param thisOwner the thread from which this function is being called - * (and thus the baton-passing state that should be waited for) - * @throws ContextStoppedException if stop() is called on this Context while - * waiting. + * Wait until the baton (see the class comments) has been passed to this thread. + * + * @param thisOwner the thread from which this function is being called (and thus the + * baton-passing state that should be waited for) + * @throws ContextStoppedException if stop() is called on this Context while waiting. */ - private void waitForControl(ControlOwner thisOwner) { + private void waitForControl(final ControlOwner thisOwner) { // If this is being called from the worker thread, log from where in the // user's code that the context is waiting. This is provided as a // convenience so the user can track the progress of execution through @@ -227,7 +224,8 @@ private void waitForControl(ControlOwner thisOwner) { if (thisOwner == ControlOwner.SUBROUTINE) { String waitPointTrace = getExecutionPoint(); if (waitPointTrace != null && !waitPointTrace.equals(m_previousWaitPoint)) { - Logger.get(Category.FRAMEWORK).logRaw(Severity.DEBUG, getContextName() + " is waiting at " + waitPointTrace); + Logger.get(Category.FRAMEWORK).logRaw(Severity.DEBUG, + getContextName() + " is waiting at " + waitPointTrace); m_previousWaitPoint = waitPointTrace; } } @@ -245,23 +243,23 @@ private void waitForControl(ControlOwner thisOwner) { } } } - + /** - * Pass the baton (see the class comments) to the other thread and then wait - * for it to be passed back. - * - * @param thisOwner the thread from which this function is being called - * (and thus the baton-passing state that should be waited for) + * Pass the baton (see the class comments) to the other thread and then wait for it to be passed + * back. + * + * @param thisOwner the thread from which this function is being called (and thus the + * baton-passing state that should be waited for) * @param desiredOwner the thread to which the baton should be passed - * @throws ContextStoppedException if stop() is called on this Context while - * waiting. + * @throws ContextStoppedException if stop() is called on this Context while waiting. */ - private void transferControl(ControlOwner thisOwner, ControlOwner desiredOwner) { + private void transferControl(final ControlOwner thisOwner, final ControlOwner desiredOwner) { synchronized (m_threadSync) { // Make sure we currently have the baton before trying to give it to // someone else. if (m_controlOwner != thisOwner) { - throw new IllegalStateException("Subroutine had control owner " + m_controlOwner + " but assumed control owner " + thisOwner); + throw new IllegalStateException("Subroutine had control owner " + m_controlOwner + + " but assumed control owner " + thisOwner); } // Pass the baton. m_controlOwner = desiredOwner; @@ -275,7 +273,7 @@ private void transferControl(ControlOwner thisOwner, ControlOwner desiredOwner) waitForControl(thisOwner); } } - + /** * This is the entry point for this Context's worker thread. */ @@ -286,13 +284,16 @@ private void threadFunction() { try { // Call into the user's code. m_func.run(this); - Logger.get(Category.FRAMEWORK).logRaw(Severity.INFO, "Context " + getContextName() + " finished"); + Logger.get(Category.FRAMEWORK).logRaw(Severity.INFO, + "Context " + getContextName() + " finished"); } catch (ContextStoppedException ex) { - Logger.get(Category.FRAMEWORK).logRaw(Severity.WARNING, getContextName() + " was stopped"); + Logger.get(Category.FRAMEWORK).logRaw(Severity.WARNING, + getContextName() + " was stopped"); } catch (Exception ex) { ex.printStackTrace(); LoggerExceptionUtils.logException(ex); - Logger.get(Category.FRAMEWORK).logRaw(Severity.WARNING, "Context " + getContextName() + " died"); + Logger.get(Category.FRAMEWORK).logRaw(Severity.WARNING, + "Context " + getContextName() + " died"); } finally { for (Mechanism m : m_ownedMechanisms) { // Don't use this.releaseOwnership here, because that would cause a @@ -311,45 +312,43 @@ private void threadFunction() { m_ownedMechanisms.clear(); } } - + /** - * Pauses the execution of this Context until the given predicate returns - * true. Yields to other Contexts in the meantime. - * - * Note that the predicate will be evaluated repeatedly (possibly on a - * different thread) while the Context is paused to determine whether it - * should continue waiting. + * Pauses the execution of this Context until the given predicate returns true. Yields to other + * Contexts in the meantime. + * + * Note that the predicate will be evaluated repeatedly (possibly on a different thread) while + * the Context is paused to determine whether it should continue waiting. */ - public void waitFor(BooleanSupplier predicate) { + public void waitFor(final BooleanSupplier predicate) { if (!predicate.getAsBoolean()) { m_blockingPredicate = predicate; transferControl(ControlOwner.SUBROUTINE, ControlOwner.MAIN_THREAD); } } - + /** - * Pauses the execution of this Context until the given LaunchedContext has - * finished running. + * Pauses the execution of this Context until the given LaunchedContext has finished running. */ - public void waitFor(LaunchedContext otherContext) { + public void waitFor(final LaunchedContext otherContext) { waitFor(otherContext::isDone); } /** - * Pauses the execution of this Context until all of the given - * LaunchedContexts have finished running. + * Pauses the execution of this Context until all of the given LaunchedContexts have finished + * running. */ - public void waitFor(LaunchedContext... otherContexts) { + public void waitFor(final LaunchedContext... otherContexts) { waitFor(() -> Arrays.stream(otherContexts).allMatch(LaunchedContext::isDone)); } /** - * Momentarily pause execution of this Context to allow other Contexts to - * execute. Execution of this Context will resume as soon as possible after - * the other Contexts have been given a chance to run. - * - * Procedures should call this periodically if they wouldn't otherwise call - * one of the wait* methods for a while. + * Momentarily pause execution of this Context to allow other Contexts to execute. Execution of + * this Context will resume as soon as possible after the other Contexts have been given a + * chance to run. + * + * Procedures should call this periodically if they wouldn't otherwise call one of the wait* + * methods for a while. */ public void yield() { m_blockingPredicate = null; @@ -359,7 +358,7 @@ public void yield() { /** * Pauses the execution of this Context for the given length of time. */ - public void waitForSeconds(double seconds) { + public void waitForSeconds(final double seconds) { double startTime = RobotProvider.instance.getClock().getTime(); waitFor(() -> RobotProvider.instance.getClock().getTime() - startTime > seconds); } @@ -367,28 +366,28 @@ public void waitForSeconds(double seconds) { /** * Start running a new Context so the given procedure can run in parallel. */ - public LaunchedContext startAsync(RunnableWithContext func) { + public LaunchedContext startAsync(final RunnableWithContext func) { return new Context(func, this); } /** * Start running a new Context so the given procedure can run in parallel. */ - public LaunchedContext startAsync(Runnable func) { + public LaunchedContext startAsync(final Runnable func) { return new Context(func, this); } /** * Interrupt the running of this Context and force it to terminate. - * - * A ContextStoppedException will be raised on this Context at the point - * where the Context most recently waited or yielded -- if this Context is - * currently executing, a ContextStoppedException will be raised - * immediately. + * + * A ContextStoppedException will be raised on this Context at the point where the Context most + * recently waited or yielded -- if this Context is currently executing, a + * ContextStoppedException will be raised immediately. */ @Override public void stop() { - Logger.get(Category.FRAMEWORK).logRaw(Severity.INFO, "Stopping requested of " + getContextName()); + Logger.get(Category.FRAMEWORK).logRaw(Severity.INFO, + "Stopping requested of " + getContextName()); synchronized (m_threadSync) { if (m_state != State.DONE) { m_state = State.CANCELED; @@ -398,20 +397,21 @@ public void stop() { } } } - + /** * Entry point for the Scheduler to execute this Context. - * - * This should only be called from framework code; it is public only as an - * implementation detail. + * + * This should only be called from framework code; it is public only as an implementation + * detail. */ @Override - public final void run() { + public void run() { if (m_state == State.DONE) { Scheduler.getInstance().cancel(this); return; } - if (m_state == State.CANCELED || m_blockingPredicate == null || m_blockingPredicate.getAsBoolean()) { + if (m_state == State.CANCELED || m_blockingPredicate == null + || m_blockingPredicate.getAsBoolean()) { transferControl(ControlOwner.MAIN_THREAD, ControlOwner.SUBROUTINE); } } @@ -422,32 +422,31 @@ public final void run() { public boolean isDone() { return m_state == State.DONE; } - + /** * Take ownership of the given Mechanism with this Context. - * - * Only one Context can own a Mechanism at one time. If any Context - * previously owned this Mechanism, it will be terminated. - * Ownership of this Mechanism can be released by calling releaseOwnership, - * or it will be automatically released when this Context finishes running. - * + * + * Only one Context can own a Mechanism at one time. If any Context previously owned this + * Mechanism, it will be terminated. Ownership of this Mechanism can be released by calling + * releaseOwnership, or it will be automatically released when this Context finishes running. + * * @see Mechanism#takeOwnership(Context, Context) */ - public void takeOwnership(Mechanism mechanism) { + public void takeOwnership(final Mechanism mechanism) { mechanism.takeOwnership(this, m_parentContext); m_ownedMechanisms.add(mechanism); } /** * Release ownership of the given Mechanism. - * - * It is an error to call this method with a Mechanism that was not - * previously passed to takeOwnership. - * + * + * It is an error to call this method with a Mechanism that was not previously passed to + * takeOwnership. + * * @see #takeOwnership(Mechanism) * @see Mechanism#releaseOwnership(Context) */ - public void releaseOwnership(Mechanism mechanism) { + public void releaseOwnership(final Mechanism mechanism) { mechanism.releaseOwnership(this); m_ownedMechanisms.remove(mechanism); } diff --git a/src/main/java/com/team766/framework/LaunchedContext.java b/src/main/java/com/team766/framework/LaunchedContext.java index f04b0e3f..8ce9076c 100644 --- a/src/main/java/com/team766/framework/LaunchedContext.java +++ b/src/main/java/com/team766/framework/LaunchedContext.java @@ -5,15 +5,15 @@ public interface LaunchedContext { * Returns a string meant to uniquely identify this Context (e.g. for use in * logging). */ - public String getContextName(); + String getContextName(); /** * Returns true if this Context has finished running, false otherwise. */ - public boolean isDone(); + boolean isDone(); /** * Interrupt the running of this Context and force it to terminate. */ - public void stop(); + void stop(); } \ No newline at end of file diff --git a/src/main/java/com/team766/framework/LoggingBase.java b/src/main/java/com/team766/framework/LoggingBase.java index 4dc02335..0810968e 100644 --- a/src/main/java/com/team766/framework/LoggingBase.java +++ b/src/main/java/com/team766/framework/LoggingBase.java @@ -9,19 +9,19 @@ public abstract class LoggingBase { public abstract String getName(); - protected void log(String message) { + protected void log(final String message) { log(Severity.INFO, message); } - protected void log(Severity severity, String message) { + protected void log(final Severity severity, final String message) { Logger.get(loggerCategory).logRaw(severity, getName() + ": " + message); } - - protected void log(String format, Object... args) { + + protected void log(final String format, final Object... args) { log(Severity.INFO, format, args); } - protected void log(Severity severity, String format, Object... args) { + protected void log(final Severity severity, final String format, final Object... args) { Logger.get(loggerCategory).logData(severity, getName() + ": " + format, args); } } \ No newline at end of file diff --git a/src/main/java/com/team766/framework/Mechanism.java b/src/main/java/com/team766/framework/Mechanism.java index b6dbd6e9..7887fdac 100644 --- a/src/main/java/com/team766/framework/Mechanism.java +++ b/src/main/java/com/team766/framework/Mechanism.java @@ -8,7 +8,7 @@ public abstract class Mechanism extends LoggingBase { private Context m_owningContext = null; private Thread m_runningPeriodic = null; - + public Mechanism() { loggerCategory = Category.MECHANISMS; @@ -18,8 +18,7 @@ public void run() { try { Mechanism.this.m_runningPeriodic = Thread.currentThread(); Mechanism.this.run(); - } - finally { + } finally { Mechanism.this.m_runningPeriodic = null; } } @@ -38,7 +37,7 @@ public String toString() { public String getName() { return this.getClass().getName(); } - + protected void checkContextOwnership() { if (Context.currentContext() != m_owningContext && m_runningPeriodic == null) { String message = getName() + " tried to be used by " + Context.currentContext().getContextName(); @@ -51,19 +50,26 @@ protected void checkContextOwnership() { throw new IllegalStateException(message); } } - - void takeOwnership(Context context, Context parentContext) { + + void takeOwnership(final Context context, final Context parentContext) { if (m_owningContext != null && m_owningContext == parentContext) { - Logger.get(Category.FRAMEWORK).logRaw(Severity.INFO, context.getContextName() + " is inheriting ownership of " + getName() + " from " + parentContext.getContextName()); + Logger.get(Category.FRAMEWORK).logRaw(Severity.INFO, + context.getContextName() + " is inheriting ownership of " + getName() + " from " + + parentContext.getContextName()); } else { - Logger.get(Category.FRAMEWORK).logRaw(Severity.INFO, context.getContextName() + " is taking ownership of " + getName()); + Logger.get(Category.FRAMEWORK).logRaw(Severity.INFO, + context.getContextName() + " is taking ownership of " + getName()); while (m_owningContext != null && m_owningContext != context) { - Logger.get(Category.FRAMEWORK).logRaw(Severity.WARNING, "Stopping previous owner of " + getName() + ": " + m_owningContext.getContextName()); + Logger.get(Category.FRAMEWORK).logRaw(Severity.WARNING, + "Stopping previous owner of " + getName() + ": " + + m_owningContext.getContextName()); m_owningContext.stop(); var stoppedContext = m_owningContext; context.yield(); if (m_owningContext == stoppedContext) { - Logger.get(Category.FRAMEWORK).logRaw(Severity.ERROR, "Previous owner of " + getName() + ", " + m_owningContext.getContextName() + " did not release ownership when requested. Release will be forced."); + Logger.get(Category.FRAMEWORK).logRaw(Severity.ERROR, "Previous owner of " + + getName() + ", " + m_owningContext.getContextName() + + " did not release ownership when requested. Release will be forced."); m_owningContext.releaseOwnership(this); break; } @@ -72,7 +78,7 @@ void takeOwnership(Context context, Context parentContext) { m_owningContext = context; } - void releaseOwnership(Context context) { + void releaseOwnership(final Context context) { if (m_owningContext != context) { LoggerExceptionUtils.logException(new Exception(context.getContextName() + " tried to release ownership of " + getName() + " but it doesn't own it")); return; @@ -81,5 +87,6 @@ void releaseOwnership(Context context) { m_owningContext = null; } - public void run () {} + public void run() { + } } diff --git a/src/main/java/com/team766/framework/Procedure.java b/src/main/java/com/team766/framework/Procedure.java index c63564a5..aae0cedc 100644 --- a/src/main/java/com/team766/framework/Procedure.java +++ b/src/main/java/com/team766/framework/Procedure.java @@ -4,7 +4,7 @@ public abstract class Procedure extends LoggingBase implements RunnableWithConte // A reusable Procedure that does nothing. private static final class NoOpProcedure extends Procedure { @Override - public void run(Context context) { + public void run(final Context context) { } } public static final Procedure NO_OP = new NoOpProcedure(); @@ -14,7 +14,7 @@ public void run(Context context) { private static synchronized int createNewId() { return c_idCounter++; } - + protected final int m_id; public Procedure() { diff --git a/src/main/java/com/team766/framework/RunnableWithContext.java b/src/main/java/com/team766/framework/RunnableWithContext.java index 6aeb1ec8..d46b8abd 100644 --- a/src/main/java/com/team766/framework/RunnableWithContext.java +++ b/src/main/java/com/team766/framework/RunnableWithContext.java @@ -2,5 +2,5 @@ @FunctionalInterface public interface RunnableWithContext { - public abstract void run(Context context); + void run(Context context); } \ No newline at end of file diff --git a/src/main/java/com/team766/framework/Scheduler.java b/src/main/java/com/team766/framework/Scheduler.java index 760b0cd3..0f364ccd 100644 --- a/src/main/java/com/team766/framework/Scheduler.java +++ b/src/main/java/com/team766/framework/Scheduler.java @@ -17,7 +17,7 @@ public class Scheduler implements Runnable { c_monitor.setDaemon(true); c_monitor.start(); } - + public static Scheduler getInstance() { return c_instance; } @@ -31,7 +31,7 @@ private static void monitor() { } catch (InterruptedException e) { } - if (c_instance.m_running != null && + if (c_instance.m_running != null && c_instance.m_iterationCount == lastIterationCount && c_instance.m_running == lastRunning) { Logger.get(Category.FRAMEWORK).logRaw( @@ -54,28 +54,28 @@ private static void monitor() { lastRunning = c_instance.m_running; } } - + private LinkedList m_runnables = new LinkedList(); private int m_iterationCount = 0; private Runnable m_running = null; - - public void add(Runnable runnable) { + + public void add(final Runnable runnable) { m_runnables.add(runnable); } - - public void cancel(Runnable runnable) { + + public void cancel(final Runnable runnable) { m_runnables.remove(runnable); } - + public void reset() { m_runnables.clear(); } - - public LaunchedContext startAsync(RunnableWithContext func) { + + public LaunchedContext startAsync(final RunnableWithContext func) { return new Context(func); } - public LaunchedContext startAsync(Runnable func) { + public LaunchedContext startAsync(final Runnable func) { return new Context(func); } diff --git a/src/main/java/com/team766/framework/StackTraceUtils.java b/src/main/java/com/team766/framework/StackTraceUtils.java index f325221c..b4ef185e 100644 --- a/src/main/java/com/team766/framework/StackTraceUtils.java +++ b/src/main/java/com/team766/framework/StackTraceUtils.java @@ -1,7 +1,7 @@ package com.team766.framework; class StackTraceUtils { - public static String getStackTrace(Thread thread) { + public static String getStackTrace(final Thread thread) { StackTraceElement[] stackTrace; try { stackTrace = thread.getStackTrace(); @@ -12,7 +12,7 @@ public static String getStackTrace(Thread thread) { return getStackTrace(stackTrace); } - public static String getStackTrace(StackTraceElement[] stackTrace) { + public static String getStackTrace(final StackTraceElement[] stackTrace) { String repr = ""; for (var stackFrame : stackTrace) { repr += " at " + stackFrame.getClassName() + "." + stackFrame.getMethodName(); diff --git a/src/main/java/com/team766/framework/WPILibCommandProcedure.java b/src/main/java/com/team766/framework/WPILibCommandProcedure.java index 720db197..0cd5c014 100644 --- a/src/main/java/com/team766/framework/WPILibCommandProcedure.java +++ b/src/main/java/com/team766/framework/WPILibCommandProcedure.java @@ -16,13 +16,13 @@ public class WPILibCommandProcedure extends Procedure { * @param requirements This Procedure will take ownership of the Mechanisms * given here during the time it is executing. */ - public WPILibCommandProcedure(Command command, Mechanism... requirements) { - this.command = command; - this.requirements = requirements; + public WPILibCommandProcedure(final Command command_, final Mechanism... requirements_) { + this.command = command_; + this.requirements = requirements_; } @Override - public void run(Context context) { + public void run(final Context context) { for (Mechanism req : this.requirements) { context.takeOwnership(req); } diff --git a/src/main/java/com/team766/hal/AnalogInputReader.java b/src/main/java/com/team766/hal/AnalogInputReader.java index e41750a4..00c333ab 100755 --- a/src/main/java/com/team766/hal/AnalogInputReader.java +++ b/src/main/java/com/team766/hal/AnalogInputReader.java @@ -7,17 +7,17 @@ public interface AnalogInputReader extends ControlInputReader { * * @return A scaled sample straight from this channel. */ - public double getVoltage(); + double getVoltage(); // Implementation for ControlInputReader interface @Override - public default double getPosition() { + default double getPosition() { return getVoltage(); } // Implementation for ControlInputReader interface @Override - public default double getRate() { + default double getRate() { throw new UnsupportedOperationException("Analog input sensor does not have support for velocity"); } } diff --git a/src/main/java/com/team766/hal/BeaconReader.java b/src/main/java/com/team766/hal/BeaconReader.java index d696a588..5d552989 100644 --- a/src/main/java/com/team766/hal/BeaconReader.java +++ b/src/main/java/com/team766/hal/BeaconReader.java @@ -1,7 +1,7 @@ package com.team766.hal; public interface BeaconReader { - public static class BeaconPose { + class BeaconPose { public double x; public double y; public double z; @@ -10,5 +10,5 @@ public static class BeaconPose { public double roll; } - public abstract BeaconPose[] getBeacons(); + BeaconPose[] getBeacons(); } diff --git a/src/main/java/com/team766/hal/CameraInterface.java b/src/main/java/com/team766/hal/CameraInterface.java index ac7d698c..167d2bb2 100755 --- a/src/main/java/com/team766/hal/CameraInterface.java +++ b/src/main/java/com/team766/hal/CameraInterface.java @@ -2,8 +2,10 @@ import org.opencv.core.Mat; -public interface CameraInterface { - public void startAutomaticCapture(); - public void getFrame(Mat img); - public void putFrame(Mat img); +public interface CameraInterface { + void startAutomaticCapture(); + + void getFrame(Mat img); + + void putFrame(Mat img); } diff --git a/src/main/java/com/team766/hal/CameraReader.java b/src/main/java/com/team766/hal/CameraReader.java index 5d8a3ace..5ecbadab 100755 --- a/src/main/java/com/team766/hal/CameraReader.java +++ b/src/main/java/com/team766/hal/CameraReader.java @@ -3,5 +3,5 @@ import org.opencv.core.Mat; public interface CameraReader { - public Mat getImage(); + Mat getImage(); } diff --git a/src/main/java/com/team766/hal/Clock.java b/src/main/java/com/team766/hal/Clock.java index 19541c18..3154f230 100644 --- a/src/main/java/com/team766/hal/Clock.java +++ b/src/main/java/com/team766/hal/Clock.java @@ -1,5 +1,5 @@ package com.team766.hal; public interface Clock { - public double getTime(); + double getTime(); } diff --git a/src/main/java/com/team766/hal/ControlInputReader.java b/src/main/java/com/team766/hal/ControlInputReader.java index a360209f..ae4105db 100644 --- a/src/main/java/com/team766/hal/ControlInputReader.java +++ b/src/main/java/com/team766/hal/ControlInputReader.java @@ -4,10 +4,10 @@ public interface ControlInputReader { /** * Get the current position of the mechanism read by the sensor. */ - public double getPosition(); + double getPosition(); /** * Get the current rate of change of the position. */ - public double getRate(); + double getRate(); } diff --git a/src/main/java/com/team766/hal/DigitalInputReader.java b/src/main/java/com/team766/hal/DigitalInputReader.java index 8dfe9c3a..ae51a69b 100755 --- a/src/main/java/com/team766/hal/DigitalInputReader.java +++ b/src/main/java/com/team766/hal/DigitalInputReader.java @@ -7,5 +7,5 @@ public interface DigitalInputReader { * * @return the status of the digital input */ - public boolean get(); + boolean get(); } diff --git a/src/main/java/com/team766/hal/DoubleSolenoid.java b/src/main/java/com/team766/hal/DoubleSolenoid.java index 6bed6c38..dbe7ae1f 100755 --- a/src/main/java/com/team766/hal/DoubleSolenoid.java +++ b/src/main/java/com/team766/hal/DoubleSolenoid.java @@ -1,29 +1,29 @@ package com.team766.hal; public class DoubleSolenoid implements SolenoidController { - + private SolenoidController forward; private SolenoidController back; private boolean boolState; - + public enum State { Forward, Neutral, Backward } - - public DoubleSolenoid(SolenoidController forward, SolenoidController back) { - this.forward = forward; - this.back = back; + + public DoubleSolenoid(final SolenoidController forward_, final SolenoidController back_) { + this.forward = forward_; + this.back = back_; set(State.Neutral); } - + @Override public boolean get() { return boolState; } - - public void set(State state) { - switch(state) { + + public void set(final State state) { + switch (state) { case Forward: boolState = true; if (forward != null) { @@ -51,11 +51,13 @@ public void set(State state) { back.set(false); } break; + default: + break; } } - + @Override - public void set(boolean on) { + public void set(final boolean on) { set(on ? State.Forward : State.Backward); } diff --git a/src/main/java/com/team766/hal/EncoderReader.java b/src/main/java/com/team766/hal/EncoderReader.java index 03daed87..e67dc30a 100755 --- a/src/main/java/com/team766/hal/EncoderReader.java +++ b/src/main/java/com/team766/hal/EncoderReader.java @@ -9,65 +9,59 @@ public interface EncoderReader extends ControlInputReader { * @return Current count from the Encoder adjusted for the 1x, 2x, or 4x * scale factor. */ - public int get(); + int get(); /** - * Reset the Encoder distance to zero. Resets the current count to zero on - * the encoder. + * Reset the Encoder distance to zero. Resets the current count to zero on the encoder. */ - public void reset(); + void reset(); /** - * Determine if the encoder is stopped. Using the MaxPeriod value, a boolean - * is returned that is true if the encoder is considered stopped and false - * if it is still moving. A stopped encoder is one where the most recent - * pulse width exceeds the MaxPeriod. + * Determine if the encoder is stopped. Using the MaxPeriod value, a boolean is returned that is + * true if the encoder is considered stopped and false if it is still moving. A stopped encoder + * is one where the most recent pulse width exceeds the MaxPeriod. * * @return True if the encoder is considered stopped. */ - public boolean getStopped(); + boolean getStopped(); /** * The last direction the encoder value changed. * * @return The last direction the encoder value changed. */ - public boolean getDirection(); + boolean getDirection(); /** * Get the distance the robot has driven since the last reset. * - * @return The distance driven since the last reset as scaled by the value - * from setDistancePerPulse(). + * @return The distance driven since the last reset as scaled by the value from + * setDistancePerPulse(). */ - public double getDistance(); + double getDistance(); /** - * Get the current rate of the encoder. Units are distance per second as - * scaled by the value from setDistancePerPulse(). + * Get the current rate of the encoder. Units are distance per second as scaled by the value + * from setDistancePerPulse(). * * @return The current rate of the encoder. */ - public double getRate(); + double getRate(); /** - * Set the distance per pulse for this encoder. This sets the multiplier - * used to determine the distance driven based on the count value from the - * encoder. Do not include the decoding type in this scale. The library - * already compensates for the decoding type. Set this value based on the - * encoder's rated Pulses per Revolution and factor in gearing reductions - * following the encoder shaft. This distance can be in any units you like, - * linear or angular. + * Set the distance per pulse for this encoder. This sets the multiplier used to determine the + * distance driven based on the count value from the encoder. Do not include the decoding type + * in this scale. The library already compensates for the decoding type. Set this value based on + * the encoder's rated Pulses per Revolution and factor in gearing reductions following the + * encoder shaft. This distance can be in any units you like, linear or angular. * - * @param distancePerPulse - * The scale factor that will be used to convert pulses to useful - * units. + * @param distancePerPulse The scale factor that will be used to convert pulses to useful units. */ - public void setDistancePerPulse(double distancePerPulse); + void setDistancePerPulse(double distancePerPulse); // Implementation for ControlInputReader interface @Override - public default double getPosition() { + default double getPosition() { return getDistance(); } } diff --git a/src/main/java/com/team766/hal/GenericRobotMain.java b/src/main/java/com/team766/hal/GenericRobotMain.java index 599f9ff3..0d489968 100755 --- a/src/main/java/com/team766/hal/GenericRobotMain.java +++ b/src/main/java/com/team766/hal/GenericRobotMain.java @@ -4,7 +4,7 @@ import com.team766.framework.AutonomousMode; import com.team766.framework.LaunchedContext; import com.team766.framework.Procedure; -import com.team766.hal.GenericRobotMain; +// import com.team766.hal.GenericRobotMain; import com.team766.logging.Category; import com.team766.logging.Logger; import com.team766.logging.Severity; @@ -23,7 +23,7 @@ public final class GenericRobotMain { private OI m_oi; - + private WebServer m_webServer; private AutonomousSelector m_autonSelector; private AutonomousMode m_autonMode = null; @@ -49,10 +49,10 @@ public GenericRobotMain() { public void robotInit() { Robot.robotInit(); - + m_oi = new OI(); } - + public void disabledInit() { m_disabledModeStartTime = RobotProvider.instance.getClock().getTime(); } @@ -82,7 +82,7 @@ public void disabledPeriodic() { } } - public void resetAutonomousMode(String reason) { + public void resetAutonomousMode(final String reason) { if (m_autonomous != null) { m_autonomous.stop(); m_autonomous = null; @@ -91,7 +91,7 @@ public void resetAutonomousMode(String reason) { Severity.INFO, "Resetting autonomus procedure from " + reason); } } - + public void autonomousInit() { if (m_oiContext != null) { m_oiContext.stop(); @@ -102,7 +102,7 @@ public void autonomousInit() { Logger.get(Category.AUTONOMOUS).logRaw(Severity.INFO, "Continuing previous autonomus procedure " + m_autonomous.getContextName()); } else if (m_autonSelector.getSelectedAutonMode() == null) { Logger.get(Category.AUTONOMOUS).logRaw(Severity.WARNING, "No autonomous mode selected"); - } + } } public void autonomousPeriodic() { @@ -114,14 +114,14 @@ public void autonomousPeriodic() { Logger.get(Category.AUTONOMOUS).logRaw(Severity.INFO, "Starting new autonomus procedure " + autonProcedure.getName()); } } - + public void teleopInit() { if (m_autonomous != null) { m_autonomous.stop(); m_autonomous = null; m_autonMode = null; } - + if (m_oiContext == null) { m_oiContext = Scheduler.getInstance().startAsync(m_oi); } diff --git a/src/main/java/com/team766/hal/GyroReader.java b/src/main/java/com/team766/hal/GyroReader.java index 0eae1632..5aa0ef22 100755 --- a/src/main/java/com/team766/hal/GyroReader.java +++ b/src/main/java/com/team766/hal/GyroReader.java @@ -9,28 +9,26 @@ public interface GyroReader { * done when the robot is first turned on while it's sitting at rest before * the competition starts. */ - public void calibrate(); + void calibrate(); /** - * Reset the gyro. Resets the gyro to a heading of zero. This can be used if - * there is significant drift in the gyro and it needs to be recalibrated - * after it has been running. + * Reset the gyro. Resets the gyro to a heading of zero. This can be used if there is + * significant drift in the gyro and it needs to be recalibrated after it has been running. */ - public void reset(); + void reset(); /** * Return the actual angle in degrees that the robot is currently facing. * - * The angle is based on the current accumulator value corrected by the - * oversampling rate, the gyro type and the A/D calibration values. The angle - * is continuous, that is it will continue from 360 to 361 degrees. This - * allows algorithms that wouldn't want to see a discontinuity in the gyro - * output as it sweeps past from 360 to 0 on the second time around. + * The angle is based on the current accumulator value corrected by the oversampling rate, the + * gyro type and the A/D calibration values. The angle is continuous, that is it will continue + * from 360 to 361 degrees. This allows algorithms that wouldn't want to see a discontinuity in + * the gyro output as it sweeps past from 360 to 0 on the second time around. * - * @return the current heading of the robot in degrees. This heading is based - * on integration of the returned rate from the gyro. + * @return the current heading of the robot in degrees. This heading is based on integration of + * the returned rate from the gyro. */ - public double getAngle(); + double getAngle(); /** * Return the rate of rotation of the gyro @@ -39,23 +37,23 @@ public interface GyroReader { * * @return the current rate in degrees per second */ - public double getRate(); + double getRate(); /** - * Returns the current pitch value (in degrees, from -180 to 180) reported by the sensor. - * This is the angle that the robot is tilted forward or backward. - * Should return 0 degrees if the robot is sitting flat on the floor. + * Returns the current pitch value (in degrees, from -180 to 180) reported by the sensor. This + * is the angle that the robot is tilted forward or backward. Should return 0 degrees if the + * robot is sitting flat on the floor. * * @return pitch angle (in degrees, -180 to 180) */ - public double getPitch(); + double getPitch(); /** - * Returns the current roll value (in degrees, from -180 to 180) reported by the sensor. - * This is the angle that the robot is tilted left or right. - * Should return 0 degrees if the robot is sitting flat on the floor. + * Returns the current roll value (in degrees, from -180 to 180) reported by the sensor. This is + * the angle that the robot is tilted left or right. Should return 0 degrees if the robot is + * sitting flat on the floor. * * @return roll angle (in degrees, -180 to 180) */ - public double getRoll(); + double getRoll(); } diff --git a/src/main/java/com/team766/hal/JoystickReader.java b/src/main/java/com/team766/hal/JoystickReader.java index ffb40e62..4ba65105 100755 --- a/src/main/java/com/team766/hal/JoystickReader.java +++ b/src/main/java/com/team766/hal/JoystickReader.java @@ -7,40 +7,38 @@ public interface JoystickReader { * @param axis The axis to read, starting at 0. * @return The value of the axis. */ - public double getAxis(int axis); - + double getAxis(int axis); + /** - * Get the button value (starting at button 1) - * - * The appropriate button is returned as a boolean value. - * - * @param button The button number to be read (starting at 1). - * @return The state of the button. - */ - public boolean getButton(int button); + * Get the button value (starting at button 1) + * + * The appropriate button is returned as a boolean value. + * + * @param button The button number to be read (starting at 1). + * @return The state of the button. + */ + boolean getButton(int button); /** - * Whether the button was pressed since the last check. Button indexes begin at - * 1. + * Whether the button was pressed since the last check. Button indexes begin at 1. * * @param button The button index, beginning at 1. * @return Whether the button was pressed since the last check. */ - public boolean getButtonPressed(int button); + boolean getButtonPressed(int button); /** - * Whether the button was released since the last check. Button indexes begin at - * 1. + * Whether the button was released since the last check. Button indexes begin at 1. * * @param button The button index, beginning at 1. * @return Whether the button was released since the last check. */ - public boolean getButtonReleased(int button); - + boolean getButtonReleased(int button); + /** - * Get the value of the POV - * - * @return the value of the POV - */ - public int getPOV(); + * Get the value of the POV + * + * @return the value of the POV + */ + int getPOV(); } diff --git a/src/main/java/com/team766/hal/LocalMotorController.java b/src/main/java/com/team766/hal/LocalMotorController.java index 41f3f170..04122862 100644 --- a/src/main/java/com/team766/hal/LocalMotorController.java +++ b/src/main/java/com/team766/hal/LocalMotorController.java @@ -22,9 +22,10 @@ public class LocalMotorController implements MotorController { private double setpoint = 0.0; private MotorController leader = null; - public LocalMotorController(String configPrefix, BasicMotorController motor, ControlInputReader sensor){ - this.motor = motor; - this.sensor = sensor; + public LocalMotorController(String configPrefix, final BasicMotorController motor_, + final ControlInputReader sensor_) { + this.motor = motor_; + this.sensor = sensor_; if (!configPrefix.endsWith(".")) { configPrefix += "."; @@ -36,13 +37,15 @@ public LocalMotorController(String configPrefix, BasicMotorController motor, Con public void run() { switch (LocalMotorController.this.controlMode) { case Current: - LoggerExceptionUtils.logException(new UnsupportedOperationException(toString() + " does not support Current control mode")); + LoggerExceptionUtils.logException(new UnsupportedOperationException( + toString() + " does not support Current control mode")); stopMotor(); break; case Disabled: // support proper output disabling if this.motor is a MotorController if (LocalMotorController.this.motor instanceof MotorController) { - ((MotorController)LocalMotorController.this.motor).set(ControlMode.Disabled, 0); + ((MotorController) LocalMotorController.this.motor) + .set(ControlMode.Disabled, 0); } else { setPower(0); } @@ -51,15 +54,18 @@ public void run() { setPower(leader.get()); break; case MotionMagic: - LoggerExceptionUtils.logException(new UnsupportedOperationException(toString() + " does not support MotionMagic control mode")); + LoggerExceptionUtils.logException(new UnsupportedOperationException( + toString() + " does not support MotionMagic control mode")); stopMotor(); break; case MotionProfile: - LoggerExceptionUtils.logException(new UnsupportedOperationException(toString() + " does not support MotionProfile control mode")); + LoggerExceptionUtils.logException(new UnsupportedOperationException( + toString() + " does not support MotionProfile control mode")); stopMotor(); break; case MotionProfileArc: - LoggerExceptionUtils.logException(new UnsupportedOperationException(toString() + " does not support MotionProfileArc control mode")); + LoggerExceptionUtils.logException(new UnsupportedOperationException( + toString() + " does not support MotionProfileArc control mode")); stopMotor(); break; case PercentOutput: @@ -76,6 +82,11 @@ public void run() { case Voltage: setPower(setpoint / RobotProvider.instance.getBatteryVoltage()); break; + default: + LoggerExceptionUtils.logException( + new UnsupportedOperationException(toString() + " does not support control mode " + LocalMotorController.this.controlMode) + ); + break; } } @@ -97,7 +108,7 @@ private void setPower(double power) { } this.motor.set(power); } - + @Override public double get() { double value = motor.get(); @@ -106,14 +117,14 @@ public double get() { } return value; } - + @Override - public void set(double power) { + public void set(final double power) { set(ControlMode.PercentOutput, power); } @Override - public void setInverted(boolean isInverted) { + public void setInverted(final boolean isInverted) { this.inverted = isInverted; } @@ -130,7 +141,8 @@ public void stopMotor() { @Override public void setSensorPosition(double position) { if (this.sensor == null) { - Logger.get(Category.CONFIGURATION).logRaw(Severity.ERROR, toString() + " does not have an attached sensor configured"); + Logger.get(Category.CONFIGURATION).logRaw(Severity.ERROR, + toString() + " does not have an attached sensor configured"); return; } if (this.sensorInverted != this.inverted) { @@ -138,11 +150,12 @@ public void setSensorPosition(double position) { } sensorOffset = position - sensor.getPosition(); } - + @Override public double getSensorPosition() { if (this.sensor == null) { - Logger.get(Category.CONFIGURATION).logRaw(Severity.ERROR, toString() + " does not have an attached sensor configured"); + Logger.get(Category.CONFIGURATION).logRaw(Severity.ERROR, + toString() + " does not have an attached sensor configured"); return 0.0; } double position = sensor.getPosition() + sensorOffset; @@ -155,7 +168,8 @@ public double getSensorPosition() { @Override public double getSensorVelocity() { if (this.sensor == null) { - Logger.get(Category.CONFIGURATION).logRaw(Severity.ERROR, toString() + " does not have an attached sensor configured"); + Logger.get(Category.CONFIGURATION).logRaw(Severity.ERROR, + toString() + " does not have an attached sensor configured"); return 0.0; } double velocity = sensor.getRate(); @@ -166,9 +180,10 @@ public double getSensorVelocity() { } @Override - public void set(ControlMode mode, double value) { + public void set(final ControlMode mode, final double value) { if (mode == ControlMode.Follower) { - throw new IllegalArgumentException("Use follow() method instead of passing Follower to set()"); + throw new IllegalArgumentException( + "Use follow() method instead of passing Follower to set()"); } if (this.controlMode != mode) { pidController.reset(); @@ -177,69 +192,72 @@ public void set(ControlMode mode, double value) { this.setpoint = value; this.pidController.setSetpoint(setpoint); } - + public ControlMode getControlMode() { return this.controlMode; } @Override - public void follow(MotorController leader) { - if (leader == null) { + public void follow(final MotorController leader_) { + if (leader_ == null) { throw new IllegalArgumentException("leader argument to follow() is null"); } // TODO: detect if this.motor is a MotorController, and delegate to its follow() method if so. this.controlMode = ControlMode.Follower; - this.leader = leader; + this.leader = leader_; } - + @Override - public void setNeutralMode(NeutralMode neutralMode) { + public void setNeutralMode(final NeutralMode neutralMode) { if (this.motor instanceof MotorController) { - ((MotorController)this.motor).setNeutralMode(neutralMode); + ((MotorController) this.motor).setNeutralMode(neutralMode); } else { - LoggerExceptionUtils.logException(new UnsupportedOperationException(this.toString() + " - setNeutralMode() is only supported with CAN motor controllers")); + LoggerExceptionUtils.logException(new UnsupportedOperationException(this.toString() + + " - setNeutralMode() is only supported with CAN motor controllers")); } } @Override - public void setP(double value) { + public void setP(final double value) { pidController.setP(value); } @Override - public void setI(double value) { + public void setI(final double value) { pidController.setI(value); } @Override - public void setD(double value) { + public void setD(final double value) { pidController.setD(value); } @Override - public void setFF(double value) { + public void setFF(final double value) { pidController.setFF(value); } @Override - public void setSelectedFeedbackSensor(FeedbackDevice feedbackDevice) { - LoggerExceptionUtils.logException(new UnsupportedOperationException("setSelectedFeedbsckSensor() is currently unsupported by LocalMotorController")); + public void setSelectedFeedbackSensor(final FeedbackDevice feedbackDevice) { + LoggerExceptionUtils.logException(new UnsupportedOperationException( + "setSelectedFeedbsckSensor() is currently unsupported by LocalMotorController")); } @Override - public void setSensorInverted(boolean inverted) { - this.sensorInverted = inverted; + public void setSensorInverted(final boolean inverted_) { + this.sensorInverted = inverted_; } @Override - public void setOutputRange(double minOutput, double maxOutput) { + public void setOutputRange(final double minOutput, final double maxOutput) { pidController.setMaxoutputLow(minOutput); pidController.setMaxoutputHigh(maxOutput); } @Override - public void setCurrentLimit(double ampsLimit) { - LoggerExceptionUtils.logException(new UnsupportedOperationException("setCurrentLimit() is currently unsupported by LocalMotorController")); + public void setCurrentLimit(final double ampsLimit) { + LoggerExceptionUtils.logException(new UnsupportedOperationException( + "setCurrentLimit() is currently unsupported by LocalMotorController")); } @Override @@ -260,12 +278,13 @@ public void restoreFactoryDefault() { } @Override - public void setOpenLoopRamp(double secondsFromNeutralToFull) { - LoggerExceptionUtils.logException(new UnsupportedOperationException("setOpenLoopRamp() is currently unsupported by LocalMotorController")); + public void setOpenLoopRamp(final double secondsFromNeutralToFull) { + LoggerExceptionUtils.logException(new UnsupportedOperationException( + "setOpenLoopRamp() is currently unsupported by LocalMotorController")); } @Override - public void setClosedLoopRamp(double secondsFromNeutralToFull) { + public void setClosedLoopRamp(final double secondsFromNeutralToFull) { LoggerExceptionUtils.logException(new UnsupportedOperationException("setClosedLoopRamp() is currently unsupported by LocalMotorController")); } } \ No newline at end of file diff --git a/src/main/java/com/team766/hal/MotorController.java b/src/main/java/com/team766/hal/MotorController.java index 80635f30..91374dfe 100755 --- a/src/main/java/com/team766/hal/MotorController.java +++ b/src/main/java/com/team766/hal/MotorController.java @@ -9,7 +9,7 @@ public interface MotorController extends BasicMotorController { - public enum Type { + enum Type { VictorSP, VictorSPX, TalonSRX, @@ -17,7 +17,7 @@ public enum Type { TalonFX, } - public enum ControlMode { + enum ControlMode { PercentOutput, Position, Velocity, @@ -97,7 +97,7 @@ public enum ControlMode { /** * Sets the motors encoder value to the given position. - * + * * @param position The desired set position */ void setSensorPosition(double position); diff --git a/src/main/java/com/team766/hal/MotorControllerCommandFailedException.java b/src/main/java/com/team766/hal/MotorControllerCommandFailedException.java index 76efb847..8afc8a22 100644 --- a/src/main/java/com/team766/hal/MotorControllerCommandFailedException.java +++ b/src/main/java/com/team766/hal/MotorControllerCommandFailedException.java @@ -2,12 +2,12 @@ public class MotorControllerCommandFailedException extends RuntimeException { - public MotorControllerCommandFailedException(String message) { + public MotorControllerCommandFailedException(final String message) { super(message); } - public MotorControllerCommandFailedException(String message, Throwable cause) { + public MotorControllerCommandFailedException(final String message, final Throwable cause) { super(message, cause); } - + } diff --git a/src/main/java/com/team766/hal/MotorControllerWithSensorScale.java b/src/main/java/com/team766/hal/MotorControllerWithSensorScale.java index 14ec2ee3..498947c7 100644 --- a/src/main/java/com/team766/hal/MotorControllerWithSensorScale.java +++ b/src/main/java/com/team766/hal/MotorControllerWithSensorScale.java @@ -7,9 +7,9 @@ public class MotorControllerWithSensorScale implements MotorController { private MotorController delegate; private double scale; - public MotorControllerWithSensorScale(MotorController delegate, double scale) { - this.delegate = delegate; - this.scale = scale; + public MotorControllerWithSensorScale(final MotorController delegate_, final double scale_) { + this.delegate = delegate_; + this.scale = scale_; } @Override @@ -23,46 +23,50 @@ public double getSensorVelocity() { } @Override - public void set(ControlMode mode, double value) { + public void set(final ControlMode mode, final double value) { switch (mode) { - case PercentOutput: - delegate.set(mode, value); - return; - case Position: - delegate.set(mode, value / scale); - return; - case Velocity: - delegate.set(mode, value / scale); - return; - case Current: - delegate.set(mode, value); - return; - case Voltage: - delegate.set(mode, value); - case Follower: - delegate.set(mode, value); - return; - case MotionProfile: - // TODO: What is value here? This assumes its a target position. - delegate.set(mode, value / scale); - return; - case MotionMagic: - // TODO: What is value here? This assumes its a target position. - delegate.set(mode, value / scale); - return; - case MotionProfileArc: - // TODO: What is value here? This assumes its a target position. - delegate.set(mode, value / scale); - return; - case Disabled: - delegate.set(mode, value); - return; + case PercentOutput: + delegate.set(mode, value); + return; + case Position: + delegate.set(mode, value / scale); + return; + case Velocity: + delegate.set(mode, value / scale); + return; + case Current: + delegate.set(mode, value); + return; + case Voltage: + delegate.set(mode, value); + return; + case Follower: + delegate.set(mode, value); + return; + case MotionProfile: + // TODO: What is value here? This assumes its a target position. + delegate.set(mode, value / scale); + return; + case MotionMagic: + // TODO: What is value here? This assumes its a target position. + delegate.set(mode, value / scale); + return; + case MotionProfileArc: + // TODO: What is value here? This assumes its a target position. + delegate.set(mode, value / scale); + return; + case Disabled: + delegate.set(mode, value); + return; + default: + break; } - throw new UnsupportedOperationException("Unimplemented control mode in MotorControllerWithSensorScale"); + throw new UnsupportedOperationException( + "Unimplemented control mode in MotorControllerWithSensorScale"); } @Override - public void setInverted(boolean isInverted) { + public void setInverted(final boolean isInverted) { delegate.setInverted(isInverted); } @@ -77,57 +81,57 @@ public void stopMotor() { } @Override - public void setSensorPosition(double position) { + public void setSensorPosition(final double position) { delegate.setSensorPosition(position / scale); } @Override - public void follow(MotorController leader) { + public void follow(final MotorController leader) { delegate.follow(leader); } @Override - public void setNeutralMode(NeutralMode neutralMode) { + public void setNeutralMode(final NeutralMode neutralMode) { delegate.setNeutralMode(neutralMode); } @Override - public void setP(double value) { + public void setP(final double value) { delegate.setP(value * scale); } @Override - public void setI(double value) { + public void setI(final double value) { delegate.setI(value * scale); } @Override - public void setD(double value) { + public void setD(final double value) { delegate.setD(value * scale); } @Override - public void setFF(double value) { + public void setFF(final double value) { delegate.setFF(value * scale); } @Override - public void setSelectedFeedbackSensor(FeedbackDevice feedbackDevice) { + public void setSelectedFeedbackSensor(final FeedbackDevice feedbackDevice) { delegate.setSelectedFeedbackSensor(feedbackDevice); } @Override - public void setSensorInverted(boolean inverted) { + public void setSensorInverted(final boolean inverted) { delegate.setSensorInverted(inverted); } @Override - public void setOutputRange(double minOutput, double maxOutput) { + public void setOutputRange(final double minOutput, final double maxOutput) { delegate.setOutputRange(minOutput, maxOutput); } - + @Override - public void setCurrentLimit(double ampsLimit) { + public void setCurrentLimit(final double ampsLimit) { delegate.setCurrentLimit(ampsLimit); } @@ -137,12 +141,12 @@ public void restoreFactoryDefault() { } @Override - public void setOpenLoopRamp(double secondsFromNeutralToFull) { + public void setOpenLoopRamp(final double secondsFromNeutralToFull) { delegate.setOpenLoopRamp(secondsFromNeutralToFull); } @Override - public void setClosedLoopRamp(double secondsFromNeutralToFull) { + public void setClosedLoopRamp(final double secondsFromNeutralToFull) { delegate.setClosedLoopRamp(secondsFromNeutralToFull); } @@ -152,7 +156,7 @@ public double get() { } @Override - public void set(double power) { + public void set(final double power) { delegate.set(power); } } diff --git a/src/main/java/com/team766/hal/MultiSolenoid.java b/src/main/java/com/team766/hal/MultiSolenoid.java index 39a47aea..4b812993 100644 --- a/src/main/java/com/team766/hal/MultiSolenoid.java +++ b/src/main/java/com/team766/hal/MultiSolenoid.java @@ -1,23 +1,23 @@ package com.team766.hal; public class MultiSolenoid implements SolenoidController { - + private SolenoidController[] solenoids; private boolean state; - - public MultiSolenoid(SolenoidController... solenoids) { - this.solenoids = solenoids; + + public MultiSolenoid(final SolenoidController... solenoids_) { + this.solenoids = solenoids_; set(false); } - + @Override public boolean get() { return state; } - + @Override - public void set(boolean on) { + public void set(final boolean on) { state = on; for (SolenoidController s : solenoids) { s.set(on); diff --git a/src/main/java/com/team766/hal/PositionReader.java b/src/main/java/com/team766/hal/PositionReader.java index 452c4579..6367e2f8 100644 --- a/src/main/java/com/team766/hal/PositionReader.java +++ b/src/main/java/com/team766/hal/PositionReader.java @@ -6,19 +6,19 @@ public interface PositionReader { * * @return the current position coordinate in meters */ - public double getX(); + double getX(); /** * Return the position of the robot along the global Y axis. * * @return the current position coordinate in meters */ - public double getY(); + double getY(); /** * Return the angle that the robot is currently facing. * * @return the current heading angle in degrees */ - public double getHeading(); + double getHeading(); } \ No newline at end of file diff --git a/src/main/java/com/team766/hal/RelayOutput.java b/src/main/java/com/team766/hal/RelayOutput.java index e6e7bd96..c7abcf98 100755 --- a/src/main/java/com/team766/hal/RelayOutput.java +++ b/src/main/java/com/team766/hal/RelayOutput.java @@ -6,11 +6,11 @@ */ public interface RelayOutput { - - public void set(Value val); - - enum Value{ + + void set(Value val); + + enum Value { kOff, kOn, kForward, kReverse } - + } diff --git a/src/main/java/com/team766/hal/RobotProvider.java b/src/main/java/com/team766/hal/RobotProvider.java index 10a81c29..d6b4477b 100755 --- a/src/main/java/com/team766/hal/RobotProvider.java +++ b/src/main/java/com/team766/hal/RobotProvider.java @@ -17,9 +17,9 @@ import com.team766.logging.Severity; public abstract class RobotProvider { - + public static RobotProvider instance; - + protected EncoderReader[] encoders = new EncoderReader[20]; protected SolenoidController[] solenoids = new SolenoidController[10]; protected GyroReader[] gyros = new GyroReader[13]; @@ -41,58 +41,69 @@ public abstract class RobotProvider { //HAL protected abstract MotorController getMotor(int index, String configPrefix, MotorController.Type type, ControlInputReader localSensor); - + public abstract EncoderReader getEncoder(int index1, int index2); - + public abstract DigitalInputReader getDigitalInput(int index); - + public abstract AnalogInputReader getAnalogInput(int index); - + public abstract RelayOutput getRelay(int index); - + public abstract SolenoidController getSolenoid(int index); - + public abstract GyroReader getGyro(int index); - + public abstract CameraReader getCamera(String id, String value); public abstract PositionReader getPositionSensor(); public abstract BeaconReader getBeaconSensor(); - public static TimeProviderI getTimeProvider(){ + public static TimeProviderI getTimeProvider() { return () -> instance.getClock().getTime(); } - + // Config-driven methods - private void checkDeviceName(String deviceType, HashMap deviceNames, Integer portId, String configName) { + private void checkDeviceName(final String deviceType, + final HashMap deviceNames, final Integer portId, + final String configName) { String previousName = deviceNames.putIfAbsent(portId, configName); if (previousName != null && previousName != configName) { - Logger.get(Category.CONFIGURATION).logRaw( - Severity.ERROR, - "Multiple " + deviceType + " devices for port ID " + portId + ": " + previousName + ", " + configName); + Logger.get(Category.CONFIGURATION).logRaw(Severity.ERROR, "Multiple " + deviceType + + " devices for port ID " + portId + ": " + previousName + ", " + configName); } } - public MotorController getMotor(String configName) { + public MotorController getMotor(final String configName) { final String encoderConfigName = configName + ".encoder"; final String analogInputConfigName = configName + ".analogInput"; final ControlInputReader sensor = - ConfigFileReader.getInstance().containsKey(encoderConfigName) ? getEncoder(encoderConfigName) : - ConfigFileReader.getInstance().containsKey(analogInputConfigName) ? getAnalogInput(analogInputConfigName) : - null; + ConfigFileReader.getInstance().containsKey(encoderConfigName) + ? getEncoder(encoderConfigName) + : ConfigFileReader.getInstance().containsKey(analogInputConfigName) + ? getAnalogInput(analogInputConfigName) + : null; try { - ValueProvider deviceId = ConfigFileReader.getInstance().getInt(configName + ".deviceId"); - final ValueProvider port = ConfigFileReader.getInstance().getInt(configName + ".port"); - final ValueProvider sensorScaleConfig = ConfigFileReader.getInstance().getDouble(configName + ".sensorScale"); - final ValueProvider invertedConfig = ConfigFileReader.getInstance().getBoolean(configName + ".inverted"); - final ValueProvider sensorInvertedConfig = ConfigFileReader.getInstance().getBoolean(configName + ".sensorInverted"); - final ValueProvider type = ConfigFileReader.getInstance().getEnum(MotorController.Type.class, configName + ".type"); + ValueProvider deviceId = + ConfigFileReader.getInstance().getInt(configName + ".deviceId"); + final ValueProvider port = + ConfigFileReader.getInstance().getInt(configName + ".port"); + final ValueProvider sensorScaleConfig = + ConfigFileReader.getInstance().getDouble(configName + ".sensorScale"); + final ValueProvider invertedConfig = + ConfigFileReader.getInstance().getBoolean(configName + ".inverted"); + final ValueProvider sensorInvertedConfig = + ConfigFileReader.getInstance().getBoolean(configName + ".sensorInverted"); + final ValueProvider type = ConfigFileReader.getInstance() + .getEnum(MotorController.Type.class, configName + ".type"); if (deviceId.hasValue() && port.hasValue()) { - Logger.get(Category.CONFIGURATION).logData(Severity.ERROR, "Motor %s configuration should have only one of `deviceId` or `port`", configName); + Logger.get(Category.CONFIGURATION).logData(Severity.ERROR, + "Motor %s configuration should have only one of `deviceId` or `port`", + configName); } MotorController.Type defaultType = MotorController.Type.TalonSRX; @@ -101,7 +112,8 @@ public MotorController getMotor(String configName) { defaultType = MotorController.Type.VictorSP; checkDeviceName("PWM motor controller", motorPortNames, port.get(), configName); } else { - checkDeviceName("CAN motor controller", motorDeviceIdNames, deviceId.get(), configName); + checkDeviceName("CAN motor controller", motorDeviceIdNames, deviceId.get(), + configName); } var motor = getMotor(deviceId.get(), configName, type.valueOr(defaultType), sensor); @@ -116,19 +128,24 @@ public MotorController getMotor(String configName) { } return motor; } catch (IllegalArgumentException ex) { - Logger.get(Category.CONFIGURATION).logData(Severity.ERROR, "Motor %s not found in config file, using mock motor instead", configName); + Logger.get(Category.CONFIGURATION).logData(Severity.ERROR, + "Motor %s not found in config file, using mock motor instead", configName); return new LocalMotorController(configName, new MockMotorController(0), sensor); } } - public EncoderReader getEncoder(String configName) { + public EncoderReader getEncoder(final String configName) { try { - final ValueProvider ports = ConfigFileReader.getInstance().getInts(configName + ".ports"); - final ValueProvider distancePerPulseConfig = ConfigFileReader.getInstance().getDouble(configName + ".distancePerPulse"); + final ValueProvider ports = + ConfigFileReader.getInstance().getInts(configName + ".ports"); + final ValueProvider distancePerPulseConfig = + ConfigFileReader.getInstance().getDouble(configName + ".distancePerPulse"); final var portsValue = ports.get(); if (portsValue.length != 2) { - Logger.get(Category.CONFIGURATION).logData(Severity.ERROR, "Encoder %s has %d config values, but expected 2", configName, portsValue.length); + Logger.get(Category.CONFIGURATION).logData(Severity.ERROR, + "Encoder %s has %d config values, but expected 2", configName, + portsValue.length); return new MockEncoder(0, 0); } checkDeviceName("encoder/digital input", digitalIoNames, portsValue[0], configName); @@ -139,56 +156,65 @@ public EncoderReader getEncoder(String configName) { } return reader; } catch (IllegalArgumentException ex) { - Logger.get(Category.CONFIGURATION).logData(Severity.ERROR, "Encoder %s not found in config file, using mock encoder instead", configName); + Logger.get(Category.CONFIGURATION).logData(Severity.ERROR, + "Encoder %s not found in config file, using mock encoder instead", configName); return new MockEncoder(0, 0); } } - public DigitalInputReader getDigitalInput(String configName) { + public DigitalInputReader getDigitalInput(final String configName) { try { - ValueProvider port = ConfigFileReader.getInstance().getInt(configName + ".port"); + ValueProvider port = + ConfigFileReader.getInstance().getInt(configName + ".port"); checkDeviceName("encoder/digital input", digitalIoNames, port.get(), configName); return getDigitalInput(port.get()); } catch (IllegalArgumentException ex) { - Logger.get(Category.CONFIGURATION).logData(Severity.ERROR, "Digital input %s not found in config file, using mock digital input instead", configName); + Logger.get(Category.CONFIGURATION).logData(Severity.ERROR, + "Digital input %s not found in config file, using mock digital input instead", + configName); return new MockDigitalInput(); } } - public AnalogInputReader getAnalogInput(String configName) { + public AnalogInputReader getAnalogInput(final String configName) { try { - ValueProvider port = ConfigFileReader.getInstance().getInt(configName + ".port"); + ValueProvider port = + ConfigFileReader.getInstance().getInt(configName + ".port"); checkDeviceName("analog input", analogInputNames, port.get(), configName); return getAnalogInput(port.get()); } catch (IllegalArgumentException ex) { - Logger.get(Category.CONFIGURATION).logData(Severity.ERROR, "Analog input %s not found in config file, using mock analog input instead", configName); + Logger.get(Category.CONFIGURATION).logData(Severity.ERROR, + "Analog input %s not found in config file, using mock analog input instead", + configName); return new MockAnalogInput(); } } - public RelayOutput getRelay(String configName) { + public RelayOutput getRelay(final String configName) { try { - ValueProvider port = ConfigFileReader.getInstance().getInt(configName + ".port"); + ValueProvider port = + ConfigFileReader.getInstance().getInt(configName + ".port"); checkDeviceName("relay", relayNames, port.get(), configName); return getRelay(port.get()); } catch (IllegalArgumentException ex) { - Logger.get(Category.CONFIGURATION).logData(Severity.ERROR, "Relay %s not found in config file, using mock relay instead", configName); + Logger.get(Category.CONFIGURATION).logData(Severity.ERROR, + "Relay %s not found in config file, using mock relay instead", configName); return new MockRelay(0); } } - public DoubleSolenoid getSolenoid(String configName) { + public DoubleSolenoid getSolenoid(final String configName) { try { final String legacyConfigKey = configName + ".port"; ValueProvider forwardPorts = - ConfigFileReader.getInstance().containsKey(legacyConfigKey) - ? ConfigFileReader.getInstance().getInts(legacyConfigKey) - : ConfigFileReader.getInstance().getInts(configName + ".forwardPort"); + ConfigFileReader.getInstance().containsKey(legacyConfigKey) + ? ConfigFileReader.getInstance().getInts(legacyConfigKey) + : ConfigFileReader.getInstance().getInts(configName + ".forwardPort"); ValueProvider reversePorts = - ConfigFileReader.getInstance().getInts(configName + ".reversePort"); + ConfigFileReader.getInstance().getInts(configName + ".reversePort"); for (Integer port : forwardPorts.valueOr(new Integer[0])) { checkDeviceName("solenoid", solenoidNames, port, configName); @@ -197,22 +223,22 @@ public DoubleSolenoid getSolenoid(String configName) { checkDeviceName("solenoid", solenoidNames, port, configName); } - SolenoidController forwardSolenoids = new MultiSolenoid( - Arrays.stream(forwardPorts.valueOr(new Integer[0])) - .map(this::getSolenoid) - .toArray(SolenoidController[]::new)); - SolenoidController reverseSolenoids = new MultiSolenoid( - Arrays.stream(reversePorts.valueOr(new Integer[0])) - .map(this::getSolenoid) - .toArray(SolenoidController[]::new)); + SolenoidController forwardSolenoids = new MultiSolenoid(Arrays + .stream(forwardPorts.valueOr(new Integer[0])) + .map(this::getSolenoid).toArray(SolenoidController[]::new)); + SolenoidController reverseSolenoids = new MultiSolenoid(Arrays + .stream(reversePorts.valueOr(new Integer[0])) + .map(this::getSolenoid).toArray(SolenoidController[]::new)); return new DoubleSolenoid(forwardSolenoids, reverseSolenoids); } catch (IllegalArgumentException ex) { - Logger.get(Category.CONFIGURATION).logData(Severity.ERROR, "Solenoid %s not found in config file, using mock solenoid instead", configName); + Logger.get(Category.CONFIGURATION).logData(Severity.ERROR, + "Solenoid %s not found in config file, using mock solenoid instead", + configName); return new DoubleSolenoid(null, null); } } - public GyroReader getGyro(String configName) { + public GyroReader getGyro(final String configName) { try { ValueProvider port = ConfigFileReader.getInstance().getInt(configName + ".port"); checkDeviceName("gyro", gyroNames, port.get(), configName); @@ -226,9 +252,9 @@ public GyroReader getGyro(String configName) { //Operator Devices public abstract JoystickReader getJoystick(int index); - + public abstract CameraInterface getCamServer(); - + public abstract Clock getClock(); public abstract double getBatteryVoltage(); diff --git a/src/main/java/com/team766/hal/SolenoidController.java b/src/main/java/com/team766/hal/SolenoidController.java index 8a6605c5..4164d162 100755 --- a/src/main/java/com/team766/hal/SolenoidController.java +++ b/src/main/java/com/team766/hal/SolenoidController.java @@ -8,12 +8,12 @@ public interface SolenoidController { * @param on * Turn the solenoid output off or on. */ - public void set(boolean on); + void set(boolean on); /** * Read the current value of the solenoid. * * @return The current value of the solenoid. */ - public boolean get(); + boolean get(); } diff --git a/src/main/java/com/team766/hal/VidSourceInterface.java b/src/main/java/com/team766/hal/VidSourceInterface.java index 22b9eef6..1ed59a9e 100755 --- a/src/main/java/com/team766/hal/VidSourceInterface.java +++ b/src/main/java/com/team766/hal/VidSourceInterface.java @@ -1,5 +1,5 @@ package com.team766.hal; public interface VidSourceInterface { - public String getName(); + String getName(); } diff --git a/src/main/java/com/team766/hal/mock/MockAnalogInput.java b/src/main/java/com/team766/hal/mock/MockAnalogInput.java index fdeeccd4..3f870ad6 100755 --- a/src/main/java/com/team766/hal/mock/MockAnalogInput.java +++ b/src/main/java/com/team766/hal/mock/MockAnalogInput.java @@ -3,10 +3,10 @@ import com.team766.hal.AnalogInputReader; public class MockAnalogInput implements AnalogInputReader { - + private double sensor = 0.0; - - public void set(double value){ + + public void set(final double value) { sensor = value; } diff --git a/src/main/java/com/team766/hal/mock/MockCamera.java b/src/main/java/com/team766/hal/mock/MockCamera.java index 125fbc3b..b47a7379 100755 --- a/src/main/java/com/team766/hal/mock/MockCamera.java +++ b/src/main/java/com/team766/hal/mock/MockCamera.java @@ -5,21 +5,21 @@ import com.team766.hal.CameraReader; -public class MockCamera implements CameraReader{ +public class MockCamera implements CameraReader { private String nextImage; - + @Override public Mat getImage() { - if(nextImage == null) { + if (nextImage == null) { return null; } - + return Imgcodecs.imread(nextImage); } - - public void setNextImage(String nextImage){ - this.nextImage = this.getClass().getClassLoader().getResource(nextImage).getPath(); + + public void setNextImage(final String nextImage_) { + this.nextImage = this.getClass().getClassLoader().getResource(nextImage_).getPath(); } } diff --git a/src/main/java/com/team766/hal/mock/MockDigitalInput.java b/src/main/java/com/team766/hal/mock/MockDigitalInput.java index e8cfe1f4..6e8de1c3 100755 --- a/src/main/java/com/team766/hal/mock/MockDigitalInput.java +++ b/src/main/java/com/team766/hal/mock/MockDigitalInput.java @@ -2,15 +2,15 @@ import com.team766.hal.DigitalInputReader; -public class MockDigitalInput implements DigitalInputReader{ - +public class MockDigitalInput implements DigitalInputReader { + private boolean sensor = false; public boolean get() { return sensor; } - - public void set(boolean on){ + + public void set(final boolean on) { sensor = on; } diff --git a/src/main/java/com/team766/hal/mock/MockEncoder.java b/src/main/java/com/team766/hal/mock/MockEncoder.java index 6eccab0d..c6fc1775 100755 --- a/src/main/java/com/team766/hal/mock/MockEncoder.java +++ b/src/main/java/com/team766/hal/mock/MockEncoder.java @@ -2,18 +2,18 @@ import com.team766.hal.EncoderReader; -public class MockEncoder implements EncoderReader{ - +public class MockEncoder implements EncoderReader { + private double distance = 0; private double rate = 0; private double distancePerPulse = 1; - - public MockEncoder(int a, int b){ + + public MockEncoder(final int a, final int b) { } - + @Override public int get() { - return (int)Math.round(distance / distancePerPulse); + return (int) Math.round(distance / distancePerPulse); } @Override @@ -41,17 +41,17 @@ public double getRate() { return this.rate; } - public void setDistance(double distance) { - this.distance = distance; + public void setDistance(final double distance_) { + this.distance = distance_; } - - public void setRate(double rate){ - this.rate = rate; + + public void setRate(final double rate_) { + this.rate = rate_; } @Override - public void setDistancePerPulse(double distancePerPulse) { - this.distancePerPulse = distancePerPulse; + public void setDistancePerPulse(final double distancePerPulse_) { + this.distancePerPulse = distancePerPulse_; } } diff --git a/src/main/java/com/team766/hal/mock/MockGyro.java b/src/main/java/com/team766/hal/mock/MockGyro.java index 32b8db2d..91215f23 100755 --- a/src/main/java/com/team766/hal/mock/MockGyro.java +++ b/src/main/java/com/team766/hal/mock/MockGyro.java @@ -2,13 +2,13 @@ import com.team766.hal.GyroReader; -public class MockGyro implements GyroReader{ +public class MockGyro implements GyroReader { private double angle = 0; private double rate = 0; private double pitch = 0; private double roll = 0; - + public void calibrate() { reset(); } @@ -33,20 +33,20 @@ public double getRoll() { return roll; } - public void setAngle(double angle) { - this.angle = angle; + public void setAngle(final double angle_) { + this.angle = angle_; } - public void setRate(double rate) { - this.rate = rate; + public void setRate(final double rate_) { + this.rate = rate_; } - - public void setPitch(double pitch) { - this.pitch = pitch; + + public void setPitch(final double pitch_) { + this.pitch = pitch_; } - - public void setRoll(double roll) { - this.roll = roll; + + public void setRoll(final double roll_) { + this.roll = roll_; } } diff --git a/src/main/java/com/team766/hal/mock/MockJoystick.java b/src/main/java/com/team766/hal/mock/MockJoystick.java index 89c2fe70..28ee408b 100755 --- a/src/main/java/com/team766/hal/mock/MockJoystick.java +++ b/src/main/java/com/team766/hal/mock/MockJoystick.java @@ -3,37 +3,37 @@ import com.team766.hal.JoystickReader; public class MockJoystick implements JoystickReader { - + private double[] axisValues; private boolean[] buttonValues; private boolean[] prevButtonValues; private int povValue; - - public MockJoystick(){ + + public MockJoystick() { axisValues = new double[12]; buttonValues = new boolean[20]; prevButtonValues = new boolean[20]; } - + @Override - public double getAxis(int axis) { + public double getAxis(final int axis) { return axisValues[axis]; } @Override - public boolean getButton(int button) { + public boolean getButton(final int button) { // Button indexes begin at 1 in WPILib, so match that here if (button <= 0) { return false; } return buttonValues[button - 1]; } - - public void setAxisValue(int axis, double value){ + + public void setAxisValue(final int axis, final double value) { axisValues[axis] = value; } - - public void setButton(int button, boolean val){ + + public void setButton(final int button, final boolean val) { // Button indexes begin at 1 in WPILib, so match that here prevButtonValues[button - 1] = buttonValues[button - 1]; buttonValues[button - 1] = val; @@ -43,13 +43,13 @@ public void setButton(int button, boolean val){ public int getPOV() { return povValue; } - - public void setPOV(int value) { + + public void setPOV(final int value) { povValue = value; } @Override - public boolean getButtonPressed(int button) { + public boolean getButtonPressed(final int button) { // Button indexes begin at 1 in WPILib, so match that here if (button <= 0) { return false; @@ -58,7 +58,7 @@ public boolean getButtonPressed(int button) { } @Override - public boolean getButtonReleased(int button) { + public boolean getButtonReleased(final int button) { // Button indexes begin at 1 in WPILib, so match that here if (button <= 0) { return false; diff --git a/src/main/java/com/team766/hal/mock/MockMotorController.java b/src/main/java/com/team766/hal/mock/MockMotorController.java index d3115af9..57c7f24c 100755 --- a/src/main/java/com/team766/hal/mock/MockMotorController.java +++ b/src/main/java/com/team766/hal/mock/MockMotorController.java @@ -5,18 +5,18 @@ public class MockMotorController implements BasicMotorController { private double output; - - public MockMotorController(int index) { + + public MockMotorController(final int index) { output = 0; } - + @Override public double get() { return output; } - + @Override - public void set(double power) { + public void set(final double power) { output = power; } diff --git a/src/main/java/com/team766/hal/mock/MockPositionSensor.java b/src/main/java/com/team766/hal/mock/MockPositionSensor.java index 0501e345..aebb4000 100644 --- a/src/main/java/com/team766/hal/mock/MockPositionSensor.java +++ b/src/main/java/com/team766/hal/mock/MockPositionSensor.java @@ -23,16 +23,16 @@ public double getHeading() { return heading; } - public void setX(double x) { - this.x = x; + public void setX(final double x_) { + this.x = x_; } - public void setY(double y) { - this.y = y; + public void setY(final double y_) { + this.y = y_; } - public void setHeading(double heading) { - this.heading = heading; + public void setHeading(final double heading_) { + this.heading = heading_; } } \ No newline at end of file diff --git a/src/main/java/com/team766/hal/mock/MockRelay.java b/src/main/java/com/team766/hal/mock/MockRelay.java index ab07476e..e1ce91a8 100755 --- a/src/main/java/com/team766/hal/mock/MockRelay.java +++ b/src/main/java/com/team766/hal/mock/MockRelay.java @@ -2,21 +2,21 @@ import com.team766.hal.RelayOutput; -public class MockRelay implements RelayOutput{ +public class MockRelay implements RelayOutput { private Value val; - - public MockRelay(int port){ + + public MockRelay(final int port) { val = Value.kOff; } - + @Override - public void set(Value out) { + public void set(final Value out) { val = out; } - - public Value get(){ + + public Value get() { return val; } - + } diff --git a/src/main/java/com/team766/hal/mock/MockSolenoid.java b/src/main/java/com/team766/hal/mock/MockSolenoid.java index 7018330c..8d2aaed5 100755 --- a/src/main/java/com/team766/hal/mock/MockSolenoid.java +++ b/src/main/java/com/team766/hal/mock/MockSolenoid.java @@ -2,15 +2,15 @@ import com.team766.hal.SolenoidController; -public class MockSolenoid implements SolenoidController{ +public class MockSolenoid implements SolenoidController { private boolean pist; - - public MockSolenoid(int port){ + + public MockSolenoid(final int port) { pist = false; } - - public void set(boolean on) { + + public void set(final boolean on) { pist = on; } diff --git a/src/main/java/com/team766/hal/mock/TestRobotProvider.java b/src/main/java/com/team766/hal/mock/TestRobotProvider.java index dd4e7319..dbeb5401 100755 --- a/src/main/java/com/team766/hal/mock/TestRobotProvider.java +++ b/src/main/java/com/team766/hal/mock/TestRobotProvider.java @@ -2,7 +2,6 @@ import com.team766.hal.AnalogInputReader; import com.team766.hal.BeaconReader; -import com.team766.hal.BeaconReader; import com.team766.hal.CameraInterface; import com.team766.hal.CameraReader; import com.team766.hal.Clock; @@ -19,66 +18,65 @@ import com.team766.hal.MotorController; import com.team766.hal.wpilib.SystemClock; -public class TestRobotProvider extends RobotProvider{ +public class TestRobotProvider extends RobotProvider { private MotorController[] motors = new MotorController[64]; private boolean m_hasDriverStationUpdate = false; private double m_batteryVoltage = 12.0; @Override - public MotorController getMotor(int index, String configPrefix, MotorController.Type type, ControlInputReader localSensor) { - if(motors[index] == null) { - motors[index] = new LocalMotorController( - configPrefix, - new MockMotorController(index), - localSensor != null ? localSensor : new MockEncoder(-1, -1)); + public MotorController getMotor(final int index, final String configPrefix, + final MotorController.Type type, final ControlInputReader localSensor) { + if (motors[index] == null) { + motors[index] = new LocalMotorController(configPrefix, new MockMotorController(index), + localSensor != null ? localSensor : new MockEncoder(-1, -1)); } return motors[index]; } @Override - public EncoderReader getEncoder(int index1, int index2) { - if(encoders[index1] == null) { + public EncoderReader getEncoder(final int index1, final int index2) { + if (encoders[index1] == null) { encoders[index1] = new MockEncoder(index1, index2); } return encoders[index1]; } @Override - public SolenoidController getSolenoid(int index) { - if(solenoids[index] == null) { + public SolenoidController getSolenoid(final int index) { + if (solenoids[index] == null) { solenoids[index] = new MockSolenoid(index); } return solenoids[index]; } @Override - public GyroReader getGyro(int index) { - if(gyros[0] == null) { + public GyroReader getGyro(final int index) { + if (gyros[0] == null) { gyros[0] = new MockGyro(); } return gyros[0]; } @Override - public CameraReader getCamera(String id, String value) { - if(!cams.containsKey(id)) { + public CameraReader getCamera(final String id, final String value) { + if (!cams.containsKey(id)) { cams.put(id, new MockCamera()); } return cams.get(id); } @Override - public JoystickReader getJoystick(int index) { - if(joysticks[index] == null) { + public JoystickReader getJoystick(final int index) { + if (joysticks[index] == null) { joysticks[index] = new MockJoystick(); } return joysticks[index]; } - + @Override - public DigitalInputReader getDigitalInput(int index) { - if(digInputs[index] == null) { + public DigitalInputReader getDigitalInput(final int index) { + if (digInputs[index] == null) { digInputs[index] = new MockDigitalInput(); } return digInputs[index]; @@ -88,17 +86,17 @@ public DigitalInputReader getDigitalInput(int index) { public CameraInterface getCamServer() { return null; } - + @Override - public AnalogInputReader getAnalogInput(int index) { - if(angInputs[index] == null) { + public AnalogInputReader getAnalogInput(final int index) { + if (angInputs[index] == null) { angInputs[index] = new MockAnalogInput(); } return angInputs[index]; } - - public RelayOutput getRelay(int index) { - if(relays[index] == null) { + + public RelayOutput getRelay(final int index) { + if (relays[index] == null) { relays[index] = new MockRelay(index); } return relays[index]; @@ -111,7 +109,7 @@ public PositionReader getPositionSensor() { } return positionSensor; } - + @Override public BeaconReader getBeaconSensor() { if (beaconSensor == null) { @@ -147,7 +145,7 @@ public double getBatteryVoltage() { return m_batteryVoltage; } - public void setBatteryVoltage(double voltage) { + public void setBatteryVoltage(final double voltage) { m_batteryVoltage = voltage; } } diff --git a/src/main/java/com/team766/hal/simulator/AnalogInput.java b/src/main/java/com/team766/hal/simulator/AnalogInput.java index 83e5766b..657b1bf6 100755 --- a/src/main/java/com/team766/hal/simulator/AnalogInput.java +++ b/src/main/java/com/team766/hal/simulator/AnalogInput.java @@ -3,14 +3,14 @@ import com.team766.hal.AnalogInputReader; import com.team766.simulator.ProgramInterface; -public class AnalogInput implements AnalogInputReader{ - +public class AnalogInput implements AnalogInputReader { + private final int channel; - - public AnalogInput(int channel) { - this.channel = channel; + + public AnalogInput(final int channel_) { + this.channel = channel_; } - + @Override public double getVoltage() { return ProgramInterface.analogChannels[channel]; diff --git a/src/main/java/com/team766/hal/simulator/Camera.java b/src/main/java/com/team766/hal/simulator/Camera.java index 7f6bb1e8..0ff02e3c 100755 --- a/src/main/java/com/team766/hal/simulator/Camera.java +++ b/src/main/java/com/team766/hal/simulator/Camera.java @@ -4,11 +4,11 @@ import com.team766.hal.CameraReader; -public class Camera implements CameraReader{ +public class Camera implements CameraReader { @Override public Mat getImage() { return null; } - + } diff --git a/src/main/java/com/team766/hal/simulator/DigitalInput.java b/src/main/java/com/team766/hal/simulator/DigitalInput.java index 7e3b3a17..7227dad5 100755 --- a/src/main/java/com/team766/hal/simulator/DigitalInput.java +++ b/src/main/java/com/team766/hal/simulator/DigitalInput.java @@ -3,12 +3,12 @@ import com.team766.hal.DigitalInputReader; import com.team766.simulator.ProgramInterface; -public class DigitalInput implements DigitalInputReader{ - +public class DigitalInput implements DigitalInputReader { + private final int channel; - - public DigitalInput(int channel) { - this.channel = channel; + + public DigitalInput(final int channel_) { + this.channel = channel_; } public boolean get() { diff --git a/src/main/java/com/team766/hal/simulator/Encoder.java b/src/main/java/com/team766/hal/simulator/Encoder.java index 092c3cb5..4615fc54 100755 --- a/src/main/java/com/team766/hal/simulator/Encoder.java +++ b/src/main/java/com/team766/hal/simulator/Encoder.java @@ -3,18 +3,18 @@ import com.team766.hal.EncoderReader; import com.team766.simulator.ProgramInterface; -public class Encoder implements EncoderReader{ - +public class Encoder implements EncoderReader { + private final int channel; private double distancePerPulse = 1.0; - - public Encoder(int a, int b){ + + public Encoder(final int a, final int b) { this.channel = a; } - + @Override public int get() { - return (int)ProgramInterface.encoderChannels[channel].distance; + return (int) ProgramInterface.encoderChannels[channel].distance; } @Override @@ -43,11 +43,11 @@ public double getRate() { } @Override - public void setDistancePerPulse(double distancePerPulse) { - this.distancePerPulse = distancePerPulse; + public void setDistancePerPulse(final double distancePerPulse_) { + this.distancePerPulse = distancePerPulse_; } - - public void set(int tick){ + + public void set(final int tick) { ProgramInterface.encoderChannels[channel].distance = tick; } diff --git a/src/main/java/com/team766/hal/simulator/Gyro.java b/src/main/java/com/team766/hal/simulator/Gyro.java index 124973d9..0b14870e 100755 --- a/src/main/java/com/team766/hal/simulator/Gyro.java +++ b/src/main/java/com/team766/hal/simulator/Gyro.java @@ -3,7 +3,7 @@ import com.team766.hal.GyroReader; import com.team766.simulator.ProgramInterface; -public class Gyro implements GyroReader{ +public class Gyro implements GyroReader { public void calibrate() { reset(); diff --git a/src/main/java/com/team766/hal/simulator/Relay.java b/src/main/java/com/team766/hal/simulator/Relay.java index f8c0caa4..e0763176 100755 --- a/src/main/java/com/team766/hal/simulator/Relay.java +++ b/src/main/java/com/team766/hal/simulator/Relay.java @@ -3,30 +3,32 @@ import com.team766.hal.RelayOutput; import com.team766.simulator.ProgramInterface; -public class Relay implements RelayOutput{ +public class Relay implements RelayOutput { private int channel; - - public Relay(int channel){ - this.channel = channel; + + public Relay(final int channel_) { + this.channel = channel_; } - + @Override - public void set(Value out) { - switch(out) { - case kForward: - ProgramInterface.relayChannels[channel] = 1; - break; - case kOff: - ProgramInterface.relayChannels[channel] = 0; - break; - case kOn: - ProgramInterface.relayChannels[channel] = 1; - break; - case kReverse: - ProgramInterface.relayChannels[channel] = -1; - break; + public void set(final Value out) { + switch (out) { + case kForward: + ProgramInterface.relayChannels[channel] = 1; + break; + case kOff: + ProgramInterface.relayChannels[channel] = 0; + break; + case kOn: + ProgramInterface.relayChannels[channel] = 1; + break; + case kReverse: + ProgramInterface.relayChannels[channel] = -1; + break; + default: + break; } } - + } diff --git a/src/main/java/com/team766/hal/simulator/RobotMain.java b/src/main/java/com/team766/hal/simulator/RobotMain.java index 1a64e9e3..123f5ce9 100755 --- a/src/main/java/com/team766/hal/simulator/RobotMain.java +++ b/src/main/java/com/team766/hal/simulator/RobotMain.java @@ -1,7 +1,6 @@ package com.team766.hal.simulator; import java.io.IOException; - import com.team766.config.ConfigFileReader; import com.team766.framework.Scheduler; import com.team766.hal.GenericRobotMain; @@ -12,29 +11,29 @@ import com.team766.simulator.Simulator; public class RobotMain { - static enum Mode { + enum Mode { MaroonSim, VrConnector, } private GenericRobotMain robot; private Runnable simulator; - - public RobotMain(Mode mode) { + + public RobotMain(final Mode mode) { try { - // TODO: update this to come from deploy directory? + // TODO: update this to come from deploy directory? ConfigFileReader.instance = new ConfigFileReader("simConfig.txt"); RobotProvider.instance = new SimulationRobotProvider(); - + Scheduler.getInstance().reset(); - + robot = new GenericRobotMain(); - + robot.robotInit(); - + ProgramInterface.program = new Program() { ProgramInterface.RobotMode prevRobotMode = null; - + @Override public void step() { switch (ProgramInterface.robotMode) { @@ -62,6 +61,9 @@ public void step() { robot.teleopPeriodic(); Scheduler.getInstance().run(); break; + default: + LoggerExceptionUtils.logException(new IllegalArgumentException("Value of ProgramInterface.robotMode invalid. Provided value: " + ProgramInterface.robotMode)); + break; } } @@ -76,22 +78,28 @@ public void reset() { } switch (mode) { - case MaroonSim: - simulator = new Simulator(); - break; - case VrConnector: - ProgramInterface.robotMode = ProgramInterface.RobotMode.DISABLED; - try { - simulator = new VrConnector(); - } catch (IOException ex) { - throw new RuntimeException("Error initializing communication with 3d Simulator", ex); - } - break; + case MaroonSim: + simulator = new Simulator(); + break; + case VrConnector: + ProgramInterface.robotMode = ProgramInterface.RobotMode.DISABLED; + try { + simulator = new VrConnector(); + } catch (IOException ex) { + throw new RuntimeException("Error initializing communication with 3d Simulator", + ex); + } + break; + default: + LoggerExceptionUtils.logException( + new IllegalArgumentException("Unknown simulator mode. ProgramInterface.robotMode: " + ProgramInterface.robotMode) + ); + break; } } - - public void run(){ + + public void run() { try { simulator.run(); } catch (Exception exc) { @@ -99,8 +107,8 @@ public void run(){ LoggerExceptionUtils.logException(exc); } } - - public static void main(String[] args) { + + public static void main(final String[] args) { if (args.length != 1) { System.err.println("Needs -maroon_sim or -vr_connector"); System.exit(1); diff --git a/src/main/java/com/team766/hal/simulator/SimMotorController.java b/src/main/java/com/team766/hal/simulator/SimMotorController.java index 4ca0fc8e..7f886221 100755 --- a/src/main/java/com/team766/hal/simulator/SimMotorController.java +++ b/src/main/java/com/team766/hal/simulator/SimMotorController.java @@ -6,11 +6,12 @@ import com.team766.simulator.ProgramInterface; public class SimMotorController extends LocalMotorController { - public SimMotorController(String configPrefix, int address) { + public SimMotorController(final String configPrefix, final int address) { this(configPrefix, ProgramInterface.canMotorControllerChannels[address]); } - SimMotorController(String configPrefix, ProgramInterface.CANMotorControllerCommunication channel) { + SimMotorController(final String configPrefix, + final ProgramInterface.CANMotorControllerCommunication channel) { super(configPrefix, new SimBasicMotorController(channel), new ControlInputReader() { @Override public double getPosition() { @@ -25,15 +26,16 @@ public double getRate() { } } + class SimBasicMotorController implements BasicMotorController { private final ProgramInterface.CANMotorControllerCommunication channel; - public SimBasicMotorController(int address) { + SimBasicMotorController(final int address) { this(ProgramInterface.canMotorControllerChannels[address]); } - public SimBasicMotorController(ProgramInterface.CANMotorControllerCommunication channel) { - this.channel = channel; + SimBasicMotorController(final ProgramInterface.CANMotorControllerCommunication channel_) { + this.channel = channel_; } @Override @@ -50,5 +52,6 @@ public void set(double power) { } @Override - public void restoreFactoryDefault() {} + public void restoreFactoryDefault() { + } } \ No newline at end of file diff --git a/src/main/java/com/team766/hal/simulator/SimulationClock.java b/src/main/java/com/team766/hal/simulator/SimulationClock.java index ffb9c4be..4d40786b 100644 --- a/src/main/java/com/team766/hal/simulator/SimulationClock.java +++ b/src/main/java/com/team766/hal/simulator/SimulationClock.java @@ -4,9 +4,9 @@ import com.team766.simulator.ProgramInterface; public class SimulationClock implements Clock { - + public static final SimulationClock instance = new SimulationClock(); - + @Override public double getTime() { return ProgramInterface.simulationTime; diff --git a/src/main/java/com/team766/hal/simulator/SimulationRobotProvider.java b/src/main/java/com/team766/hal/simulator/SimulationRobotProvider.java index 651c78aa..7b0dd0f4 100755 --- a/src/main/java/com/team766/hal/simulator/SimulationRobotProvider.java +++ b/src/main/java/com/team766/hal/simulator/SimulationRobotProvider.java @@ -18,16 +18,18 @@ import com.team766.hal.MotorController; import com.team766.simulator.ProgramInterface; -public class SimulationRobotProvider extends RobotProvider{ +public class SimulationRobotProvider extends RobotProvider { private MotorController[] motors = new MotorController[100]; private int m_dsUpdateNumber = 0; @Override - public MotorController getMotor(int index, String configPrefix, MotorController.Type type, ControlInputReader localSensor) { - if(motors[index] == null) { + public MotorController getMotor(final int index, final String configPrefix, + final MotorController.Type type, final ControlInputReader localSensor) { + if (motors[index] == null) { if (localSensor != null) { - motors[index] = new LocalMotorController(configPrefix, new SimBasicMotorController(index), localSensor); + motors[index] = new LocalMotorController(configPrefix, + new SimBasicMotorController(index), localSensor); } else { motors[index] = new SimMotorController(configPrefix, index); } @@ -36,45 +38,45 @@ public MotorController getMotor(int index, String configPrefix, MotorController. } @Override - public EncoderReader getEncoder(int index1, int index2) { - if(encoders[index1] == null) { + public EncoderReader getEncoder(final int index1, final int index2) { + if (encoders[index1] == null) { encoders[index1] = new Encoder(index1, index2); } return encoders[index1]; } @Override - public SolenoidController getSolenoid(int index) { - if(solenoids[index] == null) { + public SolenoidController getSolenoid(final int index) { + if (solenoids[index] == null) { solenoids[index] = new Solenoid(index); } return solenoids[index]; } @Override - public GyroReader getGyro(int index) { - if(gyros[0] == null) { + public GyroReader getGyro(final int index) { + if (gyros[0] == null) { gyros[0] = new Gyro(); } return gyros[0]; } @Override - public CameraReader getCamera(String id, String value) { - if(!cams.containsKey(id)) { + public CameraReader getCamera(final String id, final String value) { + if (!cams.containsKey(id)) { cams.put(id, new Camera()); } return cams.get(id); } @Override - public JoystickReader getJoystick(int index) { + public JoystickReader getJoystick(final int index) { return ProgramInterface.joystickChannels[index]; } - + @Override - public DigitalInputReader getDigitalInput(int index) { - if(digInputs[index] == null) { + public DigitalInputReader getDigitalInput(final int index) { + if (digInputs[index] == null) { digInputs[index] = new DigitalInput(index); } return digInputs[index]; @@ -84,17 +86,17 @@ public DigitalInputReader getDigitalInput(int index) { public CameraInterface getCamServer() { return null; } - + @Override - public AnalogInputReader getAnalogInput(int index) { - if(angInputs[index] == null) { + public AnalogInputReader getAnalogInput(final int index) { + if (angInputs[index] == null) { angInputs[index] = new AnalogInput(index); } return angInputs[index]; } - - public RelayOutput getRelay(int index) { - if(relays[index] == null) { + + public RelayOutput getRelay(final int index) { + if (relays[index] == null) { relays[index] = new Relay(index); } return relays[index]; diff --git a/src/main/java/com/team766/hal/simulator/Solenoid.java b/src/main/java/com/team766/hal/simulator/Solenoid.java index cdd2aec9..d49b4e6c 100755 --- a/src/main/java/com/team766/hal/simulator/Solenoid.java +++ b/src/main/java/com/team766/hal/simulator/Solenoid.java @@ -3,15 +3,15 @@ import com.team766.hal.SolenoidController; import com.team766.simulator.ProgramInterface; -public class Solenoid implements SolenoidController{ +public class Solenoid implements SolenoidController { private int channel; - - public Solenoid(int channel){ - this.channel = channel; + + public Solenoid(final int channel_) { + this.channel = channel_; } - - public void set(boolean on) { + + public void set(final boolean on) { ProgramInterface.solenoidChannels[channel] = on; } diff --git a/src/main/java/com/team766/hal/simulator/VrConnector.java b/src/main/java/com/team766/hal/simulator/VrConnector.java index b0e1a054..574832b4 100644 --- a/src/main/java/com/team766/hal/simulator/VrConnector.java +++ b/src/main/java/com/team766/hal/simulator/VrConnector.java @@ -21,7 +21,7 @@ private static class PortMapping { public final int messageDataIndex; public final int robotPortIndex; - public PortMapping(int messageIndex, int robotIndex) { + PortMapping(final int messageIndex, final int robotIndex) { this.messageDataIndex = messageIndex; this.robotPortIndex = robotIndex; } @@ -32,13 +32,11 @@ private static class CANPortMapping { public final int motorCommandMessageDataIndex; public final int sensorFeedbackMessageDataIndex; - public CANPortMapping( - int canId, - int motorCommandMessageDataIndex, - int sensorFeedbackMessageDataIndex) { - this.canId = canId; - this.motorCommandMessageDataIndex = motorCommandMessageDataIndex; - this.sensorFeedbackMessageDataIndex = sensorFeedbackMessageDataIndex; + CANPortMapping(final int canId_, final int motorCommandMessageDataIndex_, + final int sensorFeedbackMessageDataIndex_) { + this.canId = canId_; + this.motorCommandMessageDataIndex = motorCommandMessageDataIndex_; + this.sensorFeedbackMessageDataIndex = sensorFeedbackMessageDataIndex_; } } @@ -49,23 +47,28 @@ public CANPortMapping( private static final int RESET_SIM_CHANNEL = 0; private static final List PWM_CHANNELS = Arrays.asList( - //new PortMapping(10, 6), // Left motor - //new PortMapping(11, 4), // Right motor - //new PortMapping(14, 1), // Auxiliary / Center motor - //new PortMapping(12, 0) // Intake + // new PortMapping(10, 6), // Left motor + // new PortMapping(11, 4), // Right motor + // new PortMapping(14, 1), // Auxiliary / Center motor + // new PortMapping(12, 0) // Intake ); + + //CHECKSTYLE:OFF private static final List SOLENOID_CHANNELS = Arrays.asList( new PortMapping(15, 0), // Intake arm - new PortMapping(13, 1) // Catapult launch + new PortMapping(13, 1) // Catapult launch ); + //CHECKSTYLE:ON + private static final List RELAY_CHANNELS = Arrays.asList(); + //CHECKSTYLE:OFF private static final List CAN_MOTOR_CHANNELS = Arrays.asList( - new CANPortMapping(6, 10, 10), // Left motor - new CANPortMapping(4, 11, 11), // Right motor + new CANPortMapping(6, 10, 10), // Left motor + new CANPortMapping(4, 11, 11), // Right motor new CANPortMapping(10, 12, 13), // Intake - new CANPortMapping(12, 14, 0), // Aux/center motor - new CANPortMapping(14, 16, 0), // Aux2 motor + new CANPortMapping(12, 14, 0), // Aux/center motor + new CANPortMapping(14, 16, 0), // Aux2 motor new CANPortMapping(84, 84, 84), // FLD motor new CANPortMapping(85, 85, 85), // BLD motor @@ -74,8 +77,9 @@ public CANPortMapping( new CANPortMapping(88, 88, 88), // FLS motor new CANPortMapping(89, 89, 89), // BLS motor new CANPortMapping(90, 90, 90), // FRS motor - new CANPortMapping(91, 91, 91) // BRS motor + new CANPortMapping(91, 91, 91) // BRS motor ); + //CHECKSTYLE:ON /// Feedback indexes @@ -85,11 +89,9 @@ public CANPortMapping( private static final int RESET_COUNTER_CHANNEL = 6; private static final int ROBOT_MODE_CHANNEL = 3; - private static final Map ROBOT_MODES = Map.of( - 0, ProgramInterface.RobotMode.DISABLED, - 1, ProgramInterface.RobotMode.AUTON, - 2, ProgramInterface.RobotMode.TELEOP - ); + private static final Map ROBOT_MODES = + Map.of(0, ProgramInterface.RobotMode.DISABLED, 1, ProgramInterface.RobotMode.AUTON, 2, + ProgramInterface.RobotMode.TELEOP); private static final int ROBOT_X_CHANNEL = 8; private static final int ROBOT_Y_CHANNEL = 9; @@ -97,22 +99,29 @@ public CANPortMapping( private static final int BEACON_SENSOR_START = 120; private static final int BEACON_SENSOR_STRIDE = 6; // (x, y, z, yaw, pitch, roll) + //CHECKSTYLE:OFF private static final List ENCODER_CHANNELS = Arrays.asList( new PortMapping(10, 0), // Left encoder new PortMapping(11, 2), // Right encoder - new PortMapping(13, 4) // Mechanism encoder + new PortMapping(13, 4) // Mechanism encoder ); + //CHECKSTYLE:ON + private static final int GYRO_CHANNEL = 15; private static final int GYRO_RATE_CHANNEL = 16; private static final int GYRO_PITCH_CHANNEL = 80; private static final int GYRO_ROLL_CHANNEL = 81; + + //CHECKSTYLE:OFF private static final List DIGITAL_CHANNELS = Arrays.asList( new PortMapping(13, 0), // Intake state new PortMapping(14, 1), // Ball presence new PortMapping(17, 4), // Line Sensor 1 new PortMapping(18, 5), // Line Sensor 2 - new PortMapping(19, 6) // Line Sensor 3 + new PortMapping(19, 6) // Line Sensor 3 ); + //CHECKSTYLE:ON + private static final List ANALOG_CHANNELS = Arrays.asList(); private static final int NUM_JOYSTICK = 4; @@ -141,34 +150,36 @@ public CANPortMapping( private int lastResetCounter = 0; private double lastGyroValue = Double.NaN; private long[] lastEncoderValue = new long[ProgramInterface.encoderChannels.length]; - private long[] lastCANSensorValue = new long[ProgramInterface.canMotorControllerChannels.length]; + private long[] lastCANSensorValue = + new long[ProgramInterface.canMotorControllerChannels.length]; - private int getFeedback(int index) { + private int getFeedback(final int index) { return feedback.getInt(index * 4); } - private static long assembleLong(int msw, int lsw) { - return ((long)msw << 32) | (lsw & 0xffffffffL); + private static long assembleLong(final int msw, final int lsw) { + return ((long) msw << 32) | (lsw & 0xffffffffL); } - private void putCommand(int index, int value) { + private void putCommand(final int index, final int value) { commands.putInt(index * 4, value); } - private void putCommandFloat(int index, double value) { + private void putCommandFloat(final int index, final double value) { putCommand(index, (int) (value * 512.0)); } - private void putCommandTristate(int index, int value) { - if (value == 0) + private void putCommandTristate(final int index, final int value) { + if (value == 0) { putCommand(index, 0); - else if (value > 0) + } else if (value > 0) { putCommand(index, 511); - else + } else { putCommand(index, -512); + } } - private void putCommandBool(int index, boolean value) { + private void putCommandBool(final int index, final boolean value) { putCommand(index, value ? 511 : -512); } @@ -231,7 +242,7 @@ private boolean process() throws IOException { // Time is sent in milliseconds ProgramInterface.simulationTime = assembleLong( getFeedback(TIMESTAMP_MSW_CHANNEL), getFeedback(TIMESTAMP_LSW_CHANNEL)) * 0.001; - + resetCounter = getFeedback(RESET_COUNTER_CHANNEL); ProgramInterface.robotMode = ROBOT_MODES.get(getFeedback(ROBOT_MODE_CHANNEL)); @@ -317,7 +328,8 @@ public void run() { LoggerExceptionUtils.logException(e); try { Thread.sleep(10); - } catch (InterruptedException e1) {} + } catch (InterruptedException e1) { + } } if (ProgramInterface.simulationTime == 0) { // Wait for a connection to the simulator before starting to run the robot code. diff --git a/src/main/java/com/team766/hal/wpilib/ADXRS450_Gyro.java b/src/main/java/com/team766/hal/wpilib/ADXRS450_Gyro.java index cf71649b..1f11813e 100755 --- a/src/main/java/com/team766/hal/wpilib/ADXRS450_Gyro.java +++ b/src/main/java/com/team766/hal/wpilib/ADXRS450_Gyro.java @@ -7,7 +7,7 @@ import edu.wpi.first.wpilibj.SPI; public class ADXRS450_Gyro extends edu.wpi.first.wpilibj.ADXRS450_Gyro implements GyroReader { - public ADXRS450_Gyro(SPI.Port port) { + public ADXRS450_Gyro(final SPI.Port port) { super(port); if (!isConnected()) { Logger.get(Category.HAL).logData(Severity.ERROR, "ADXRS450 Gyro is not connected!"); diff --git a/src/main/java/com/team766/hal/wpilib/AnalogGyro.java b/src/main/java/com/team766/hal/wpilib/AnalogGyro.java index 7417cf86..4d96dff5 100755 --- a/src/main/java/com/team766/hal/wpilib/AnalogGyro.java +++ b/src/main/java/com/team766/hal/wpilib/AnalogGyro.java @@ -3,7 +3,7 @@ import com.team766.hal.GyroReader; public class AnalogGyro extends edu.wpi.first.wpilibj.AnalogGyro implements GyroReader { - public AnalogGyro(int channel) { + public AnalogGyro(final int channel) { super(channel); } diff --git a/src/main/java/com/team766/hal/wpilib/AnalogInput.java b/src/main/java/com/team766/hal/wpilib/AnalogInput.java index eca6ae4a..21b5e9a5 100755 --- a/src/main/java/com/team766/hal/wpilib/AnalogInput.java +++ b/src/main/java/com/team766/hal/wpilib/AnalogInput.java @@ -3,7 +3,7 @@ import com.team766.hal.AnalogInputReader; public class AnalogInput extends edu.wpi.first.wpilibj.AnalogInput implements AnalogInputReader { - public AnalogInput(int channel) { + public AnalogInput(final int channel) { super(channel); } } diff --git a/src/main/java/com/team766/hal/wpilib/BaseCTRESpeedController.java b/src/main/java/com/team766/hal/wpilib/BaseCTRESpeedController.java index b33b2736..0ee1c0fb 100644 --- a/src/main/java/com/team766/hal/wpilib/BaseCTRESpeedController.java +++ b/src/main/java/com/team766/hal/wpilib/BaseCTRESpeedController.java @@ -8,12 +8,12 @@ class BaseCTREMotorController { protected static final int TIMEOUT_MS = 20; - protected static enum ExceptionTarget { + protected enum ExceptionTarget { THROW, LOG, } - protected static void errorCodeToException(ExceptionTarget throwEx, ErrorCode err) { + protected static void errorCodeToException(final ExceptionTarget throwEx, final ErrorCode err) { if (err == ErrorCode.OK) { return; } @@ -21,7 +21,7 @@ protected static void errorCodeToException(ExceptionTarget throwEx, ErrorCode er switch (throwEx) { case THROW: throw ex; - case LOG: + default: case LOG: LoggerExceptionUtils.logException(ex); break; } diff --git a/src/main/java/com/team766/hal/wpilib/CANSparkMaxMotorController.java b/src/main/java/com/team766/hal/wpilib/CANSparkMaxMotorController.java index 006d65b4..14f3113f 100644 --- a/src/main/java/com/team766/hal/wpilib/CANSparkMaxMotorController.java +++ b/src/main/java/com/team766/hal/wpilib/CANSparkMaxMotorController.java @@ -20,7 +20,7 @@ public class CANSparkMaxMotorController extends CANSparkMax implements MotorCont private Function sensorInvertedSetter; private boolean sensorInverted = false; - public CANSparkMaxMotorController(int deviceId) { + public CANSparkMaxMotorController(final int deviceId) { super(deviceId, MotorType.kBrushless); // Set default feedback device. This ensures that our implementations of @@ -29,12 +29,12 @@ public CANSparkMaxMotorController(int deviceId) { setSelectedFeedbackSensor(FeedbackDevice.IntegratedSensor); } - private static enum ExceptionTarget { + private enum ExceptionTarget { THROW, LOG, } - private static void revErrorToException(ExceptionTarget throwEx, REVLibError err) { + private static void revErrorToException(final ExceptionTarget throwEx, final REVLibError err) { if (err == REVLibError.kOk) { return; } @@ -42,7 +42,7 @@ private static void revErrorToException(ExceptionTarget throwEx, REVLibError err switch (throwEx) { case THROW: throw ex; - case LOG: + default: case LOG: LoggerExceptionUtils.logException(ex); break; } @@ -59,7 +59,7 @@ public double getSensorVelocity() { } @Override - public void set(ControlMode mode, double value) { + public void set(final ControlMode mode, final double value) { switch (mode) { case Current: getPIDController().setReference(value, CANSparkMax.ControlType.kCurrent); @@ -92,21 +92,22 @@ public void set(ControlMode mode, double value) { } @Override - public void setSensorPosition(double position) { + public void setSensorPosition(final double position) { revErrorToException(ExceptionTarget.THROW, sensorPositionSetter.apply(position)); } @Override - public void follow(MotorController leader) { + public void follow(final MotorController leader) { try { - revErrorToException(ExceptionTarget.LOG, super.follow((CANSparkMax)leader)); + revErrorToException(ExceptionTarget.LOG, super.follow((CANSparkMax) leader)); } catch (ClassCastException ex) { - LoggerExceptionUtils.logException(new IllegalArgumentException("Spark Max can only follow another Spark Max", ex)); + LoggerExceptionUtils.logException(new IllegalArgumentException( + "Spark Max can only follow another Spark Max", ex)); } } @Override - public void setNeutralMode(NeutralMode neutralMode) { + public void setNeutralMode(final NeutralMode neutralMode) { switch (neutralMode) { case Brake: revErrorToException(ExceptionTarget.LOG, setIdleMode(IdleMode.kBrake)); @@ -115,33 +116,34 @@ public void setNeutralMode(NeutralMode neutralMode) { revErrorToException(ExceptionTarget.LOG, setIdleMode(IdleMode.kCoast)); break; default: - LoggerExceptionUtils.logException(new IllegalArgumentException("Unsupported neutral mode " + neutralMode)); + LoggerExceptionUtils.logException( + new IllegalArgumentException("Unsupported neutral mode " + neutralMode)); break; } } @Override - public void setP(double value) { + public void setP(final double value) { revErrorToException(ExceptionTarget.LOG, getPIDController().setP(value)); } @Override - public void setI(double value) { + public void setI(final double value) { revErrorToException(ExceptionTarget.LOG, getPIDController().setI(value)); } @Override - public void setD(double value) { + public void setD(final double value) { revErrorToException(ExceptionTarget.LOG, getPIDController().setD(value)); } @Override - public void setFF(double value) { + public void setFF(final double value) { revErrorToException(ExceptionTarget.LOG, getPIDController().setFF(value)); } @Override - public void setSelectedFeedbackSensor(FeedbackDevice feedbackDevice) { + public void setSelectedFeedbackSensor(final FeedbackDevice feedbackDevice) { switch (feedbackDevice) { case Analog: { SparkMaxAnalogSensor analog = getAnalog(SparkMaxAnalogSensor.Mode.kAbsolute); @@ -150,31 +152,38 @@ public void setSelectedFeedbackSensor(FeedbackDevice feedbackDevice) { sensorVelocitySupplier = analog::getVelocity; sensorPositionSetter = (pos) -> REVLibError.kOk; sensorInvertedSetter = analog::setInverted; - revErrorToException(ExceptionTarget.LOG, getPIDController().setFeedbackDevice(analog)); + revErrorToException(ExceptionTarget.LOG, + getPIDController().setFeedbackDevice(analog)); return; } case CTRE_MagEncoder_Absolute: - LoggerExceptionUtils.logException(new IllegalArgumentException("SparkMax does not support CTRE Mag Encoder")); + LoggerExceptionUtils.logException( + new IllegalArgumentException("SparkMax does not support CTRE Mag Encoder")); case CTRE_MagEncoder_Relative: - LoggerExceptionUtils.logException(new IllegalArgumentException("SparkMax does not support CTRE Mag Encoder")); + LoggerExceptionUtils.logException( + new IllegalArgumentException("SparkMax does not support CTRE Mag Encoder")); case IntegratedSensor: { RelativeEncoder encoder = getEncoder(); - // NOTE(rcahoon, 2022-04-19): Don't call this. Trying to call setInverted on the integrated sensor returns an error. + // NOTE(rcahoon, 2022-04-19): Don't call this. Trying to call setInverted on the + // integrated sensor returns an error. // revErrorToException(ExceptionTarget.LOG, encoder.setInverted(sensorInverted)); sensorPositionSupplier = encoder::getPosition; sensorVelocitySupplier = encoder::getVelocity; sensorPositionSetter = encoder::setPosition; - // NOTE(rcahoon, 2022-04-19): Don't call this. Trying to call setInverted on the integrated sensor returns an error. + // NOTE(rcahoon, 2022-04-19): Don't call this. Trying to call setInverted on the + // integrated sensor returns an error. // sensorInvertedSetter = encoder::setInverted; sensorInvertedSetter = (inverted) -> REVLibError.kOk; - revErrorToException(ExceptionTarget.LOG, getPIDController().setFeedbackDevice(encoder)); + revErrorToException(ExceptionTarget.LOG, + getPIDController().setFeedbackDevice(encoder)); return; } case None: return; case PulseWidthEncodedPosition: - LoggerExceptionUtils.logException(new IllegalArgumentException("SparkMax does not support PWM sensors")); - case QuadEncoder: { + LoggerExceptionUtils.logException( + new IllegalArgumentException("SparkMax does not support PWM sensors")); + case QuadEncoder: // TODO: should we pass a real counts-per-rev scale here? RelativeEncoder encoder = getAlternateEncoder(1); revErrorToException(ExceptionTarget.LOG, encoder.setInverted(sensorInverted)); @@ -182,39 +191,47 @@ public void setSelectedFeedbackSensor(FeedbackDevice feedbackDevice) { sensorVelocitySupplier = encoder::getVelocity; sensorPositionSetter = encoder::setPosition; sensorInvertedSetter = encoder::setInverted; - revErrorToException(ExceptionTarget.LOG, getPIDController().setFeedbackDevice(encoder)); + revErrorToException(ExceptionTarget.LOG, + getPIDController().setFeedbackDevice(encoder)); return; - } case RemoteSensor0: - LoggerExceptionUtils.logException(new IllegalArgumentException("SparkMax does not support remote sensors")); + LoggerExceptionUtils.logException( + new IllegalArgumentException("SparkMax does not support remote sensors")); case RemoteSensor1: - LoggerExceptionUtils.logException(new IllegalArgumentException("SparkMax does not support remote sensors")); + LoggerExceptionUtils.logException( + new IllegalArgumentException("SparkMax does not support remote sensors")); case SensorDifference: - LoggerExceptionUtils.logException(new IllegalArgumentException("SparkMax does not support SensorDifference")); + LoggerExceptionUtils.logException( + new IllegalArgumentException("SparkMax does not support SensorDifference")); case SensorSum: - LoggerExceptionUtils.logException(new IllegalArgumentException("SparkMax does not support SensorSum")); + LoggerExceptionUtils.logException( + new IllegalArgumentException("SparkMax does not support SensorSum")); case SoftwareEmulatedSensor: - LoggerExceptionUtils.logException(new IllegalArgumentException("SparkMax does not support SoftwareEmulatedSensor")); + LoggerExceptionUtils.logException(new IllegalArgumentException( + "SparkMax does not support SoftwareEmulatedSensor")); case Tachometer: - LoggerExceptionUtils.logException(new IllegalArgumentException("SparkMax does not support Tachometer")); + LoggerExceptionUtils.logException( + new IllegalArgumentException("SparkMax does not support Tachometer")); default: - LoggerExceptionUtils.logException(new IllegalArgumentException("Unsupported sensor type " + feedbackDevice)); + LoggerExceptionUtils.logException( + new IllegalArgumentException("Unsupported sensor type " + feedbackDevice)); } } @Override - public void setSensorInverted(boolean inverted) { + public void setSensorInverted(final boolean inverted) { sensorInverted = inverted; revErrorToException(ExceptionTarget.LOG, sensorInvertedSetter.apply(inverted)); } @Override - public void setOutputRange(double minOutput, double maxOutput) { - revErrorToException(ExceptionTarget.LOG, getPIDController().setOutputRange(minOutput, maxOutput)); + public void setOutputRange(final double minOutput, final double maxOutput) { + revErrorToException(ExceptionTarget.LOG, + getPIDController().setOutputRange(minOutput, maxOutput)); } - public void setCurrentLimit(double ampsLimit) { - revErrorToException(ExceptionTarget.LOG, setSmartCurrentLimit((int)ampsLimit)); + public void setCurrentLimit(final double ampsLimit) { + revErrorToException(ExceptionTarget.LOG, setSmartCurrentLimit((int) ampsLimit)); } @Override @@ -223,13 +240,12 @@ public void restoreFactoryDefault() { } @Override - public void setOpenLoopRamp(double secondsFromNeutralToFull) { + public void setOpenLoopRamp(final double secondsFromNeutralToFull) { revErrorToException(ExceptionTarget.LOG, setOpenLoopRampRate(secondsFromNeutralToFull)); } @Override - public void setClosedLoopRamp(double secondsFromNeutralToFull) { + public void setClosedLoopRamp(final double secondsFromNeutralToFull) { revErrorToException(ExceptionTarget.LOG, setClosedLoopRampRate(secondsFromNeutralToFull)); } - } diff --git a/src/main/java/com/team766/hal/wpilib/CANTalonFxMotorController.java b/src/main/java/com/team766/hal/wpilib/CANTalonFxMotorController.java index ec30728a..2daa0d03 100644 --- a/src/main/java/com/team766/hal/wpilib/CANTalonFxMotorController.java +++ b/src/main/java/com/team766/hal/wpilib/CANTalonFxMotorController.java @@ -17,54 +17,56 @@ public class CANTalonFxMotorController extends BaseCTREMotorController implement private WPI_TalonFX m_device; private double m_feedForward = 0.0; - public CANTalonFxMotorController(int deviceNumber) { + public CANTalonFxMotorController(final int deviceNumber) { m_device = new WPI_TalonFX(deviceNumber); } @Override - public void set(ControlMode mode, double value) { + public void set(final ControlMode mode, double value) { com.ctre.phoenix.motorcontrol.ControlMode ctre_mode = null; boolean useFourTermSet = true; switch (mode) { - case PercentOutput: - ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.PercentOutput; - useFourTermSet = false; - break; - case Position: - ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.Position; - break; - case Velocity: - // Sensor velocity is measured in units per 100ms. - value /= 10.0; - ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.Velocity; - break; - case Current: - ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.Current; - break; - case Follower: - ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.Follower; - useFourTermSet = false; - break; - case MotionProfile: - ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.MotionProfile; - break; - case MotionMagic: - ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.MotionMagic; - break; - case MotionProfileArc: - ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.MotionProfileArc; - break; - case Voltage: - m_device.setVoltage(value); - return; - case Disabled: - ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.Disabled; - useFourTermSet = false; - break; + case PercentOutput: + ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.PercentOutput; + useFourTermSet = false; + break; + case Position: + ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.Position; + break; + case Velocity: + // Sensor velocity is measured in units per 100ms. + value /= 10.0; + ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.Velocity; + break; + case Current: + ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.Current; + break; + case Follower: + ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.Follower; + useFourTermSet = false; + break; + case MotionProfile: + ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.MotionProfile; + break; + case MotionMagic: + ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.MotionMagic; + break; + case MotionProfileArc: + ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.MotionProfileArc; + break; + case Voltage: + m_device.setVoltage(value); + return; + case Disabled: + ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.Disabled; + useFourTermSet = false; + break; + default: + LoggerExceptionUtils.logException(new UnsupportedOperationException("invalid mode provided. provided value: " + mode)); + break; } if (ctre_mode == null) { - Logger.get(Category.HAL).logRaw( - Severity.ERROR, + Logger.get(Category.HAL).logRaw(Severity.ERROR, "CAN ControlMode is not translatable: " + mode); ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.Disabled; } @@ -90,71 +92,76 @@ public double getSensorVelocity() { // Sensor velocity is returned in units per 100ms. return m_device.getSelectedSensorVelocity(0) * 10.0; } - + @Override - public void setSensorPosition(double position){ - errorCodeToException(ExceptionTarget.THROW, m_device.setSelectedSensorPosition(position, 0, 0)); + public void setSensorPosition(final double position) { + errorCodeToException(ExceptionTarget.THROW, + m_device.setSelectedSensorPosition(position, 0, 0)); } @Override - public void follow(MotorController leader) { + public void follow(final MotorController leader) { try { - m_device.follow((IMotorController)leader); + m_device.follow((IMotorController) leader); } catch (ClassCastException ex) { - LoggerExceptionUtils.logException(new IllegalArgumentException("Talon can only follow another CTRE motor controller", ex)); + LoggerExceptionUtils.logException(new IllegalArgumentException( + "Talon can only follow another CTRE motor controller", ex)); } } @Override - public void setOpenLoopRamp(double secondsFromNeutralToFull) { - errorCodeToException(ExceptionTarget.LOG, m_device.configOpenloopRamp(secondsFromNeutralToFull, TIMEOUT_MS)); + public void setOpenLoopRamp(final double secondsFromNeutralToFull) { + errorCodeToException(ExceptionTarget.LOG, + m_device.configOpenloopRamp(secondsFromNeutralToFull, TIMEOUT_MS)); } @Override - public void setClosedLoopRamp(double secondsFromNeutralToFull) { - errorCodeToException(ExceptionTarget.LOG, m_device.configClosedloopRamp(secondsFromNeutralToFull, TIMEOUT_MS)); + public void setClosedLoopRamp(final double secondsFromNeutralToFull) { + errorCodeToException(ExceptionTarget.LOG, + m_device.configClosedloopRamp(secondsFromNeutralToFull, TIMEOUT_MS)); } @Override - public void setFF(double value) { + public void setFF(final double value) { errorCodeToException(ExceptionTarget.LOG, m_device.config_kF(0, value, TIMEOUT_MS)); } @Override - public void setP(double value) { + public void setP(final double value) { errorCodeToException(ExceptionTarget.LOG, m_device.config_kP(0, value)); } @Override - public void setI(double value) { + public void setI(final double value) { errorCodeToException(ExceptionTarget.LOG, m_device.config_kI(0, value)); } @Override - public void setD(double value) { + public void setD(final double value) { errorCodeToException(ExceptionTarget.LOG, m_device.config_kD(0, value)); } @Override - public void setSelectedFeedbackSensor(FeedbackDevice feedbackDevice) { - errorCodeToException(ExceptionTarget.LOG, m_device.configSelectedFeedbackSensor(feedbackDevice)); + public void setSelectedFeedbackSensor(final FeedbackDevice feedbackDevice) { + errorCodeToException(ExceptionTarget.LOG, + m_device.configSelectedFeedbackSensor(feedbackDevice)); } @Override - public void setSensorInverted(boolean inverted) { + public void setSensorInverted(final boolean inverted) { m_device.setSensorPhase(inverted); } @Override - public void setOutputRange(double minOutput, double maxOutput) { + public void setOutputRange(final double minOutput, final double maxOutput) { errorCodeToException(ExceptionTarget.LOG, m_device.configPeakOutputReverse(minOutput)); errorCodeToException(ExceptionTarget.LOG, m_device.configPeakOutputForward(maxOutput)); } @Override - public void setCurrentLimit(double ampsLimit) { + public void setCurrentLimit(final double ampsLimit) { errorCodeToException(ExceptionTarget.LOG, m_device.configSupplyCurrentLimit( - new SupplyCurrentLimitConfiguration(true, ampsLimit, 0, 0.01))); + new SupplyCurrentLimitConfiguration(true, ampsLimit, 0, 0.01))); } @Override @@ -168,12 +175,12 @@ public double get() { } @Override - public void set(double power) { + public void set(final double power) { m_device.set(power); } @Override - public void setInverted(boolean isInverted) { + public void setInverted(final boolean isInverted) { m_device.setInverted(isInverted); } @@ -183,8 +190,8 @@ public boolean getInverted() { } @Override - public void setNeutralMode(NeutralMode neutralMode) { + public void setNeutralMode(final NeutralMode neutralMode) { m_device.setNeutralMode(neutralMode); } - + } diff --git a/src/main/java/com/team766/hal/wpilib/CANTalonMotorController.java b/src/main/java/com/team766/hal/wpilib/CANTalonMotorController.java index 7eae784b..c4648ce4 100644 --- a/src/main/java/com/team766/hal/wpilib/CANTalonMotorController.java +++ b/src/main/java/com/team766/hal/wpilib/CANTalonMotorController.java @@ -16,54 +16,56 @@ public class CANTalonMotorController extends BaseCTREMotorController implements private WPI_TalonSRX m_device; private double m_feedForward = 0.0; - public CANTalonMotorController(int deviceNumber) { + public CANTalonMotorController(final int deviceNumber) { m_device = new WPI_TalonSRX(deviceNumber); } @Override - public void set(ControlMode mode, double value) { + public void set(final ControlMode mode, double value) { com.ctre.phoenix.motorcontrol.ControlMode ctre_mode = null; boolean useFourTermSet = true; switch (mode) { - case PercentOutput: - ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.PercentOutput; - useFourTermSet = false; - break; - case Position: - ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.Position; - break; - case Velocity: - // Sensor velocity is measured in units per 100ms. - value /= 10.0; - ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.Velocity; - break; - case Current: - ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.Current; - break; - case Follower: - ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.Follower; - useFourTermSet = false; - break; - case MotionProfile: - ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.MotionProfile; - break; - case MotionMagic: - ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.MotionMagic; - break; - case MotionProfileArc: - ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.MotionProfileArc; - break; - case Voltage: - m_device.setVoltage(value); - return; - case Disabled: - ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.Disabled; - useFourTermSet = false; - break; + case PercentOutput: + ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.PercentOutput; + useFourTermSet = false; + break; + case Position: + ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.Position; + break; + case Velocity: + // Sensor velocity is measured in units per 100ms. + value /= 10.0; + ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.Velocity; + break; + case Current: + ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.Current; + break; + case Follower: + ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.Follower; + useFourTermSet = false; + break; + case MotionProfile: + ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.MotionProfile; + break; + case MotionMagic: + ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.MotionMagic; + break; + case MotionProfileArc: + ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.MotionProfileArc; + break; + case Voltage: + m_device.setVoltage(value); + return; + case Disabled: + ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.Disabled; + useFourTermSet = false; + break; + default: + LoggerExceptionUtils.logException(new UnsupportedOperationException("invalid mode provided. provided value: " + mode)); + break; } if (ctre_mode == null) { - Logger.get(Category.HAL).logRaw( - Severity.ERROR, + Logger.get(Category.HAL).logRaw(Severity.ERROR, "CAN ControlMode is not translatable: " + mode); ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.Disabled; } @@ -89,72 +91,78 @@ public double getSensorVelocity() { // Sensor velocity is returned in units per 100ms. return m_device.getSelectedSensorVelocity(0) * 10.0; } - + @Override - public void setSensorPosition(double position){ - errorCodeToException(ExceptionTarget.THROW, m_device.setSelectedSensorPosition(position, 0, 0)); + public void setSensorPosition(final double position) { + errorCodeToException(ExceptionTarget.THROW, + m_device.setSelectedSensorPosition(position, 0, 0)); } @Override - public void follow(MotorController leader) { + public void follow(final MotorController leader) { try { - m_device.follow((IMotorController)leader); + m_device.follow((IMotorController) leader); } catch (ClassCastException ex) { - LoggerExceptionUtils.logException(new IllegalArgumentException("Talon can only follow another CTRE motor controller", ex)); + LoggerExceptionUtils.logException(new IllegalArgumentException( + "Talon can only follow another CTRE motor controller", ex)); } } @Override - public void setOpenLoopRamp(double secondsFromNeutralToFull) { - errorCodeToException(ExceptionTarget.LOG, m_device.configOpenloopRamp(secondsFromNeutralToFull, TIMEOUT_MS)); + public void setOpenLoopRamp(final double secondsFromNeutralToFull) { + errorCodeToException(ExceptionTarget.LOG, + m_device.configOpenloopRamp(secondsFromNeutralToFull, TIMEOUT_MS)); } @Override - public void setClosedLoopRamp(double secondsFromNeutralToFull) { - errorCodeToException(ExceptionTarget.LOG, m_device.configClosedloopRamp(secondsFromNeutralToFull, TIMEOUT_MS)); + public void setClosedLoopRamp(final double secondsFromNeutralToFull) { + errorCodeToException(ExceptionTarget.LOG, + m_device.configClosedloopRamp(secondsFromNeutralToFull, TIMEOUT_MS)); } @Override - public void setFF(double value) { + public void setFF(final double value) { errorCodeToException(ExceptionTarget.LOG, m_device.config_kF(0, value, TIMEOUT_MS)); } @Override - public void setP(double value) { + public void setP(final double value) { errorCodeToException(ExceptionTarget.LOG, m_device.config_kP(0, value)); } @Override - public void setI(double value) { + public void setI(final double value) { errorCodeToException(ExceptionTarget.LOG, m_device.config_kI(0, value)); } @Override - public void setD(double value) { + public void setD(final double value) { errorCodeToException(ExceptionTarget.LOG, m_device.config_kD(0, value)); } @Override - public void setSelectedFeedbackSensor(FeedbackDevice feedbackDevice) { - errorCodeToException(ExceptionTarget.LOG, m_device.configSelectedFeedbackSensor(feedbackDevice)); + public void setSelectedFeedbackSensor(final FeedbackDevice feedbackDevice) { + errorCodeToException(ExceptionTarget.LOG, + m_device.configSelectedFeedbackSensor(feedbackDevice)); } @Override - public void setSensorInverted(boolean inverted) { + public void setSensorInverted(final boolean inverted) { m_device.setSensorPhase(inverted); } @Override - public void setOutputRange(double minOutput, double maxOutput) { + public void setOutputRange(final double minOutput, final double maxOutput) { errorCodeToException(ExceptionTarget.LOG, m_device.configPeakOutputReverse(minOutput)); errorCodeToException(ExceptionTarget.LOG, m_device.configPeakOutputForward(maxOutput)); } @Override - public void setCurrentLimit(double ampsLimit) { + public void setCurrentLimit(final double ampsLimit) { errorCodeToException(ExceptionTarget.LOG, m_device.configPeakCurrentLimit(0)); errorCodeToException(ExceptionTarget.LOG, m_device.configPeakCurrentDuration(10)); - errorCodeToException(ExceptionTarget.LOG, m_device.configContinuousCurrentLimit((int)ampsLimit)); + errorCodeToException(ExceptionTarget.LOG, + m_device.configContinuousCurrentLimit((int) ampsLimit)); m_device.enableCurrentLimit(true); } @@ -169,12 +177,12 @@ public double get() { } @Override - public void set(double power) { + public void set(final double power) { m_device.set(power); } @Override - public void setInverted(boolean isInverted) { + public void setInverted(final boolean isInverted) { m_device.setInverted(isInverted); } @@ -184,8 +192,8 @@ public boolean getInverted() { } @Override - public void setNeutralMode(NeutralMode neutralMode) { + public void setNeutralMode(final NeutralMode neutralMode) { m_device.setNeutralMode(neutralMode); } - + } diff --git a/src/main/java/com/team766/hal/wpilib/CANVictorMotorController.java b/src/main/java/com/team766/hal/wpilib/CANVictorMotorController.java index 1dffa99b..ecf303be 100644 --- a/src/main/java/com/team766/hal/wpilib/CANVictorMotorController.java +++ b/src/main/java/com/team766/hal/wpilib/CANVictorMotorController.java @@ -15,55 +15,57 @@ public class CANVictorMotorController extends BaseCTREMotorController implements private WPI_VictorSPX m_device; private double m_feedForward = 0.0; - - public CANVictorMotorController(int deviceNumber) { + + public CANVictorMotorController(final int deviceNumber) { m_device = new WPI_VictorSPX(deviceNumber); } @Override - public void set(ControlMode mode, double value) { + public void set(final ControlMode mode, double value) { com.ctre.phoenix.motorcontrol.ControlMode ctre_mode = null; boolean useFourTermSet = true; switch (mode) { - case PercentOutput: - ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.PercentOutput; - useFourTermSet = false; - break; - case Position: - ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.Position; - break; - case Velocity: - // Sensor velocity is measured in units per 100ms. - value /= 10.0; - ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.Velocity; - break; - case Current: - ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.Current; - break; - case Follower: - ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.Follower; - useFourTermSet = false; - break; - case MotionProfile: - ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.MotionProfile; - break; - case MotionMagic: - ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.MotionMagic; - break; - case MotionProfileArc: - ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.MotionProfileArc; - break; - case Voltage: - m_device.setVoltage(value); - return; - case Disabled: - ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.Disabled; - useFourTermSet = false; - break; + case PercentOutput: + ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.PercentOutput; + useFourTermSet = false; + break; + case Position: + ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.Position; + break; + case Velocity: + // Sensor velocity is measured in units per 100ms. + value /= 10.0; + ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.Velocity; + break; + case Current: + ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.Current; + break; + case Follower: + ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.Follower; + useFourTermSet = false; + break; + case MotionProfile: + ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.MotionProfile; + break; + case MotionMagic: + ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.MotionMagic; + break; + case MotionProfileArc: + ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.MotionProfileArc; + break; + case Voltage: + m_device.setVoltage(value); + return; + case Disabled: + ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.Disabled; + useFourTermSet = false; + break; + default: + LoggerExceptionUtils.logException(new UnsupportedOperationException("invalid mode provided. provided value: " + mode)); + break; } if (ctre_mode == null) { - Logger.get(Category.HAL).logRaw( - Severity.ERROR, + Logger.get(Category.HAL).logRaw(Severity.ERROR, "CAN ControlMode is not translatable: " + mode); ctre_mode = com.ctre.phoenix.motorcontrol.ControlMode.Disabled; } @@ -89,33 +91,37 @@ public double getSensorVelocity() { // Sensor velocity is returned in units per 100ms. return m_device.getSelectedSensorVelocity(0) * 10.0; } - + @Override - public void setSensorPosition(double position){ - errorCodeToException(ExceptionTarget.THROW, m_device.setSelectedSensorPosition(position, 0, 20)); + public void setSensorPosition(final double position) { + errorCodeToException(ExceptionTarget.THROW, + m_device.setSelectedSensorPosition(position, 0, 20)); } @Override - public void follow(MotorController leader) { + public void follow(final MotorController leader) { try { - m_device.follow((IMotorController)leader); + m_device.follow((IMotorController) leader); } catch (ClassCastException ex) { - LoggerExceptionUtils.logException(new IllegalArgumentException("Victor can only follow another CTRE motor controller", ex)); + LoggerExceptionUtils.logException(new IllegalArgumentException( + "Victor can only follow another CTRE motor controller", ex)); } } @Override - public void setOpenLoopRamp(double secondsFromNeutralToFull) { - errorCodeToException(ExceptionTarget.LOG, m_device.configOpenloopRamp(secondsFromNeutralToFull, TIMEOUT_MS)); + public void setOpenLoopRamp(final double secondsFromNeutralToFull) { + errorCodeToException(ExceptionTarget.LOG, + m_device.configOpenloopRamp(secondsFromNeutralToFull, TIMEOUT_MS)); } @Override - public void setClosedLoopRamp(double secondsFromNeutralToFull) { - errorCodeToException(ExceptionTarget.LOG, m_device.configClosedloopRamp(secondsFromNeutralToFull, TIMEOUT_MS)); + public void setClosedLoopRamp(final double secondsFromNeutralToFull) { + errorCodeToException(ExceptionTarget.LOG, + m_device.configClosedloopRamp(secondsFromNeutralToFull, TIMEOUT_MS)); } @Override - public void setFF(double value) { + public void setFF(final double value) { errorCodeToException(ExceptionTarget.LOG, m_device.config_kF(0, value, TIMEOUT_MS)); } @@ -125,12 +131,12 @@ public double get() { } @Override - public void set(double power) { + public void set(final double power) { m_device.set(power); } @Override - public void setInverted(boolean isInverted) { + public void setInverted(final boolean isInverted) { m_device.setInverted(isInverted); } @@ -140,43 +146,44 @@ public boolean getInverted() { } @Override - public void setNeutralMode(NeutralMode neutralMode) { + public void setNeutralMode(final NeutralMode neutralMode) { m_device.setNeutralMode(neutralMode); } @Override - public void setP(double value) { + public void setP(final double value) { errorCodeToException(ExceptionTarget.LOG, m_device.config_kP(0, value, TIMEOUT_MS)); } @Override - public void setI(double value) { + public void setI(final double value) { errorCodeToException(ExceptionTarget.LOG, m_device.config_kI(0, value, TIMEOUT_MS)); } @Override - public void setD(double value) { + public void setD(final double value) { errorCodeToException(ExceptionTarget.LOG, m_device.config_kD(0, value, TIMEOUT_MS)); } @Override - public void setSelectedFeedbackSensor(FeedbackDevice feedbackDevice) { - errorCodeToException(ExceptionTarget.LOG, m_device.configSelectedFeedbackSensor(feedbackDevice)); + public void setSelectedFeedbackSensor(final FeedbackDevice feedbackDevice) { + errorCodeToException(ExceptionTarget.LOG, + m_device.configSelectedFeedbackSensor(feedbackDevice)); } @Override - public void setSensorInverted(boolean inverted) { + public void setSensorInverted(final boolean inverted) { m_device.setSensorPhase(inverted); } @Override - public void setOutputRange(double minOutput, double maxOutput) { + public void setOutputRange(final double minOutput, final double maxOutput) { errorCodeToException(ExceptionTarget.LOG, m_device.configPeakOutputReverse(minOutput)); errorCodeToException(ExceptionTarget.LOG, m_device.configPeakOutputForward(maxOutput)); } - + @Override - public void setCurrentLimit(double ampsLimit) { + public void setCurrentLimit(final double ampsLimit) { LoggerExceptionUtils.logException( new UnsupportedOperationException("VictorSPX does not support current limiting")); } diff --git a/src/main/java/com/team766/hal/wpilib/CameraInterface.java b/src/main/java/com/team766/hal/wpilib/CameraInterface.java index 4f5122c5..d561a656 100755 --- a/src/main/java/com/team766/hal/wpilib/CameraInterface.java +++ b/src/main/java/com/team766/hal/wpilib/CameraInterface.java @@ -16,21 +16,21 @@ public class CameraInterface implements com.team766.hal.CameraInterface { @Override public void startAutomaticCapture() { - try{ + try { CameraServer.startAutomaticCapture(VideoSource.enumerateSources()[0]); - } catch(Exception e){ + } catch (Exception e) { Logger.get(Category.CAMERA).logRaw(Severity.ERROR, e.toString()); } } @Override - public void getFrame(Mat img) { + public void getFrame(final Mat img) { CameraServer.getVideo().grabFrame(img); } @Override - public void putFrame(Mat img){ - if(vidSource == null){ + public void putFrame(final Mat img) { + if (vidSource == null) { vidSource = CameraServer.putVideo("VisionTracking", img.width(), img.height()); } diff --git a/src/main/java/com/team766/hal/wpilib/DigitalInput.java b/src/main/java/com/team766/hal/wpilib/DigitalInput.java index d9abc338..8c7311df 100755 --- a/src/main/java/com/team766/hal/wpilib/DigitalInput.java +++ b/src/main/java/com/team766/hal/wpilib/DigitalInput.java @@ -3,7 +3,7 @@ import com.team766.hal.DigitalInputReader; public class DigitalInput extends edu.wpi.first.wpilibj.DigitalInput implements DigitalInputReader { - public DigitalInput(int channel) { + public DigitalInput(final int channel) { super(channel); } } diff --git a/src/main/java/com/team766/hal/wpilib/Encoder.java b/src/main/java/com/team766/hal/wpilib/Encoder.java index 509ddee2..dffb2997 100755 --- a/src/main/java/com/team766/hal/wpilib/Encoder.java +++ b/src/main/java/com/team766/hal/wpilib/Encoder.java @@ -3,7 +3,7 @@ import com.team766.hal.EncoderReader; public class Encoder extends edu.wpi.first.wpilibj.Encoder implements EncoderReader { - public Encoder(int channelA, int channelB) { + public Encoder(final int channelA, final int channelB) { super(channelA, channelB); } } diff --git a/src/main/java/com/team766/hal/wpilib/Joystick.java b/src/main/java/com/team766/hal/wpilib/Joystick.java index b5a267f2..a2419d61 100755 --- a/src/main/java/com/team766/hal/wpilib/Joystick.java +++ b/src/main/java/com/team766/hal/wpilib/Joystick.java @@ -3,27 +3,27 @@ import com.team766.hal.JoystickReader; public class Joystick extends edu.wpi.first.wpilibj.Joystick implements JoystickReader { - public Joystick(int port) { + public Joystick(final int port) { super(port); } @Override - public double getAxis(int axis) { + public double getAxis(final int axis) { return getRawAxis(axis); } @Override - public boolean getButton(int button) { + public boolean getButton(final int button) { return getRawButton(button); } @Override - public boolean getButtonPressed(int button) { + public boolean getButtonPressed(final int button) { return getRawButtonPressed(button); } @Override - public boolean getButtonReleased(int button) { + public boolean getButtonReleased(final int button) { return getRawButtonReleased(button); } } diff --git a/src/main/java/com/team766/hal/wpilib/NavXGyro.java b/src/main/java/com/team766/hal/wpilib/NavXGyro.java index 65430501..26a07ae5 100644 --- a/src/main/java/com/team766/hal/wpilib/NavXGyro.java +++ b/src/main/java/com/team766/hal/wpilib/NavXGyro.java @@ -2,15 +2,15 @@ import com.kauailabs.navx.frc.AHRS; import com.team766.hal.GyroReader; -import com.team766.logging.Category; -import com.team766.logging.Logger; -import com.team766.logging.Severity; +// import com.team766.logging.Category; +// import com.team766.logging.Logger; +// import com.team766.logging.Severity; import edu.wpi.first.wpilibj.I2C; public class NavXGyro implements GyroReader { private AHRS m_gyro; - public NavXGyro(I2C.Port port) { + public NavXGyro(final I2C.Port port) { m_gyro = new AHRS(port); // NOTE: It takes a bit of time until the gyro reader thread updates // the connected status, so we can't check it immediately. @@ -51,5 +51,5 @@ public double getPitch() { public double getRoll() { return m_gyro.getRoll(); } - + } diff --git a/src/main/java/com/team766/hal/wpilib/PWMVictorSP.java b/src/main/java/com/team766/hal/wpilib/PWMVictorSP.java index 553cf741..ce6d809d 100755 --- a/src/main/java/com/team766/hal/wpilib/PWMVictorSP.java +++ b/src/main/java/com/team766/hal/wpilib/PWMVictorSP.java @@ -5,7 +5,7 @@ import edu.wpi.first.wpilibj.motorcontrol.VictorSP; public class PWMVictorSP extends VictorSP implements BasicMotorController { - public PWMVictorSP(int channel) { + public PWMVictorSP(final int channel) { super(channel); } diff --git a/src/main/java/com/team766/hal/wpilib/Relay.java b/src/main/java/com/team766/hal/wpilib/Relay.java index 7b9fbeec..020466e3 100755 --- a/src/main/java/com/team766/hal/wpilib/Relay.java +++ b/src/main/java/com/team766/hal/wpilib/Relay.java @@ -3,29 +3,33 @@ import com.team766.hal.RelayOutput; import com.team766.logging.Category; import com.team766.logging.Logger; +import com.team766.logging.LoggerExceptionUtils; import com.team766.logging.Severity; public class Relay extends edu.wpi.first.wpilibj.Relay implements RelayOutput { - public Relay(int channel) { + public Relay(final int channel) { super(channel); } @Override - public void set(com.team766.hal.RelayOutput.Value value) { + public void set(final com.team766.hal.RelayOutput.Value value) { edu.wpi.first.wpilibj.Relay.Value wpi_value = null; switch (value) { - case kOff: - wpi_value = edu.wpi.first.wpilibj.Relay.Value.kOff; - break; - case kOn: - wpi_value = edu.wpi.first.wpilibj.Relay.Value.kOn; - break; - case kForward: - wpi_value = edu.wpi.first.wpilibj.Relay.Value.kForward; - break; - case kReverse: - wpi_value = edu.wpi.first.wpilibj.Relay.Value.kReverse; - break; + case kOff: + wpi_value = edu.wpi.first.wpilibj.Relay.Value.kOff; + break; + case kOn: + wpi_value = edu.wpi.first.wpilibj.Relay.Value.kOn; + break; + case kForward: + wpi_value = edu.wpi.first.wpilibj.Relay.Value.kForward; + break; + case kReverse: + wpi_value = edu.wpi.first.wpilibj.Relay.Value.kReverse; + break; + default: + LoggerExceptionUtils.logException(new UnsupportedOperationException("invalid relay output provided. provided value: " + value)); + break; } if (wpi_value == null) { Logger.get(Category.HAL).logRaw( diff --git a/src/main/java/com/team766/hal/wpilib/RobotMain.java b/src/main/java/com/team766/hal/wpilib/RobotMain.java index 1459ba6b..e928f7a1 100755 --- a/src/main/java/com/team766/hal/wpilib/RobotMain.java +++ b/src/main/java/com/team766/hal/wpilib/RobotMain.java @@ -1,7 +1,7 @@ package com.team766.hal.wpilib; import java.io.File; -import java.nio.file.Files; +//import java.nio.file.Files; import java.nio.file.Path; import java.util.function.Supplier; import com.team766.config.ConfigFileReader; @@ -18,20 +18,22 @@ public class RobotMain extends TimedRobot { // this allows for the same code to be deployed to multiple physical robots, each with their own // config file with CAN bus port mappings, etc, with the actual file used for a specific robot // to be "selected" via this symlink to the actual file. - private final static String SELECTED_CONFIG_FILE = "/home/lvuser/selectedConfig.txt"; + private static final String SELECTED_CONFIG_FILE = "/home/lvuser/selectedConfig.txt"; // if the symlink (above) is not present, back off to this file in the deploy directory. - private final static String DEFAULT_CONFIG_FILE = "configs/defaultRobotConfig.txt"; + private static final String DEFAULT_CONFIG_FILE = "configs/defaultRobotConfig.txt"; - // for backwards compatibility, back off to the previous config file location if the above are not + // for backwards compatibility, back off to the previous config file location if the above are + // not // found in the deploy directory. - private final static String LEGACY_CONFIG_FILE = "/home/lvuser/robotConfig.txt"; + private static final String LEGACY_CONFIG_FILE = "/home/lvuser/robotConfig.txt"; private GenericRobotMain robot; - public static void main(String... args) { + public static void main(final String... args) { Supplier supplier = new Supplier() { RobotMain instance; + @Override public RobotMain get() { if (instance == null) { @@ -52,9 +54,9 @@ public RobotMain() { super(0.005); } - private static String checkForAndReturnPathToConfigFile(String file) { + private static String checkForAndReturnPathToConfigFile(final String file) { Path configPath = Filesystem.getDeployDirectory().toPath().resolve(file); - File configFile = configPath.toFile(); + File configFile = configPath.toFile(); if (configFile.exists()) { return configFile.getPath(); } @@ -66,7 +68,7 @@ public void robotInit() { try { String filename = null; filename = checkForAndReturnPathToConfigFile(SELECTED_CONFIG_FILE); - + if (filename == null) { filename = checkForAndReturnPathToConfigFile(DEFAULT_CONFIG_FILE); } @@ -78,7 +80,7 @@ public void robotInit() { ConfigFileReader.instance = new ConfigFileReader(filename); RobotProvider.instance = new WPIRobotProvider(); robot = new GenericRobotMain(); - + robot.robotInit(); } catch (Exception e) { e.printStackTrace(); @@ -88,19 +90,19 @@ public void robotInit() { @Override public void disabledInit() { - try{ + try { robot.disabledInit(); - }catch (Exception e){ + } catch (Exception e) { e.printStackTrace(); LoggerExceptionUtils.logException(e); } } - + @Override public void autonomousInit() { - try{ + try { robot.autonomousInit(); - }catch (Exception e){ + } catch (Exception e) { e.printStackTrace(); LoggerExceptionUtils.logException(e); } @@ -108,9 +110,9 @@ public void autonomousInit() { @Override public void teleopInit() { - try{ + try { robot.teleopInit(); - }catch (Exception e){ + } catch (Exception e) { e.printStackTrace(); LoggerExceptionUtils.logException(e); } @@ -118,10 +120,10 @@ public void teleopInit() { @Override public void disabledPeriodic() { - try{ + try { robot.disabledPeriodic(); Scheduler.getInstance().run(); - }catch (Exception e){ + } catch (Exception e) { e.printStackTrace(); LoggerExceptionUtils.logException(e); } @@ -129,10 +131,10 @@ public void disabledPeriodic() { @Override public void autonomousPeriodic() { - try{ + try { robot.autonomousPeriodic(); Scheduler.getInstance().run(); - }catch (Exception e){ + } catch (Exception e) { e.printStackTrace(); LoggerExceptionUtils.logException(e); } @@ -140,10 +142,10 @@ public void autonomousPeriodic() { @Override public void teleopPeriodic() { - try{ + try { robot.teleopPeriodic(); Scheduler.getInstance().run(); - }catch (Exception e){ + } catch (Exception e) { e.printStackTrace(); LoggerExceptionUtils.logException(e); } diff --git a/src/main/java/com/team766/hal/wpilib/Solenoid.java b/src/main/java/com/team766/hal/wpilib/Solenoid.java index e72f4694..10f5ae6e 100755 --- a/src/main/java/com/team766/hal/wpilib/Solenoid.java +++ b/src/main/java/com/team766/hal/wpilib/Solenoid.java @@ -5,7 +5,7 @@ import edu.wpi.first.wpilibj.PneumaticsModuleType; public class Solenoid extends edu.wpi.first.wpilibj.Solenoid implements SolenoidController { - public Solenoid(int channel) { + public Solenoid(final int channel) { super(PneumaticsModuleType.CTREPCM, channel); } } diff --git a/src/main/java/com/team766/hal/wpilib/SystemClock.java b/src/main/java/com/team766/hal/wpilib/SystemClock.java index de5c9d4f..6ed78cfa 100644 --- a/src/main/java/com/team766/hal/wpilib/SystemClock.java +++ b/src/main/java/com/team766/hal/wpilib/SystemClock.java @@ -1,7 +1,7 @@ package com.team766.hal.wpilib; public class SystemClock implements com.team766.hal.Clock { - + public static final SystemClock instance = new SystemClock(); @Override diff --git a/src/main/java/com/team766/hal/wpilib/WPIRobotProvider.java b/src/main/java/com/team766/hal/wpilib/WPIRobotProvider.java index 89540f83..be9bbc62 100755 --- a/src/main/java/com/team766/hal/wpilib/WPIRobotProvider.java +++ b/src/main/java/com/team766/hal/wpilib/WPIRobotProvider.java @@ -26,7 +26,6 @@ import com.team766.logging.Logger; import com.team766.logging.LoggerExceptionUtils; import com.team766.logging.Severity; -import com.team766.simulator.elements.AirCompressor; import edu.wpi.first.hal.DriverStationJNI; import edu.wpi.first.util.WPIUtilJNI; import edu.wpi.first.wpilibj.DriverStation; @@ -45,7 +44,7 @@ private static class DataRefreshRunnable implements Runnable { private final AtomicBoolean m_keepAlive = new AtomicBoolean(); private final AtomicInteger m_dataCount = new AtomicInteger(); - public DataRefreshRunnable() { + DataRefreshRunnable() { m_keepAlive.set(true); } @@ -102,8 +101,8 @@ public WPIRobotProvider() { private PneumaticsControlModule pcm = new PneumaticsControlModule(); @Override - public MotorController getMotor(int index, String configPrefix, MotorController.Type type, - ControlInputReader localSensor) { + public MotorController getMotor(final int index, final String configPrefix, + final MotorController.Type type, ControlInputReader localSensor) { if (motors[type.ordinal()][index] != null) { return motors[type.ordinal()][index]; } @@ -132,6 +131,8 @@ public MotorController getMotor(int index, String configPrefix, MotorController. motor = new LocalMotorController(configPrefix, new PWMVictorSP(index), localSensor); localSensor = null; break; + default: + break; } if (motor == null) { LoggerExceptionUtils @@ -148,16 +149,16 @@ public MotorController getMotor(int index, String configPrefix, MotorController. } @Override - public EncoderReader getEncoder(int index1, int index2) { - if(encoders[index1] == null) { + public EncoderReader getEncoder(final int index1, final int index2) { + if (encoders[index1] == null) { encoders[index1] = new Encoder(index1, index2); } return encoders[index1]; } @Override - public SolenoidController getSolenoid(int index) { - if(solenoids[index] == null) { + public SolenoidController getSolenoid(final int index) { + if (solenoids[index] == null) { solenoids[index] = new Solenoid(index); } return solenoids[index]; @@ -167,15 +168,15 @@ public SolenoidController getSolenoid(int index) { // Gyro index values: // -1 = Spartan Gyro // 0+ = Analog Gyro on port index - public GyroReader getGyro(int index) { + public GyroReader getGyro(final int index) { if (gyros[index + 2] == null) { if (index < -2) { Logger.get(Category.CONFIGURATION).logRaw(Severity.ERROR, "Invalid gyro port " + index + ". Must be -2, -1, or a non-negative integer"); return new MockGyro(); - } else if(index == -2) { + } else if (index == -2) { gyros[index + 2] = new NavXGyro(I2C.Port.kOnboard); - } else if(index == -1) { + } else if (index == -1) { gyros[index + 2] = new ADXRS450_Gyro(SPI.Port.kOnboardCS0); } else { gyros[index + 2] = new AnalogGyro(index); @@ -185,14 +186,14 @@ public GyroReader getGyro(int index) { } @Override - public CameraReader getCamera(String id, String value) { + public CameraReader getCamera(final String id, final String value) { System.err.println("Camera support not yet avaible"); return null; } @Override - public JoystickReader getJoystick(int index) { - if(joysticks[index] == null) { + public JoystickReader getJoystick(final int index) { + if (joysticks[index] == null) { joysticks[index] = new Joystick(index); } return joysticks[index]; @@ -204,7 +205,7 @@ public CameraInterface getCamServer() { } @Override - public DigitalInputReader getDigitalInput(int index) { + public DigitalInputReader getDigitalInput(final int index) { if (digInputs[index] == null) { digInputs[index] = new DigitalInput(index); } @@ -212,16 +213,16 @@ public DigitalInputReader getDigitalInput(int index) { } @Override - public AnalogInputReader getAnalogInput(int index){ - if(angInputs[index] == null) { + public AnalogInputReader getAnalogInput(final int index) { + if (angInputs[index] == null) { angInputs[index] = new AnalogInput(index); } return angInputs[index]; } @Override - public RelayOutput getRelay(int index) { - if(relays[index] == null) { + public RelayOutput getRelay(final int index) { + if (relays[index] == null) { relays[index] = new Relay(index); } return relays[index]; diff --git a/src/main/java/com/team766/library/CircularBuffer.java b/src/main/java/com/team766/library/CircularBuffer.java index d14c8fb9..c583f5b2 100644 --- a/src/main/java/com/team766/library/CircularBuffer.java +++ b/src/main/java/com/team766/library/CircularBuffer.java @@ -7,11 +7,11 @@ public class CircularBuffer extends AbstractCollection { private Object[] buffer; private int count = 0; private int headIndex = 0; - - public CircularBuffer(int bufferLength) { + + public CircularBuffer(final int bufferLength) { buffer = new Object[bufferLength]; } - + @Override public Iterator iterator() { return new Iterator() { @@ -29,7 +29,7 @@ public E next() { } }; } - + @SuppressWarnings("unchecked") public E peek() { if (count == 0) { @@ -37,7 +37,7 @@ public E peek() { } return (E) buffer[headIndex]; } - + public E poll() { if (count == 0) { return null; @@ -47,9 +47,9 @@ public E poll() { --count; return element; } - + @Override - public boolean add(E element) { + public boolean add(final E element) { if (count < buffer.length) { buffer[(headIndex + count) % buffer.length] = element; ++count; @@ -59,12 +59,12 @@ public boolean add(E element) { } return true; } - + @Override public int size() { return count; } - + @Override public void clear() { count = 0; diff --git a/src/main/java/com/team766/library/LossyPriorityQueue.java b/src/main/java/com/team766/library/LossyPriorityQueue.java index 5837bf11..c934e88b 100644 --- a/src/main/java/com/team766/library/LossyPriorityQueue.java +++ b/src/main/java/com/team766/library/LossyPriorityQueue.java @@ -14,12 +14,12 @@ public class LossyPriorityQueue { private final PriorityQueue m_items; private final int m_capacity; - public LossyPriorityQueue(int capacity, Comparator comparator) { + public LossyPriorityQueue(final int capacity, final Comparator comparator) { m_capacity = capacity; m_items = new PriorityQueue(m_capacity, comparator); } - public void add(E element) { + public void add(final E element) { m_lock.lock(); try { while (m_items.size() > m_capacity - 1) { @@ -47,7 +47,7 @@ public E poll() throws InterruptedException { m_lock.unlock(); } } - + public void waitForEmpty() throws InterruptedException { m_lock.lock(); try { diff --git a/src/main/java/com/team766/library/RateLimiter.java b/src/main/java/com/team766/library/RateLimiter.java index 371ecd54..aabfe5d1 100644 --- a/src/main/java/com/team766/library/RateLimiter.java +++ b/src/main/java/com/team766/library/RateLimiter.java @@ -6,8 +6,8 @@ public class RateLimiter { private final double periodSeconds; private double nextTime = 0; - public RateLimiter(double periodSeconds) { - this.periodSeconds = periodSeconds; + public RateLimiter(final double periodSeconds_) { + this.periodSeconds = periodSeconds_; } public boolean next() { diff --git a/src/main/java/com/team766/library/SetValueProvider.java b/src/main/java/com/team766/library/SetValueProvider.java index b751e481..8b03767f 100644 --- a/src/main/java/com/team766/library/SetValueProvider.java +++ b/src/main/java/com/team766/library/SetValueProvider.java @@ -9,7 +9,7 @@ public SetValueProvider() { m_hasValue = false; } - public SetValueProvider(E value) { + public SetValueProvider(final E value) { m_value = value; m_hasValue = true; } @@ -24,7 +24,7 @@ public boolean hasValue() { return m_hasValue; } - public void set(E value) { + public void set(final E value) { m_value = value; m_hasValue = true; } diff --git a/src/main/java/com/team766/library/SettableValueProvider.java b/src/main/java/com/team766/library/SettableValueProvider.java index 565ef7cf..54d96b1e 100644 --- a/src/main/java/com/team766/library/SettableValueProvider.java +++ b/src/main/java/com/team766/library/SettableValueProvider.java @@ -1,7 +1,7 @@ package com.team766.library; public interface SettableValueProvider extends ValueProvider { - public void set(E value); + void set(E value); - public void clear(); + void clear(); } \ No newline at end of file diff --git a/src/main/java/com/team766/library/ValueProvider.java b/src/main/java/com/team766/library/ValueProvider.java index 49ffc6a1..1d46c2ea 100644 --- a/src/main/java/com/team766/library/ValueProvider.java +++ b/src/main/java/com/team766/library/ValueProvider.java @@ -1,9 +1,9 @@ package com.team766.library; public interface ValueProvider { - public E get(); - - public boolean hasValue(); + E get(); + + boolean hasValue(); default E valueOr(E default_value) { if (hasValue()) { diff --git a/src/main/java/com/team766/logging/LogEntryComparator.java b/src/main/java/com/team766/logging/LogEntryComparator.java index b4c90ee7..42e9c7c8 100644 --- a/src/main/java/com/team766/logging/LogEntryComparator.java +++ b/src/main/java/com/team766/logging/LogEntryComparator.java @@ -15,7 +15,7 @@ class LogEntryComparator implements Comparator { .build(); @Override - public int compare(LogEntry o1, LogEntry o2) { + public int compare(final LogEntry o1, final LogEntry o2) { // Sort by highest severity first int severityResult = -o1.getSeverity().compareTo(o2.getSeverity()); if (severityResult != 0) { diff --git a/src/main/java/com/team766/logging/LogEntryRenderer.java b/src/main/java/com/team766/logging/LogEntryRenderer.java index 29c10021..83eb89bf 100644 --- a/src/main/java/com/team766/logging/LogEntryRenderer.java +++ b/src/main/java/com/team766/logging/LogEntryRenderer.java @@ -1,7 +1,7 @@ package com.team766.logging; public class LogEntryRenderer { - public static String renderLogEntry(LogEntry entry, LogReader reader) { + public static String renderLogEntry(final LogEntry entry, final LogReader reader) { String message = entry.hasMessageStr() ? entry.getMessageStr() : reader.getFormatString(entry.getMessageIndex()); final int argCount = entry.getArgCount(); diff --git a/src/main/java/com/team766/logging/LogReader.java b/src/main/java/com/team766/logging/LogReader.java index 2bfbc05f..7d3281fb 100644 --- a/src/main/java/com/team766/logging/LogReader.java +++ b/src/main/java/com/team766/logging/LogReader.java @@ -13,13 +13,13 @@ public class LogReader { private LogEntry.Builder m_entryBuilder; private ArrayList m_formatStrings; - public LogReader(String filename) throws IOException { + public LogReader(final String filename) throws IOException { m_fileStream = new FileInputStream(filename); m_dataStream = CodedInputStream.newInstance(m_fileStream); m_entryBuilder = LogEntry.newBuilder(); m_formatStrings = new ArrayList(); } - + public LogEntry readNext() throws IOException { m_entryBuilder.clear(); m_dataStream.readMessage(m_entryBuilder, ExtensionRegistryLite.getEmptyRegistry()); @@ -35,8 +35,8 @@ public LogEntry readNext() throws IOException { } return entry; } - - String getFormatString(int index) { + + String getFormatString(final int index) { String str; try { str = m_formatStrings.get(index); diff --git a/src/main/java/com/team766/logging/LogWriter.java b/src/main/java/com/team766/logging/LogWriter.java index 4cd06718..8e7970ce 100644 --- a/src/main/java/com/team766/logging/LogWriter.java +++ b/src/main/java/com/team766/logging/LogWriter.java @@ -8,20 +8,20 @@ public class LogWriter { private static final int QUEUE_SIZE = 50; - + private LossyPriorityQueue m_entriesQueue; - + private Thread m_workerThread; private boolean m_running = true; - + private HashMap m_formatStringIndices = new HashMap(); - + private FileOutputStream m_fileStream; private CodedOutputStream m_dataStream; - + private Severity m_minSeverity = Severity.INFO; - - public LogWriter(String filename) throws IOException { + + public LogWriter(final String filename) throws IOException { m_entriesQueue = new LossyPriorityQueue(QUEUE_SIZE, new LogEntryComparator()); m_fileStream = new FileOutputStream(filename); m_dataStream = CodedOutputStream.newInstance(m_fileStream); @@ -43,9 +43,8 @@ public void run() { m_dataStream.writeMessageNoTag(entry); } catch (IOException e) { e.printStackTrace(); - Logger.get(Category.JAVA_EXCEPTION).logOnlyInMemory( - Severity.ERROR, - LoggerExceptionUtils.exceptionToString(e)); + Logger.get(Category.JAVA_EXCEPTION).logOnlyInMemory(Severity.ERROR, + LoggerExceptionUtils.exceptionToString(e)); } } } @@ -67,17 +66,18 @@ public void close() throws IOException, InterruptedException { m_fileStream.close(); } - - public void setSeverityFilter(Severity threshold) { + + public void setSeverityFilter(final Severity threshold) { m_minSeverity = threshold; } - - public void logStoredFormat(LogEntry.Builder entry) { + + public void logStoredFormat(final LogEntry.Builder entry) { if (entry.getSeverity().compareTo(m_minSeverity) < 0) { return; } if (!m_running) { - System.out.println("Log message during shutdown: " + LogEntryRenderer.renderLogEntry(entry.build(), null)); + System.out.println("Log message during shutdown: " + + LogEntryRenderer.renderLogEntry(entry.build(), null)); return; } final String format = entry.getMessageStr(); @@ -86,7 +86,8 @@ public void logStoredFormat(LogEntry.Builder entry) { index = m_formatStringIndices.size() + 1; m_formatStringIndices.put(format, index); if (m_formatStringIndices.size() % 100 == 0) { - System.out.println("You're logging a lot of unique messages. Please switch to using logRaw()"); + System.out.println( + "You're logging a lot of unique messages. Please switch to using logRaw()"); } } else { entry.clearMessageStr(); @@ -95,7 +96,7 @@ public void logStoredFormat(LogEntry.Builder entry) { m_entriesQueue.add(entry.build()); } - public void log(LogEntry entry) { + public void log(final LogEntry entry) { if (entry.getSeverity().compareTo(m_minSeverity) < 0) { return; } diff --git a/src/main/java/com/team766/logging/Loggable.java b/src/main/java/com/team766/logging/Loggable.java index 14bf6e7d..d25d1df5 100644 --- a/src/main/java/com/team766/logging/Loggable.java +++ b/src/main/java/com/team766/logging/Loggable.java @@ -1,5 +1,5 @@ package com.team766.logging; public interface Loggable { - public abstract void toLogValue(LogValue.Builder value); + void toLogValue(LogValue.Builder value); } \ No newline at end of file diff --git a/src/main/java/com/team766/logging/Logger.java b/src/main/java/com/team766/logging/Logger.java index 473dd5d4..17607b84 100644 --- a/src/main/java/com/team766/logging/Logger.java +++ b/src/main/java/com/team766/logging/Logger.java @@ -10,9 +10,9 @@ import com.team766.config.ConfigFileReader; import com.team766.library.CircularBuffer; -public class Logger { +public final class Logger { private static class LogUncaughtException implements Thread.UncaughtExceptionHandler { - public void uncaughtException(Thread t, Throwable e) { + public void uncaughtException(final Thread t, final Throwable e) { e.printStackTrace(); LoggerExceptionUtils.logException(e); @@ -30,15 +30,17 @@ public void uncaughtException(Thread t, Throwable e) { } private static final int MAX_NUM_RECENT_ENTRIES = 100; - - private static EnumMap m_loggers = new EnumMap(Category.class); + + private static EnumMap m_loggers = + new EnumMap(Category.class); private static LogWriter m_logWriter = null; - private CircularBuffer m_recentEntries = new CircularBuffer(MAX_NUM_RECENT_ENTRIES); + private CircularBuffer m_recentEntries = + new CircularBuffer(MAX_NUM_RECENT_ENTRIES); private static Object s_lastWriteTimeSync = new Object(); private static long s_lastWriteTime = 0L; public static String logFilePathBase = null; - + static { for (Category category : Category.values()) { m_loggers.put(category, new Logger(category)); @@ -48,12 +50,14 @@ public void uncaughtException(Thread t, Throwable e) { if (config_file != null) { logFilePathBase = config_file.getString("logFilePath").get(); new File(logFilePathBase).mkdirs(); - final String timestamp = new SimpleDateFormat("yyyyMMdd'T'HHmmss").format(new Date()); + final String timestamp = + new SimpleDateFormat("yyyyMMdd'T'HHmmss").format(new Date()); final String logFilePath = new File(logFilePathBase, timestamp).getAbsolutePath(); m_logWriter = new LogWriter(logFilePath); get(Category.CONFIGURATION).logRaw(Severity.INFO, "Logging to " + logFilePath); } else { - get(Category.CONFIGURATION).logRaw(Severity.ERROR, "Config file is not available. Logs will only be in-memory and will be lost when the robot is turned off."); + get(Category.CONFIGURATION).logRaw(Severity.ERROR, + "Config file is not available. Logs will only be in-memory and will be lost when the robot is turned off."); } } catch (Exception e) { e.printStackTrace(); @@ -62,14 +66,14 @@ public void uncaughtException(Thread t, Throwable e) { Thread.setDefaultUncaughtExceptionHandler(new LogUncaughtException()); } - - public static Logger get(Category category) { + + public static Logger get(final Category category) { return m_loggers.get(category); } static long getTime() { long nowNanosec = new Date().getTime() * 1000000; - synchronized(s_lastWriteTimeSync) { + synchronized (s_lastWriteTimeSync) { // Ensure that log entries' timestamps are unique. This is important // because the log viewer uses an entry's timestamp as a unique ID, // and we don't want two different log entries to accidentally @@ -78,26 +82,22 @@ static long getTime() { } return nowNanosec; } - + private final Category m_category; - - private Logger(Category category) { + + private Logger(final Category category) { m_category = category; } - + public Collection recentEntries() { return Collections.unmodifiableCollection(m_recentEntries); } - - public void logData(Severity severity, String format, Object... args) { - var entry = LogEntry.newBuilder() - .setTime(getTime()) - .setSeverity(severity) + + public void logData(final Severity severity, final String format, final Object... args) { + var entry = LogEntry.newBuilder().setTime(getTime()).setSeverity(severity) .setCategory(m_category); - { - entry.setMessageStr(String.format(format, args)); - m_recentEntries.add(entry.build()); - } + entry.setMessageStr(String.format(format, args)); + m_recentEntries.add(entry.build()); entry.setMessageStr(format); for (Object arg : args) { SerializationUtils.valueToProto(arg, entry.addArgBuilder()); @@ -106,21 +106,17 @@ public void logData(Severity severity, String format, Object... args) { m_logWriter.logStoredFormat(entry); } } - - public void logRaw(Severity severity, String message) { - var entry = LogEntry.newBuilder() - .setTime(getTime()) - .setSeverity(severity) - .setCategory(m_category) - .setMessageStr(message) - .build(); + + public void logRaw(final Severity severity, final String message) { + var entry = LogEntry.newBuilder().setTime(getTime()).setSeverity(severity) + .setCategory(m_category).setMessageStr(message).build(); m_recentEntries.add(entry); if (m_logWriter != null) { m_logWriter.log(entry); } } - void logOnlyInMemory(Severity severity, String message) { + void logOnlyInMemory(final Severity severity, final String message) { var entry = LogEntry.newBuilder() .setTime(getTime()) .setSeverity(severity) diff --git a/src/main/java/com/team766/logging/LoggerExceptionUtils.java b/src/main/java/com/team766/logging/LoggerExceptionUtils.java index 2f13388a..3db06cfa 100644 --- a/src/main/java/com/team766/logging/LoggerExceptionUtils.java +++ b/src/main/java/com/team766/logging/LoggerExceptionUtils.java @@ -4,7 +4,7 @@ import java.io.StringWriter; public class LoggerExceptionUtils { - public static String exceptionToString(Throwable e) { + public static String exceptionToString(final Throwable e) { StringWriter sw = new StringWriter(); PrintWriter pw = new PrintWriter(sw); pw.print("Uncaught exception: "); @@ -13,7 +13,7 @@ public static String exceptionToString(Throwable e) { return sw.toString(); } - public static String logException(Throwable e) { + public static String logException(final Throwable e) { String str = exceptionToString(e); try { Logger.get(Category.JAVA_EXCEPTION).logRaw(Severity.ERROR, str); diff --git a/src/main/java/com/team766/logging/SerializationUtils.java b/src/main/java/com/team766/logging/SerializationUtils.java index ac6b7997..7cf79408 100644 --- a/src/main/java/com/team766/logging/SerializationUtils.java +++ b/src/main/java/com/team766/logging/SerializationUtils.java @@ -1,34 +1,32 @@ package com.team766.logging; public class SerializationUtils { - public static void valueToProto(Object object, LogValue.Builder value) { - if (object instanceof Byte || - object instanceof Short || - object instanceof Integer || - object instanceof Long) { - value.setIntValue(((Number)object).longValue()); + public static void valueToProto(final Object object, final LogValue.Builder value) { + if (object instanceof Byte || object instanceof Short || object instanceof Integer + || object instanceof Long) { + value.setIntValue(((Number) object).longValue()); } else if (object instanceof Character) { - value.setStringValue(((Character)object).toString()); + value.setStringValue(((Character) object).toString()); } else if (object instanceof Number) { // If object is a Number but not one of the integer types, treat it // as a double (this primarily handles Float and Double values, but // also handles any weird other type that might inherit from Number) - value.setFloatValue(((Number)object).doubleValue()); + value.setFloatValue(((Number) object).doubleValue()); } else if (object instanceof Boolean) { - value.setBoolValue(((Boolean)object).booleanValue()); + value.setBoolValue(((Boolean) object).booleanValue()); } else if (object instanceof String) { - value.setStringValue((String)object); + value.setStringValue((String) object); } else if (object == null) { value.clearKind(); } else if (object instanceof Loggable) { - ((Loggable)object).toLogValue(value); + ((Loggable) object).toLogValue(value); } else { throw new IllegalArgumentException( - "Value of type " + object.getClass().getName() + " isn't loggable"); + "Value of type " + object.getClass().getName() + " isn't loggable"); } } - public static Object protoToValue(LogValue value) { + public static Object protoToValue(final LogValue value) { switch (value.getKindCase()) { case KIND_NOT_SET: return null; @@ -40,9 +38,11 @@ public static Object protoToValue(LogValue value) { return value.getIntValue(); case LIST: return value.getList().getElementList().stream() - .map(SerializationUtils::protoToValue).toArray(); + .map(SerializationUtils::protoToValue).toArray(); case STRING_VALUE: return value.getStringValue(); + default: + break; } throw new IllegalArgumentException( "Unsupported LogValue kind: " + value.getKindCase()); diff --git a/src/main/java/com/team766/math/Algebraic.java b/src/main/java/com/team766/math/Algebraic.java index 3bce828d..6a863f85 100644 --- a/src/main/java/com/team766/math/Algebraic.java +++ b/src/main/java/com/team766/math/Algebraic.java @@ -1,7 +1,7 @@ package com.team766.math; public interface Algebraic> { - public E add(E b); - - public E scale(double b); + E add(E b); + + E scale(double b); } diff --git a/src/main/java/com/team766/math/Filter.java b/src/main/java/com/team766/math/Filter.java index 146980b5..fa15547e 100644 --- a/src/main/java/com/team766/math/Filter.java +++ b/src/main/java/com/team766/math/Filter.java @@ -1,7 +1,7 @@ package com.team766.math; public interface Filter { - public void push(double sample); - - public double getValue(); + void push(double sample); + + double getValue(); } diff --git a/src/main/java/com/team766/math/FirFilter.java b/src/main/java/com/team766/math/FirFilter.java index 4bad9289..af69ff99 100644 --- a/src/main/java/com/team766/math/FirFilter.java +++ b/src/main/java/com/team766/math/FirFilter.java @@ -6,15 +6,15 @@ public class FirFilter implements Filter { private CircularBuffer buffer; - - public FirFilter(int bufferLength) { + + public FirFilter(final int bufferLength) { buffer = new CircularBuffer<>(bufferLength); } - - public void push(double sample) { + + public void push(final double sample) { buffer.add(sample); } - + public double getValue() { return buffer.stream().collect(Collectors.averagingDouble(Double::doubleValue)); } diff --git a/src/main/java/com/team766/math/IirFilter.java b/src/main/java/com/team766/math/IirFilter.java index ac146be4..ab965b95 100644 --- a/src/main/java/com/team766/math/IirFilter.java +++ b/src/main/java/com/team766/math/IirFilter.java @@ -3,24 +3,24 @@ public class IirFilter implements Filter { private double decay; private double value; - - public IirFilter(double decay, double initialValue) { - this.decay = decay; - this.value = initialValue; + + public IirFilter(final double decay_, final double initialValue_) { + this.decay = decay_; + this.value = initialValue_; if (decay > 1.0 || decay <= 0.0) { throw new IllegalArgumentException("decay should be in (0.0, 1.0]"); } } - - public IirFilter(double decay) { - this(decay, 0.0); + + public IirFilter(final double decay_) { + this(decay_, 0.0); } - - public void push(double sample) { + + public void push(final double sample) { value *= (1.0 - decay); value += sample * decay; } - + public double getValue() { return value; } diff --git a/src/main/java/com/team766/math/IsometricTransform.java b/src/main/java/com/team766/math/IsometricTransform.java index dc75c294..fed3e275 100644 --- a/src/main/java/com/team766/math/IsometricTransform.java +++ b/src/main/java/com/team766/math/IsometricTransform.java @@ -7,33 +7,34 @@ public class IsometricTransform { public final Rotation rotation; public final Vector3D translation; - + public static final IsometricTransform IDENTITY = new IsometricTransform(Rotation.IDENTITY, Vector3D.ZERO); - - public IsometricTransform(Rotation rotation, Vector3D translation) { - this.rotation = rotation; - this.translation = translation; + + public IsometricTransform(final Rotation rotation_, final Vector3D translation_) { + this.rotation = rotation_; + this.translation = translation_; } - - Vector3D applyInverseTo(Vector3D u) { + + Vector3D applyInverseTo(final Vector3D u) { return rotation.applyInverseTo(u.subtract(translation)); } - - Vector3D applyTo(Vector3D u) { + + Vector3D applyTo(final Vector3D u) { return rotation.applyTo(u).add(translation); } - - IsometricTransform compose(IsometricTransform other) { - return new IsometricTransform(rotation.compose(other.rotation, RotationConvention.VECTOR_OPERATOR), - rotation.applyTo(other.translation).add(translation)); + + IsometricTransform compose(final IsometricTransform other) { + return new IsometricTransform( + rotation.compose(other.rotation, RotationConvention.VECTOR_OPERATOR), + rotation.applyTo(other.translation).add(translation)); } - - IsometricTransform composeInverse(IsometricTransform other) { + + IsometricTransform composeInverse(final IsometricTransform other) { return new IsometricTransform(rotation.composeInverse(other.rotation, RotationConvention.VECTOR_OPERATOR), rotation.applyInverseTo(other.translation).subtract(translation)); } - + IsometricTransform invert() { return new IsometricTransform(rotation.revert(), rotation.applyInverseTo(translation)); } diff --git a/src/main/java/com/team766/math/LinearInterpolation.java b/src/main/java/com/team766/math/LinearInterpolation.java index 41a1f2a8..6cc25766 100644 --- a/src/main/java/com/team766/math/LinearInterpolation.java +++ b/src/main/java/com/team766/math/LinearInterpolation.java @@ -8,7 +8,7 @@ private static class LerpArgs { public E b; public double t; } - + private static LerpArgs getArgs(double[] t, E[] x, double q) { if (t.length != x.length) { throw new IllegalArgumentException("Keys and values must have the same length"); @@ -40,12 +40,12 @@ private static LerpArgs getArgs(double[] t, E[] x, double q) { args.b = x[upper]; return args; } - + public static double get(double[] t, Double[] x, double q) { LerpArgs args = getArgs(t, x, q); return args.a * (1 - args.t) + (args.b * args.t); } - + public static > E get(double[] t, E[] x, double q) { LerpArgs args = getArgs(t, x, q); return args.a.scale(1 - args.t).add(args.b.scale(args.t)); diff --git a/src/main/java/com/team766/math/Math.java b/src/main/java/com/team766/math/Math.java index 84b109d9..c62fe32d 100644 --- a/src/main/java/com/team766/math/Math.java +++ b/src/main/java/com/team766/math/Math.java @@ -1,9 +1,13 @@ package com.team766.math; public class Math { - public static double clamp(double x, double min, double max) { - if (x < min) return min; - if (x > max) return max; + public static double clamp(final double x, final double min, final double max) { + if (x < min) { + return min; + } + if (x > max) { + return max; + } return x; } diff --git a/src/main/java/com/team766/math/TransformTree.java b/src/main/java/com/team766/math/TransformTree.java index 6e73823e..0cd7e50f 100644 --- a/src/main/java/com/team766/math/TransformTree.java +++ b/src/main/java/com/team766/math/TransformTree.java @@ -5,42 +5,45 @@ public class TransformTree { private ArrayList tree; - + private final String name; private TransformTree parent; private IsometricTransform transform; - - public TransformTree(String rootName) { + + public TransformTree(final String rootName) { this.name = rootName; } - - private TransformTree(String name, TransformTree parent) { - this.name = name; - this.parent = parent; + + private TransformTree(final String name_, final TransformTree parent_) { + this.name = name_; + this.parent = parent_; } - - public TransformTree addSubordinateTransform(String name) { - TransformTree subtree = new TransformTree(name, this); + + public TransformTree addSubordinateTransform(final String name_) { + TransformTree subtree = new TransformTree(name_, this); tree.add(subtree); return subtree; } - - public void setLocalTransform(IsometricTransform xf) { + + public void setLocalTransform(final IsometricTransform xf) { transform = xf; } + public IsometricTransform getLocalTransform() { return transform; } - - public IsometricTransform getTransformRelativeTo(String name) { + + public IsometricTransform getTransformRelativeTo(final String name_) { TransformTree other = getRoot().findTransform(name); if (other == null) { - throw new IllegalArgumentException("Can't find a transform named " + name); + throw new IllegalArgumentException("Can't find a transform named " + name_); } return getTransformRelativeTo(other); } - public IsometricTransform getTransformRelativeTo(TransformTree other) { - Hashtable parentChain = new Hashtable(); + + public IsometricTransform getTransformRelativeTo(final TransformTree other) { + Hashtable parentChain = + new Hashtable(); IsometricTransform xf = transform; parentChain.put(name, xf); TransformTree iterator = this.parent; @@ -59,20 +62,20 @@ public IsometricTransform getTransformRelativeTo(TransformTree other) { } throw new IllegalArgumentException("Transforms aren't part of the same tree"); } - - public TransformTree findTransform(String name) { - if (this.name == name) { + + public TransformTree findTransform(final String name_) { + if (this.name == name_) { return this; } for (TransformTree sub : tree) { - TransformTree subResult = sub.findTransform(name); + TransformTree subResult = sub.findTransform(name_); if (subResult != null) { return subResult; } } return null; } - + private TransformTree getRoot() { TransformTree iterator = this; while (iterator.parent != null) { diff --git a/src/main/java/com/team766/math/Vector3.java b/src/main/java/com/team766/math/Vector3.java index 0cd38152..b31fa8f2 100644 --- a/src/main/java/com/team766/math/Vector3.java +++ b/src/main/java/com/team766/math/Vector3.java @@ -5,54 +5,52 @@ public class Vector3 implements Algebraic { public static final Vector3 UNIT_X = new Vector3(1, 0, 0); public static final Vector3 UNIT_Y = new Vector3(0, 1, 0); public static final Vector3 UNIT_Z = new Vector3(0, 0, 1); - + public final double x; public final double y; public final double z; - - public Vector3(double x, double y, double z) { - this.x = x; - this.y = y; - this.z = z; - } - - public Vector3(Vector3 other) { + + public Vector3(final double x_, final double y_, final double z_) { + this.x = x_; + this.y = y_; + this.z = z_; + } + + public Vector3(final Vector3 other) { this.x = other.x; this.y = other.y; this.z = other.z; } - - public Vector3 add(Vector3 b) { + + public Vector3 add(final Vector3 b) { return new Vector3(x + b.x, y + b.y, z + b.z); } - - public Vector3 subtract(Vector3 b) { + + public Vector3 subtract(final Vector3 b) { return new Vector3(x - b.x, y - b.y, z - b.z); } - - public double dot(Vector3 b) { + + public double dot(final Vector3 b) { return x * b.x + y * b.y + z * b.z; } - - public Vector3 cross(Vector3 b) { - return new Vector3(y * b.z - z * b.y, - z * b.x - x * b.z, - x * b.y - y * b.x); + + public Vector3 cross(final Vector3 b) { + return new Vector3(y * b.z - z * b.y, z * b.x - x * b.z, x * b.y - y * b.x); } - - public Vector3 scale(double b) { + + public Vector3 scale(final double b) { return new Vector3(x * b, y * b, z * b); } - + @Override - public boolean equals(Object other) { + public boolean equals(final Object other) { if (!(other instanceof Vector3)) { return false; } - Vector3 otherVector = (Vector3)other; + Vector3 otherVector = (Vector3) other; return x != otherVector.x || y != otherVector.y || z != otherVector.z; } - + @Override public String toString() { return String.format("[%s, %s, %s]", x, y, z); diff --git a/src/main/java/com/team766/robot/OI.java b/src/main/java/com/team766/robot/OI.java index b33f97e4..d7f65d05 100644 --- a/src/main/java/com/team766/robot/OI.java +++ b/src/main/java/com/team766/robot/OI.java @@ -16,7 +16,7 @@ public class OI extends Procedure { private JoystickReader joystick0; private JoystickReader joystick1; private JoystickReader joystick2; - + public OI() { loggerCategory = Category.OPERATOR_INTERFACE; @@ -24,8 +24,8 @@ public OI() { joystick1 = RobotProvider.instance.getJoystick(1); joystick2 = RobotProvider.instance.getJoystick(2); } - - public void run(Context context) { + + public void run(final Context context) { while (true) { // wait for driver station data (and refresh it using the WPILib APIs) context.waitFor(() -> RobotProvider.instance.hasNewDriverStationData()); diff --git a/src/main/java/com/team766/robot/Robot.java b/src/main/java/com/team766/robot/Robot.java index b2b3c2a7..89ef434d 100644 --- a/src/main/java/com/team766/robot/Robot.java +++ b/src/main/java/com/team766/robot/Robot.java @@ -4,10 +4,9 @@ public class Robot { // Declare mechanisms here - + public static void robotInit() { // Initialize mechanisms here - } } diff --git a/src/main/java/com/team766/robot/mechanisms/ExampleMechanism.java b/src/main/java/com/team766/robot/mechanisms/ExampleMechanism.java index 75f24df9..b80cd9e4 100644 --- a/src/main/java/com/team766/robot/mechanisms/ExampleMechanism.java +++ b/src/main/java/com/team766/robot/mechanisms/ExampleMechanism.java @@ -13,7 +13,7 @@ public ExampleMechanism() { rightMotor = RobotProvider.instance.getMotor("exampleMechanism.rightMotor"); } - public void setMotorPower(double leftPower, double rightPower){ + public void setMotorPower(final double leftPower, final double rightPower) { checkContextOwnership(); leftMotor.set(leftPower); diff --git a/src/main/java/com/team766/robot/procedures/DoNothing.java b/src/main/java/com/team766/robot/procedures/DoNothing.java index 566ad756..9f5c5c4a 100644 --- a/src/main/java/com/team766/robot/procedures/DoNothing.java +++ b/src/main/java/com/team766/robot/procedures/DoNothing.java @@ -5,7 +5,7 @@ public class DoNothing extends Procedure { - public void run(Context context) { + public void run(final Context context) { } - + } \ No newline at end of file diff --git a/src/main/java/com/team766/simulator/ElectricalSystem.java b/src/main/java/com/team766/simulator/ElectricalSystem.java index 398d497b..b6ded9f6 100644 --- a/src/main/java/com/team766/simulator/ElectricalSystem.java +++ b/src/main/java/com/team766/simulator/ElectricalSystem.java @@ -7,19 +7,19 @@ public class ElectricalSystem { private double nominalVoltage = Parameters.BATTERY_VOLTAGE; private double primaryResistance = Parameters.PRIMARY_ELECTRICAL_RESISTANCE; - + private ArrayList branchCircuits = new ArrayList(); - + private ElectricalDevice.Input systemState; - + public ElectricalSystem() { systemState = new ElectricalDevice.Input(nominalVoltage); } - - public void addDevice(ElectricalDevice device) { + + public void addDevice(final ElectricalDevice device) { branchCircuits.add(device); } - + public void step() { double current = 0.0; for (ElectricalDevice device : branchCircuits) { @@ -28,7 +28,7 @@ public void step() { } systemState = new ElectricalDevice.Input(Math.max(0, nominalVoltage - primaryResistance * current)); } - + public double getSystemVoltage() { return systemState.voltage; } diff --git a/src/main/java/com/team766/simulator/Parameters.java b/src/main/java/com/team766/simulator/Parameters.java index 0a226972..2e8cc4a6 100644 --- a/src/main/java/com/team766/simulator/Parameters.java +++ b/src/main/java/com/team766/simulator/Parameters.java @@ -6,22 +6,22 @@ public class Parameters { // Robot mode to run in the simulator public static final ProgramInterface.RobotMode INITIAL_ROBOT_MODE = ProgramInterface.RobotMode.AUTON; - + public static final double BATTERY_VOLTAGE = 12.6; // volts public static final double PRIMARY_ELECTRICAL_RESISTANCE = 0.018 + 0.01; // ohms - + public static final double STARTING_PRESSURE = 0; // pascals (relative); 120 psi = 827370.875 pascals - + public static final double DRIVE_WHEEL_DIAMETER = 0.1524; // 6 inches in meters public static final double DRIVE_GEAR_RATIO = 8.0; public static final int NUM_LOADED_WHEELS = 2; public static final int ENCODER_TICKS_PER_REVOLUTION = 256; - + public static final double ROBOT_MASS = 66; // approx. 145 lbs in kg public static final double ROBOT_LENGTH = 1.0; // meters public static final double ROBOT_WIDTH = 0.8; // meters - public static final double ROBOT_MOMENT_OF_INERTIA = 1.0/12.0 * ROBOT_MASS * (ROBOT_WIDTH*ROBOT_WIDTH + ROBOT_LENGTH*ROBOT_LENGTH); - + public static final double ROBOT_MOMENT_OF_INERTIA = 1.0 / 12.0 * ROBOT_MASS * (ROBOT_WIDTH * ROBOT_WIDTH + ROBOT_LENGTH * ROBOT_LENGTH); + public static final double WHEEL_COEFFICIENT_OF_FRICTION = 1.1; public static final double ROLLING_RESISTANCE = 0.09; public static final double TURNING_RESISTANCE_FACTOR = 0.15; diff --git a/src/main/java/com/team766/simulator/PhysicalConstants.java b/src/main/java/com/team766/simulator/PhysicalConstants.java index bcba78d5..79355837 100644 --- a/src/main/java/com/team766/simulator/PhysicalConstants.java +++ b/src/main/java/com/team766/simulator/PhysicalConstants.java @@ -2,6 +2,6 @@ public class PhysicalConstants { public static final double GRAVITY_ACCELERATION = 9.81; // m/s^2 - + public static final double ATMOSPHERIC_PRESSURE = 101325; // Pascals } diff --git a/src/main/java/com/team766/simulator/PneumaticsSystem.java b/src/main/java/com/team766/simulator/PneumaticsSystem.java index 768b8aba..321e6f44 100644 --- a/src/main/java/com/team766/simulator/PneumaticsSystem.java +++ b/src/main/java/com/team766/simulator/PneumaticsSystem.java @@ -6,25 +6,25 @@ public class PneumaticsSystem { public static final double PSI_TO_PASCALS = 6894.75729; - + private static class BranchCircuit { public PneumaticDevice device; public double regulatedPressure; } - + private ArrayList branchCircuits = new ArrayList(); - + private double systemPressure = Parameters.STARTING_PRESSURE; private double compressedAirVolume = 0.0; private boolean initialized = false; - - public void addDevice(PneumaticDevice device, double regulatedPressure) { + + public void addDevice(final PneumaticDevice device, final double regulatedPressure) { BranchCircuit circuit = new BranchCircuit(); circuit.device = device; circuit.regulatedPressure = regulatedPressure; branchCircuits.add(circuit); } - + public void step() { double flowVolume = 0.0; double systemVolume = 0.0; @@ -47,11 +47,11 @@ public void step() { } systemPressure = compressedAirVolume / systemVolume * PhysicalConstants.ATMOSPHERIC_PRESSURE - PhysicalConstants.ATMOSPHERIC_PRESSURE; } - + public double getSystemPressure() { return systemPressure; } - + // Simulate the system venting all of its compressed air (e.g. someone opened the release valve; // to simulate the pneumatics system becoming compromised, call this method on every simulation tick) public void ventPressure() { diff --git a/src/main/java/com/team766/simulator/Program.java b/src/main/java/com/team766/simulator/Program.java index c83d2cb0..e91b8b15 100644 --- a/src/main/java/com/team766/simulator/Program.java +++ b/src/main/java/com/team766/simulator/Program.java @@ -1,7 +1,7 @@ package com.team766.simulator; public interface Program { - public void step(); + void step(); - public void reset(); + void reset(); } diff --git a/src/main/java/com/team766/simulator/ProgramInterface.java b/src/main/java/com/team766/simulator/ProgramInterface.java index fea9d5bc..3e219b3d 100644 --- a/src/main/java/com/team766/simulator/ProgramInterface.java +++ b/src/main/java/com/team766/simulator/ProgramInterface.java @@ -6,19 +6,19 @@ public class ProgramInterface { public static Program program = null; - + public static double simulationTime; public static int driverStationUpdateNumber = 0; - public static enum RobotMode { + public enum RobotMode { DISABLED, AUTON, TELEOP } public static RobotMode robotMode = Parameters.INITIAL_ROBOT_MODE; - + public static final double[] pwmChannels = new double[20]; - + public static class CANMotorControllerCommand { public enum ControlMode { PercentOutput, @@ -32,7 +32,7 @@ public enum ControlMode { Voltage, Disabled, } - + public double output; public ControlMode controlMode; } @@ -44,18 +44,18 @@ public static class CANMotorControllerCommunication { public final CANMotorControllerCommand command = new CANMotorControllerCommand(); public final CANMotorControllerStatus status = new CANMotorControllerStatus(); } - + public static final CANMotorControllerCommunication[] canMotorControllerChannels = initializeArray(256, CANMotorControllerCommunication.class); - + public static final double[] analogChannels = new double[20]; - + public static final boolean[] digitalChannels = new boolean[20]; - + public static final int[] relayChannels = new int[20]; - + public static final boolean[] solenoidChannels = new boolean[20]; - + public static class EncoderChannel { public long distance = 0; public double rate = 0; @@ -63,14 +63,14 @@ public static class EncoderChannel { public static final EncoderChannel[] encoderChannels = initializeArray(20, EncoderChannel.class); - + public static class GyroCommunication { public double angle; // Yaw angle (accumulative) public double rate; // Yaw rate public double pitch; public double roll; } - + public static final GyroCommunication gyro = new GyroCommunication(); public static class RobotPosition { @@ -84,12 +84,12 @@ public static class RobotPosition { public static final int NUM_BEACONS = 8; public static BeaconReader.BeaconPose[] beacons = initializeArray(NUM_BEACONS, BeaconReader.BeaconPose.class); - + public static final MockJoystick[] joystickChannels = initializeArray(6, MockJoystick.class); - - - private static E[] initializeArray(int size, Class clazz) { + + + private static E[] initializeArray(final int size, final Class clazz) { @SuppressWarnings("unchecked") E[] array = (E[]) Array.newInstance(clazz, size); for (int i = 0; i < size; ++i) { diff --git a/src/main/java/com/team766/simulator/Simulator.java b/src/main/java/com/team766/simulator/Simulator.java index 792ae667..61b9049c 100644 --- a/src/main/java/com/team766/simulator/Simulator.java +++ b/src/main/java/com/team766/simulator/Simulator.java @@ -16,30 +16,30 @@ public class Simulator implements Runnable { private PneumaticsSystem pneumaticsSystem = new PneumaticsSystem(); private WestCoastDrive drive = new WestCoastDrive(electricalSystem); private AirCompressor compressor = new AirCompressor(); - + private double time; private ArrayList metrics = new ArrayList(); private ArrayList trajectory = new ArrayList(); - + public Simulator() { electricalSystem.addDevice(compressor); pneumaticsSystem.addDevice(compressor, 120 * PneumaticsSystem.PSI_TO_PASCALS); pneumaticsSystem.addDevice(new AirReservoir(0.000574), 120 * PneumaticsSystem.PSI_TO_PASCALS); // 574 mL pneumaticsSystem.addDevice(new AirReservoir(0.000574), 120 * PneumaticsSystem.PSI_TO_PASCALS); // 574 mL } - + public void step() { time += Parameters.TIME_STEP; ProgramInterface.simulationTime = time; - + electricalSystem.step(); pneumaticsSystem.step(); drive.step(); - + if (ProgramInterface.program != null) { ProgramInterface.program.step(); } - + metrics.add(new Double[] { time, drive.getPosition().getX(), @@ -58,7 +58,7 @@ public void step() { drive.getLinearVelocity().getY(), }); } - + public void run() { metrics.clear(); time = 0.0; diff --git a/src/main/java/com/team766/simulator/elements/AirCompressor.java b/src/main/java/com/team766/simulator/elements/AirCompressor.java index febca8b3..1a38a489 100644 --- a/src/main/java/com/team766/simulator/elements/AirCompressor.java +++ b/src/main/java/com/team766/simulator/elements/AirCompressor.java @@ -12,29 +12,29 @@ public class AirCompressor implements ElectricalDevice, PneumaticDevice { private static final double CFM_TO_M3_PER_SEC = 0.000471947443; - + // Values for http://www.andymark.com/product-p/am-2005.htm private static final double NOMINAL_VOLTAGE = 12; - private static final double[] PRESSURES_PSI = { 0., 10., 20., 30., 40., 50., 60., 70., 80., 90., 100., 110. }; - private static final double[] FLOW_RATES_CFM = { 0.88, 0.50, 0.43, 0.36, 0.30, 0.27, 0.25, 0.24, 0.24, 0.23, 0.22, 0.22 }; - private static final double[] CURRENTS = { 7., 8., 8., 9., 9., 9., 10., 10., 10., 11., 11., 10. }; + private static final double[] PRESSURES_PSI = {0., 10., 20., 30., 40., 50., 60., 70., 80., 90., 100., 110.}; + private static final double[] FLOW_RATES_CFM = {0.88, 0.50, 0.43, 0.36, 0.30, 0.27, 0.25, 0.24, 0.24, 0.23, 0.22, 0.22}; + private static final double[] CURRENTS = {7., 8., 8., 9., 9., 9., 10., 10., 10., 11., 11., 10.}; private static final double[] PRESSURES = Arrays.stream(PRESSURES_PSI).map(psi -> psi * PneumaticsSystem.PSI_TO_PASCALS).toArray(); private static final double[] FLOW_RATES = Arrays.stream(FLOW_RATES_CFM).map(cfm -> cfm * CFM_TO_M3_PER_SEC).toArray(); - + PolynomialSplineFunction currentFunction = new LinearInterpolator().interpolate(PRESSURES, CURRENTS); PolynomialSplineFunction flowRateFunction = new LinearInterpolator().interpolate(PRESSURES, FLOW_RATES); private boolean isOn = true; - + private ElectricalDevice.Input electricalState = new ElectricalDevice.Input(0); private PneumaticDevice.Input pneumaticState = new PneumaticDevice.Input(0); - public void setIsOn(boolean on) { + public void setIsOn(final boolean on) { isOn = on; } @Override - public ElectricalDevice.Output step(ElectricalDevice.Input input) { + public ElectricalDevice.Output step(final ElectricalDevice.Input input) { electricalState = input; if (isOn) { double nominalCurrent = currentFunction.value(pneumaticState.pressure); @@ -46,7 +46,7 @@ public ElectricalDevice.Output step(ElectricalDevice.Input input) { } @Override - public PneumaticDevice.Output step(PneumaticDevice.Input input) { + public PneumaticDevice.Output step(final PneumaticDevice.Input input) { pneumaticState = input; double nominalFlowRate = flowRateFunction.value(pneumaticState.pressure); double adjustedFlowRate = nominalFlowRate * electricalState.voltage / NOMINAL_VOLTAGE; diff --git a/src/main/java/com/team766/simulator/elements/AirReservoir.java b/src/main/java/com/team766/simulator/elements/AirReservoir.java index 0faf6870..5b32c58e 100644 --- a/src/main/java/com/team766/simulator/elements/AirReservoir.java +++ b/src/main/java/com/team766/simulator/elements/AirReservoir.java @@ -5,13 +5,13 @@ public class AirReservoir implements PneumaticDevice { private double volume; - - public AirReservoir(double volume) { - this.volume = volume; + + public AirReservoir(final double volume_) { + this.volume = volume_; } - + @Override - public PneumaticDevice.Output step(PneumaticDevice.Input input) { + public PneumaticDevice.Output step(final PneumaticDevice.Input input) { return new PneumaticDevice.Output(0, volume); } } diff --git a/src/main/java/com/team766/simulator/elements/CanMotorController.java b/src/main/java/com/team766/simulator/elements/CanMotorController.java index 685e8ca1..9e4c128a 100644 --- a/src/main/java/com/team766/simulator/elements/CanMotorController.java +++ b/src/main/java/com/team766/simulator/elements/CanMotorController.java @@ -6,11 +6,10 @@ public class CanMotorController extends MotorController { private int address; - - public CanMotorController(int address, ElectricalDevice downstream) { + + public CanMotorController(final int address_, final ElectricalDevice downstream) { super(downstream); - - this.address = address; + this.address = address_; } @Override diff --git a/src/main/java/com/team766/simulator/elements/DCMotor.java b/src/main/java/com/team766/simulator/elements/DCMotor.java index 5cb95ba5..8bb9b058 100644 --- a/src/main/java/com/team766/simulator/elements/DCMotor.java +++ b/src/main/java/com/team766/simulator/elements/DCMotor.java @@ -6,43 +6,43 @@ public class DCMotor implements ElectricalDevice, MechanicalAngularDevice { // TODO: Add rotor inertia // TODO: Add thermal effects - + public static DCMotor makeCIM() { return new DCMotor(46.513, 0.018397, 0.091603053435115); } public static DCMotor make775Pro() { return new DCMotor(163.450, 0.0052985, 0.08955223880597); } - + // Motor velocity constant in radian/second/volt - // (motor velocity) = kV * (motor voltage) + // (motor velocity) = kV * (motor voltage) private final double kV; - + // Motor torque constant in newton-meter/ampere // (motor torque) = kT * (motor current) private final double kT; // Motor resistance is calculated as 12V / (stall current at 12V) private final double motorResistance; - + private ElectricalDevice.Output electricalState = new ElectricalDevice.Output(0); private MechanicalAngularDevice.Input mechanicalState = new MechanicalAngularDevice.Input(0); - public DCMotor(double kV, double kT, double motorResistance) { - this.kV = kV; - this.kT = kT; - this.motorResistance = motorResistance; + public DCMotor(final double kV_, final double kT_, final double motorResistance_) { + this.kV = kV_; + this.kT = kT_; + this.motorResistance = motorResistance_; } @Override - public MechanicalAngularDevice.Output step(MechanicalAngularDevice.Input input) { + public MechanicalAngularDevice.Output step(final MechanicalAngularDevice.Input input) { mechanicalState = new MechanicalAngularDevice.Input(input); - + return new MechanicalAngularDevice.Output(kT * electricalState.current); } @Override - public ElectricalDevice.Output step(ElectricalDevice.Input input) { + public ElectricalDevice.Output step(final ElectricalDevice.Input input) { electricalState = new ElectricalDevice.Output((input.voltage - mechanicalState.angularVelocity / kV) / motorResistance); return electricalState; } diff --git a/src/main/java/com/team766/simulator/elements/DoubleActingPneumaticCylinder.java b/src/main/java/com/team766/simulator/elements/DoubleActingPneumaticCylinder.java index bf6295c0..3cdc299d 100644 --- a/src/main/java/com/team766/simulator/elements/DoubleActingPneumaticCylinder.java +++ b/src/main/java/com/team766/simulator/elements/DoubleActingPneumaticCylinder.java @@ -8,31 +8,34 @@ public class DoubleActingPneumaticCylinder implements PneumaticDevice, MechanicalDevice { private static final Vector3D FORWARD = new Vector3D(1, 0, 0); - + private final double boreDiameter; private final double stroke; - + private boolean isExtended = false; private boolean commandExtended = false; - + private PneumaticDevice.Input pneumaticState = new PneumaticDevice.Input(0); - - public DoubleActingPneumaticCylinder(double boreDiameter, double stroke) { + + public DoubleActingPneumaticCylinder(final double boreDiameter, final double stroke) { this.boreDiameter = boreDiameter; this.stroke = stroke; } - - public void setExtended(boolean state) { + + public void setExtended(final boolean state) { commandExtended = state; } - + @Override - public PneumaticDevice.Output step(PneumaticDevice.Input input) { + public PneumaticDevice.Output step(final PneumaticDevice.Input input) { pneumaticState = input; PneumaticDevice.Output output; double deviceVolume = boreArea() * stroke; if (commandExtended != isExtended) { - output = new PneumaticDevice.Output(-deviceVolume * (input.pressure + PhysicalConstants.ATMOSPHERIC_PRESSURE) / PhysicalConstants.ATMOSPHERIC_PRESSURE, deviceVolume); + output = new PneumaticDevice.Output( + -deviceVolume * (input.pressure + PhysicalConstants.ATMOSPHERIC_PRESSURE) + / PhysicalConstants.ATMOSPHERIC_PRESSURE, + deviceVolume); } else { output = new PneumaticDevice.Output(0, deviceVolume); } @@ -41,7 +44,7 @@ public PneumaticDevice.Output step(PneumaticDevice.Input input) { } @Override - public MechanicalDevice.Output step(MechanicalDevice.Input input) { + public MechanicalDevice.Output step(final MechanicalDevice.Input input) { Vector3D direction = isExtended ? FORWARD : FORWARD.negate(); return new MechanicalDevice.Output(direction.scalarMultiply(boreArea() * pneumaticState.pressure)); } diff --git a/src/main/java/com/team766/simulator/elements/ElectricalResistance.java b/src/main/java/com/team766/simulator/elements/ElectricalResistance.java index c4d3a621..e14a88de 100644 --- a/src/main/java/com/team766/simulator/elements/ElectricalResistance.java +++ b/src/main/java/com/team766/simulator/elements/ElectricalResistance.java @@ -11,23 +11,24 @@ public class ElectricalResistance implements ElectricalDevice { 0.0333, 0.0420, 0.0530, 0.0668, 0.0842, 0.106, 0.134, 0.169, 0.213, 0.268, // 20-29 0.339, 0.427, 0.538, 0.679, 0.856, 1.08, 1.36, 1.72, 2.16, 2.73, 3.44, // 30-40 }; - public static ElectricalResistance makeWires(int awg, double length, ElectricalDevice downstream) { + public static ElectricalResistance makeWires(final int awg, final double length, + final ElectricalDevice downstream) { return new ElectricalResistance(WIRE_RESISTANCE_PER_M[awg] * length / 1000., downstream); } - + private final double resistance; - + private ElectricalDevice downstream; - + private ElectricalDevice.Output state; - - public ElectricalResistance(double resistance, ElectricalDevice downstream) { - this.resistance = resistance; - this.downstream = downstream; + + public ElectricalResistance(final double resistance_, final ElectricalDevice downstream_) { + this.resistance = resistance_; + this.downstream = downstream_; } - + @Override - public ElectricalDevice.Output step(ElectricalDevice.Input input) { + public ElectricalDevice.Output step(final ElectricalDevice.Input input) { ElectricalDevice.Input downstreamInput = new ElectricalDevice.Input(input.voltage - resistance * state.current); state = downstream.step(downstreamInput); return state; diff --git a/src/main/java/com/team766/simulator/elements/Gears.java b/src/main/java/com/team766/simulator/elements/Gears.java index 220b00dc..a439abee 100644 --- a/src/main/java/com/team766/simulator/elements/Gears.java +++ b/src/main/java/com/team766/simulator/elements/Gears.java @@ -8,16 +8,16 @@ public class Gears implements MechanicalAngularDevice { // Torque ratio (output / input) private final double torqueRatio; - + private MechanicalAngularDevice upstream; - - public Gears(double torqueRatio, MechanicalAngularDevice upstream) { - this.torqueRatio = torqueRatio; - this.upstream = upstream; + + public Gears(final double torqueRatio_, final MechanicalAngularDevice upstream_) { + this.torqueRatio = torqueRatio_; + this.upstream = upstream_; } @Override - public MechanicalAngularDevice.Output step(MechanicalAngularDevice.Input input) { + public MechanicalAngularDevice.Output step(final MechanicalAngularDevice.Input input) { MechanicalAngularDevice.Input upstreamInput = new MechanicalAngularDevice.Input(input.angularVelocity * torqueRatio); MechanicalAngularDevice.Output upstreamOutput = upstream.step(upstreamInput); diff --git a/src/main/java/com/team766/simulator/elements/MotorController.java b/src/main/java/com/team766/simulator/elements/MotorController.java index d837e20a..25c2bf89 100644 --- a/src/main/java/com/team766/simulator/elements/MotorController.java +++ b/src/main/java/com/team766/simulator/elements/MotorController.java @@ -4,16 +4,16 @@ public abstract class MotorController implements ElectricalDevice { private ElectricalDevice downstream; - - public MotorController(ElectricalDevice downstream) { - this.downstream = downstream; + + public MotorController(final ElectricalDevice downstream_) { + this.downstream = downstream_; } - + // [-1, 1] representing the command sent from the application processor protected abstract double getCommand(); - + @Override - public ElectricalDevice.Output step(ElectricalDevice.Input input) { + public ElectricalDevice.Output step(final ElectricalDevice.Input input) { double command = getCommand(); ElectricalDevice.Input downstreamInput = new ElectricalDevice.Input(input.voltage * command); ElectricalDevice.Output downstreamOutput = downstream.step(downstreamInput); diff --git a/src/main/java/com/team766/simulator/elements/PwmMotorController.java b/src/main/java/com/team766/simulator/elements/PwmMotorController.java index a0791220..13f12eb8 100644 --- a/src/main/java/com/team766/simulator/elements/PwmMotorController.java +++ b/src/main/java/com/team766/simulator/elements/PwmMotorController.java @@ -4,13 +4,13 @@ import com.team766.simulator.interfaces.ElectricalDevice; public class PwmMotorController extends MotorController { - + private int channel; - public PwmMotorController(int channel, ElectricalDevice downstream) { + public PwmMotorController(final int channel_, final ElectricalDevice downstream) { super(downstream); - - this.channel = channel; + + this.channel = channel_; } @Override diff --git a/src/main/java/com/team766/simulator/elements/SingleActingPneumaticCylinder.java b/src/main/java/com/team766/simulator/elements/SingleActingPneumaticCylinder.java index a8263dbf..f00c3a5b 100644 --- a/src/main/java/com/team766/simulator/elements/SingleActingPneumaticCylinder.java +++ b/src/main/java/com/team766/simulator/elements/SingleActingPneumaticCylinder.java @@ -8,33 +8,37 @@ public class SingleActingPneumaticCylinder implements PneumaticDevice, MechanicalDevice { private static final Vector3D FORWARD = new Vector3D(1, 0, 0); - + private final double boreDiameter; private final double stroke; private final double returnSpringForce; - + private boolean isExtended = false; private boolean commandExtended = false; - + private PneumaticDevice.Input pneumaticState = new PneumaticDevice.Input(0); - - public SingleActingPneumaticCylinder(double boreDiameter, double stroke, double returnSpringForce) { - this.boreDiameter = boreDiameter; - this.stroke = stroke; - this.returnSpringForce = returnSpringForce; + + public SingleActingPneumaticCylinder(final double boreDiameter_, final double stroke_, + final double returnSpringForce_) { + this.boreDiameter = boreDiameter_; + this.stroke = stroke_; + this.returnSpringForce = returnSpringForce_; } - - public void setExtended(boolean state) { + + public void setExtended(final boolean state) { commandExtended = state; } - + @Override - public PneumaticDevice.Output step(PneumaticDevice.Input input) { + public PneumaticDevice.Output step(final PneumaticDevice.Input input) { pneumaticState = input; PneumaticDevice.Output output; double deviceVolume = isExtended ? boreArea() * stroke : 0; if (isExtended && !commandExtended) { - output = new PneumaticDevice.Output(-deviceVolume * (input.pressure + PhysicalConstants.ATMOSPHERIC_PRESSURE) / PhysicalConstants.ATMOSPHERIC_PRESSURE, deviceVolume); + output = new PneumaticDevice.Output( + -deviceVolume * (input.pressure + PhysicalConstants.ATMOSPHERIC_PRESSURE) + / PhysicalConstants.ATMOSPHERIC_PRESSURE, + deviceVolume); } else { output = new PneumaticDevice.Output(0, deviceVolume); } @@ -43,7 +47,7 @@ public PneumaticDevice.Output step(PneumaticDevice.Input input) { } @Override - public MechanicalDevice.Output step(MechanicalDevice.Input input) { + public MechanicalDevice.Output step(final MechanicalDevice.Input input) { Vector3D direction = isExtended ? FORWARD : FORWARD.negate(); double force = isExtended ? boreArea() * pneumaticState.pressure : returnSpringForce; return new MechanicalDevice.Output(direction.scalarMultiply(force)); diff --git a/src/main/java/com/team766/simulator/elements/Wheel.java b/src/main/java/com/team766/simulator/elements/Wheel.java index 1f6efc18..403ca0de 100644 --- a/src/main/java/com/team766/simulator/elements/Wheel.java +++ b/src/main/java/com/team766/simulator/elements/Wheel.java @@ -12,21 +12,21 @@ public class Wheel implements MechanicalDevice { // TODO: Add transverse friction // TODO: Add traction limit/wheel slip (static vs kinetic friction) // TODO: Add rotational inertia - + private static final Vector3D FORWARD = new Vector3D(-1, 0, 0); - + // Diameter of the wheel in meters private final double diameter; - + private MechanicalAngularDevice upstream; - - public Wheel(double diameter, MechanicalAngularDevice upstream) { - this.diameter = diameter; - this.upstream = upstream; + + public Wheel(final double diameter_, final MechanicalAngularDevice upstream_) { + this.diameter = diameter_; + this.upstream = upstream_; } @Override - public MechanicalDevice.Output step(MechanicalDevice.Input input) { + public MechanicalDevice.Output step(final MechanicalDevice.Input input) { MechanicalAngularDevice.Input upstreamInput = new MechanicalAngularDevice.Input(FORWARD.dotProduct(input.velocity) * 2. / diameter); MechanicalAngularDevice.Output upstreamOutput = upstream.step(upstreamInput); diff --git a/src/main/java/com/team766/simulator/interfaces/ElectricalDevice.java b/src/main/java/com/team766/simulator/interfaces/ElectricalDevice.java index f4472268..af1aad98 100644 --- a/src/main/java/com/team766/simulator/interfaces/ElectricalDevice.java +++ b/src/main/java/com/team766/simulator/interfaces/ElectricalDevice.java @@ -1,27 +1,29 @@ package com.team766.simulator.interfaces; public interface ElectricalDevice { - public class Input { - public Input(double voltage) { - this.voltage = voltage; + class Input { + public Input(final double voltage_) { + this.voltage = voltage_; } - public Input(Input other) { + + public Input(final Input other) { voltage = other.voltage; } - + public final double voltage; } - - public class Output { - public Output(double current) { - this.current = current; + + class Output { + public Output(final double current_) { + this.current = current_; } - public Output(Output other) { + + public Output(final Output other) { current = other.current; } - + public final double current; } - - public Output step(Input input); + + Output step(Input input); } diff --git a/src/main/java/com/team766/simulator/interfaces/MechanicalAngularDevice.java b/src/main/java/com/team766/simulator/interfaces/MechanicalAngularDevice.java index a3ea3526..15683015 100644 --- a/src/main/java/com/team766/simulator/interfaces/MechanicalAngularDevice.java +++ b/src/main/java/com/team766/simulator/interfaces/MechanicalAngularDevice.java @@ -1,27 +1,29 @@ package com.team766.simulator.interfaces; public interface MechanicalAngularDevice { - public class Input { - public Input(double angularVelocity) { - this.angularVelocity = angularVelocity; + class Input { + public Input(final double angularVelocity_) { + this.angularVelocity = angularVelocity_; } - public Input(Input other) { - this.angularVelocity = other.angularVelocity; + + public Input(final Input other) { + this.angularVelocity = other.angularVelocity; } public final double angularVelocity; } - - public class Output { - public Output(double torque) { - this.torque = torque; + + class Output { + public Output(final double torque_) { + this.torque = torque_; } - public Output(Output other) { + + public Output(final Output other) { this.torque = other.torque; } - + public final double torque; } - - public Output step(Input input); + + Output step(Input input); } diff --git a/src/main/java/com/team766/simulator/interfaces/MechanicalDevice.java b/src/main/java/com/team766/simulator/interfaces/MechanicalDevice.java index c943b093..7c18b3e4 100644 --- a/src/main/java/com/team766/simulator/interfaces/MechanicalDevice.java +++ b/src/main/java/com/team766/simulator/interfaces/MechanicalDevice.java @@ -3,30 +3,32 @@ import org.apache.commons.math3.geometry.euclidean.threed.Vector3D; public interface MechanicalDevice { - public class Input { - public Input(Vector3D position, Vector3D velocity) { - this.position = position; - this.velocity = velocity; + class Input { + public Input(final Vector3D position_, final Vector3D velocity_) { + this.position = position_; + this.velocity = velocity_; } - public Input(Input other) { + + public Input(final Input other) { position = other.position; velocity = other.velocity; } - + public final Vector3D position; public final Vector3D velocity; } - - public class Output { - public Output(Vector3D force) { - this.force = force; + + class Output { + public Output(final Vector3D force_) { + this.force = force_; } - public Output(Output other) { + + public Output(final Output other) { force = other.force; } - + public final Vector3D force; } - - public Output step(Input input); + + Output step(Input input); } diff --git a/src/main/java/com/team766/simulator/interfaces/PneumaticDevice.java b/src/main/java/com/team766/simulator/interfaces/PneumaticDevice.java index 72a0fc4a..528d2848 100644 --- a/src/main/java/com/team766/simulator/interfaces/PneumaticDevice.java +++ b/src/main/java/com/team766/simulator/interfaces/PneumaticDevice.java @@ -1,40 +1,42 @@ package com.team766.simulator.interfaces; public interface PneumaticDevice { - public class Input { - public Input(double pressure) { - this.pressure = pressure; + class Input { + public Input(final double pressure_) { + this.pressure = pressure_; } - public Input(Input other) { + + public Input(final Input other) { pressure = other.pressure; } - + // Pascals (relative pressure) public final double pressure; } - - public class Output { - public Output(double flowVolume, double deviceVolume) { - this.flowVolume = flowVolume; - this.deviceVolume = deviceVolume; + + class Output { + public Output(final double flowVolume_, final double deviceVolume_) { + this.flowVolume = flowVolume_; + this.deviceVolume = deviceVolume_; } - public Output(Output other) { + + public Output(final Output other) { flowVolume = other.flowVolume; deviceVolume = other.deviceVolume; } - + // Volumetric flow (delta m^3 at atmospheric pressure) // Positive flow is into the system, e.g. from a compressor // Negative flow is out of the system, e.g. from venting to atmosphere public final double flowVolume; - + // Volume of air that the device contains (m^3) public final double deviceVolume; - + // Note that an expanding volume (such as a cylinder expanding) // should increase volume, but have 0 flow volume because no // pressurized air is actually leaving the system. } - - public Output step(Input input); + + Output step(Input input); } diff --git a/src/main/java/com/team766/simulator/mechanisms/WestCoastDrive.java b/src/main/java/com/team766/simulator/mechanisms/WestCoastDrive.java index 25a4de82..f7dcc632 100644 --- a/src/main/java/com/team766/simulator/mechanisms/WestCoastDrive.java +++ b/src/main/java/com/team766/simulator/mechanisms/WestCoastDrive.java @@ -20,20 +20,20 @@ public class WestCoastDrive extends DriveBase { private DCMotor leftMotor = DCMotor.makeCIM(); private DCMotor rightMotor = DCMotor.makeCIM(); - + private MotorController leftController = new PwmMotorController(6, leftMotor); private MotorController rightController = new PwmMotorController(4, rightMotor); - + private Gears leftGears = new Gears(Parameters.DRIVE_GEAR_RATIO, leftMotor); private Gears rightGears = new Gears(Parameters.DRIVE_GEAR_RATIO, rightMotor); - + private Wheel leftWheels = new Wheel(Parameters.DRIVE_WHEEL_DIAMETER, leftGears); private static final Vector3D LEFT_WHEEL_POSITION = new Vector3D(0., 0.3302, 0.); private Wheel rightWheels = new Wheel(Parameters.DRIVE_WHEEL_DIAMETER, rightGears); private static final Vector3D RIGHT_WHEEL_POSITION = new Vector3D(0., -0.3302, 0.); private static final double WHEEL_BASE = 0.585; private static final double ENCODER_TICKS_PER_METER = Parameters.ENCODER_TICKS_PER_REVOLUTION / (Parameters.DRIVE_WHEEL_DIAMETER * Math.PI); - + private Vector3D robotPosition = Vector3D.ZERO; private Rotation robotRotation = Rotation.IDENTITY; private Vector3D linearVelocity = Vector3D.ZERO; @@ -43,8 +43,8 @@ public class WestCoastDrive extends DriveBase { private double leftEncoderResidual = 0; private double rightEncoderResidual = 0; - - public WestCoastDrive(ElectricalSystem electricalSystem) { + + public WestCoastDrive(final ElectricalSystem electricalSystem) { electricalSystem.addDevice(leftController); electricalSystem.addDevice(rightController); } @@ -75,16 +75,16 @@ public void step() { wheelForce = rightWheels.step(rightWheelInput).force.scalarMultiply(-1.0); netForce = netForce.add(wheelForce); netTorque = netTorque.add(Vector3D.crossProduct(RIGHT_WHEEL_POSITION, wheelForce)); - + Vector3D ego_velocity = robotRotation.applyInverseTo(linearVelocity); - + double rateLeft = ENCODER_TICKS_PER_METER * (ego_velocity.getX() - angularVelocity.getZ() * LEFT_WHEEL_POSITION.getNorm()); double rateRight = ENCODER_TICKS_PER_METER * (ego_velocity.getX() + angularVelocity.getZ() * RIGHT_WHEEL_POSITION.getNorm()); leftEncoderResidual += rateLeft * Parameters.TIME_STEP; rightEncoderResidual += rateRight * Parameters.TIME_STEP; - ProgramInterface.encoderChannels[0].distance += (long)leftEncoderResidual; + ProgramInterface.encoderChannels[0].distance += (long) leftEncoderResidual; ProgramInterface.encoderChannels[0].rate = rateLeft; - ProgramInterface.encoderChannels[2].distance += (long)rightEncoderResidual; + ProgramInterface.encoderChannels[2].distance += (long) rightEncoderResidual; ProgramInterface.encoderChannels[2].rate = rateRight; leftEncoderResidual %= 1; rightEncoderResidual %= 1; @@ -104,11 +104,11 @@ public void step() { netTorque = netTorque.add( new Vector3D(0, 0, -softSignum(angularVelocity.getZ())).scalarMultiply( maxFriction * WHEEL_BASE / 2)); - + linearAcceleration = robotRotation.applyTo(netForce).scalarMultiply(1.0 / Parameters.ROBOT_MASS); linearVelocity = linearVelocity.add(linearAcceleration.scalarMultiply(Parameters.TIME_STEP)); robotPosition = robotPosition.add(linearVelocity.scalarMultiply(Parameters.TIME_STEP)); - + angularAcceleration = netTorque.scalarMultiply(1.0 / Parameters.ROBOT_MOMENT_OF_INERTIA); angularVelocity = angularVelocity.add(angularAcceleration.scalarMultiply(Parameters.TIME_STEP)); Vector3D angularDelta = angularVelocity.scalarMultiply(Parameters.TIME_STEP); @@ -120,27 +120,27 @@ public void step() { angularDelta.getZ()), RotationConvention.VECTOR_OPERATOR); } - + public Vector3D getPosition() { return robotPosition; } - + public Rotation getRotation() { return robotRotation; } - + public Vector3D getLinearVelocity() { return linearVelocity; } - + public Vector3D getAngularVelocity() { return angularVelocity; } - + public Vector3D getLinearAcceleration() { return linearAcceleration; } - + public Vector3D getAngularAcceleration() { return angularAcceleration; } diff --git a/src/main/java/com/team766/simulator/ui/Metrics.java b/src/main/java/com/team766/simulator/ui/Metrics.java index 2615c6ea..6dec5292 100644 --- a/src/main/java/com/team766/simulator/ui/Metrics.java +++ b/src/main/java/com/team766/simulator/ui/Metrics.java @@ -40,16 +40,16 @@ public class Metrics extends JPanel { "#DECF3F", // yellow "#F15854", // red }; - + private static class Inspector extends MouseAdapter implements KeyListener { private int sourceIndex = 0; private double selectedTime = Double.NaN; private XYPlot plot; - - public Inspector(XYPlot plot) { - this.plot = plot; + + Inspector(final XYPlot plot_) { + this.plot = plot_; } - + void update() { if (!Double.isNaN(selectedTime)) { DataSource source = plot.getData().get(sourceIndex); @@ -60,17 +60,16 @@ void update() { System.out.println(String.format("(%s, %f): %f", source.getName(), selectedTime, source.get(1, index))); } } - + @Override - public void mouseClicked(MouseEvent e) { + public void mouseClicked(final MouseEvent e) { double x = e.getX() - plot.getPlotArea().getX(); selectedTime = plot.getAxisRenderer(XYPlot.AXIS_X).viewToWorld(plot.getAxis(XYPlot.AXIS_X), x, false).doubleValue(); - update(); } - + @Override - public void keyTyped(KeyEvent e) { + public void keyTyped(final KeyEvent e) { if (e.getKeyChar() >= '1' && e.getKeyChar() <= '9') { int index = e.getKeyChar() - '1'; if (index < plot.getData().size()) { @@ -80,15 +79,17 @@ public void keyTyped(KeyEvent e) { } } } - + @Override - public void keyReleased(KeyEvent e) {} - + public void keyReleased(final KeyEvent e) { + } + @Override - public void keyPressed(KeyEvent e) {} + public void keyPressed(final KeyEvent e) { + } } - - public static JFrame makePlotFrame(Collection series, String[] labels) { + + public static JFrame makePlotFrame(final Collection series, final String[] labels) { JFrame frame = new JFrame(); frame.setDefaultCloseOperation(JFrame.EXIT_ON_CLOSE); frame.setSize(800, 600); @@ -96,14 +97,14 @@ public static JFrame makePlotFrame(Collection series, String[] labels) frame.setVisible(true); return frame; } - + XYPlot plot; JSlider slider; DataTable data; JPanel plotPanel; Timer playbackTimer; - - public Metrics(Collection series, String[] labels) { + + public Metrics(final Collection series, final String[] labels) { Double[] first = series.iterator().next(); @SuppressWarnings("unchecked") Class[] types = new Class[first.length]; @@ -116,7 +117,8 @@ public Metrics(Collection series, String[] labels) { data.add(values); } if (first.length - 1 != labels.length) { - throw new IllegalArgumentException("Number of labels does not match the size of data values"); + throw new IllegalArgumentException( + "Number of labels does not match the size of data values"); } DataSource[] sources = new DataSource[labels.length]; for (int i = 0; i < labels.length; ++i) { @@ -132,18 +134,18 @@ public Metrics(Collection series, String[] labels) { plot.getLineRenderers(source).get(0).setColor(color); } plot.setLegendVisible(true); - + InteractivePanel panel = new InteractivePanel(plot); plotPanel = panel; setLayout(new BorderLayout()); add(panel, BorderLayout.CENTER); - + final int TIMER_PERIOD_MS = 50; playbackTimer = new Timer(TIMER_PERIOD_MS, new ActionListener() { @Override - public void actionPerformed(ActionEvent e) { + public void actionPerformed(final ActionEvent e) { double deltaSteps = (TIMER_PERIOD_MS / 1000.0) / Parameters.TIME_STEP; - int newValue = slider.getValue() + (int)deltaSteps; + int newValue = slider.getValue() + (int) deltaSteps; if (newValue > slider.getMaximum()) { newValue = slider.getMaximum(); playbackTimer.stop(); @@ -152,7 +154,7 @@ public void actionPerformed(ActionEvent e) { } }); playbackTimer.setRepeats(true); - + Inspector inspector = new Inspector(plot); addKeyListener(inspector); panel.addMouseListener(inspector); diff --git a/src/main/java/com/team766/simulator/ui/Trajectory.java b/src/main/java/com/team766/simulator/ui/Trajectory.java index bc97b9fe..f69c8e22 100644 --- a/src/main/java/com/team766/simulator/ui/Trajectory.java +++ b/src/main/java/com/team766/simulator/ui/Trajectory.java @@ -28,7 +28,7 @@ @SuppressWarnings("serial") public class Trajectory extends JPanel { - public static JFrame makePlotFrame(Collection series) { + public static JFrame makePlotFrame(final Collection series) { JFrame frame = new JFrame(); frame.setDefaultCloseOperation(JFrame.EXIT_ON_CLOSE); frame.setSize(800, 600); @@ -36,14 +36,14 @@ public static JFrame makePlotFrame(Collection series) { frame.setVisible(true); return frame; } - + XYPlot plot; JSlider slider; DataTable data; JPanel plotPanel; Timer playbackTimer; - - public Trajectory(Collection series) { + + public Trajectory(final Collection series) { Double[] first = series.iterator().next(); @SuppressWarnings("unchecked") Class[] types = new Class[first.length]; @@ -58,18 +58,18 @@ public Trajectory(Collection series) { plot = new XYPlot(new DataSeries("Trajectory", data, 0, 1)); plot.getAxis(XYPlot.AXIS_X).setRange(-10.0, 10.0); plot.getAxis(XYPlot.AXIS_Y).setRange(-10.0, 10.0); - + InteractivePanel panel = new InteractivePanel(plot); plotPanel = panel; setLayout(new BorderLayout()); add(panel, BorderLayout.CENTER); - + final int TIMER_PERIOD_MS = 50; playbackTimer = new Timer(TIMER_PERIOD_MS, new ActionListener() { @Override - public void actionPerformed(ActionEvent e) { + public void actionPerformed(final ActionEvent e) { double deltaSteps = (TIMER_PERIOD_MS / 1000.0) / Parameters.TIME_STEP; - int newValue = slider.getValue() + (int)deltaSteps; + int newValue = slider.getValue() + (int) deltaSteps; if (newValue > slider.getMaximum()) { newValue = slider.getMaximum(); playbackTimer.stop(); @@ -78,13 +78,13 @@ public void actionPerformed(ActionEvent e) { } }); playbackTimer.setRepeats(true); - + JPanel controlsPanel = new JPanel(); controlsPanel.setLayout(new BoxLayout(controlsPanel, BoxLayout.LINE_AXIS)); slider = new JSlider(0, data.getRowCount() - 1); slider.setValue(0); slider.addChangeListener(new ChangeListener() { - public void stateChanged(ChangeEvent e) { + public void stateChanged(final ChangeEvent e) { Trajectory.this.repaint(); } }); @@ -92,7 +92,7 @@ public void stateChanged(ChangeEvent e) { JButton playButton = new JButton(">"); playButton.addActionListener(new ActionListener() { @Override - public void actionPerformed(ActionEvent e) { + public void actionPerformed(final ActionEvent e) { if (playbackTimer.isRunning()) { playbackTimer.stop(); } else { @@ -106,36 +106,37 @@ public void actionPerformed(ActionEvent e) { controlsPanel.add(playButton); add(controlsPanel, BorderLayout.SOUTH); } - + @Override - public void paint(Graphics g) { + public void paint(final Graphics g) { super.paint(g); - + int slider_value = slider.getValue(); - double x = (Double)data.get(0, slider_value); - double y = (Double)data.get(1, slider_value); - double orientation = (Double)data.get(2, slider_value); - double vel_x = (Double)data.get(3, slider_value); - double vel_y = (Double)data.get(4, slider_value); - + double x = (Double) data.get(0, slider_value); + double y = (Double) data.get(1, slider_value); + double orientation = (Double) data.get(2, slider_value); + // unused values + //double vel_x = (Double) data.get(3, slider_value); + //double vel_y = (Double) data.get(4, slider_value); + double pixelX = plot.getAxisRenderer(XYPlot.AXIS_X).worldToView(plot.getAxis(XYPlot.AXIS_X), x, false); double pixelY = plot.getAxisRenderer(XYPlot.AXIS_Y).worldToView(plot.getAxis(XYPlot.AXIS_Y), y, false); double plotAreaHeight = plot.getPlotArea().getHeight(); double plotAreaX = plot.getPlotArea().getX(); double plotAreaY = plot.getPlotArea().getY(); - + pixelX = plotAreaX + pixelX; pixelY = plotAreaY + plotAreaHeight - pixelY; - - Graphics2D g2d = (Graphics2D)g; + + Graphics2D g2d = (Graphics2D) g; final int SIZE_X = 30; final int SIZE_Y = 20; g2d.setColor(new Color(128, 128, 255)); AffineTransform saveXf = g2d.getTransform(); g2d.rotate(-orientation, pixelX, pixelY); - g2d.fillRect((int)pixelX - SIZE_X / 2, (int)pixelY - SIZE_Y / 2, SIZE_X, SIZE_Y); + g2d.fillRect((int) pixelX - SIZE_X / 2, (int) pixelY - SIZE_Y / 2, SIZE_X, SIZE_Y); g2d.setTransform(saveXf); //g2d.setColor(Color.red); //g2d.drawLine((int)pixelX, (int)pixelY, (int)(pixelX + vel_x * 20), (int)(pixelY - vel_y * 20)); diff --git a/src/main/java/com/team766/web/AutonomousSelector.java b/src/main/java/com/team766/web/AutonomousSelector.java index 22170e55..9d87df89 100644 --- a/src/main/java/com/team766/web/AutonomousSelector.java +++ b/src/main/java/com/team766/web/AutonomousSelector.java @@ -15,21 +15,19 @@ public class AutonomousSelector implements WebServer.Handler { private final AutonomousMode[] m_autonModes; private final String[] m_autonModeNames; private AutonomousMode m_selectedAutonMode; - - public AutonomousSelector(AutonomousMode[] autonModes) { + + public AutonomousSelector(final AutonomousMode[] autonModes) { m_autonModes = autonModes; - m_autonModeNames = - Arrays.stream(autonModes).map(m -> m.name()).toArray(String[]::new); + m_autonModeNames = Arrays.stream(autonModes).map(m -> m.name()).toArray(String[]::new); if (m_autonModeNames.length > 0) { m_selectedAutonMode = m_autonModes[0]; } else { - Logger.get(Category.AUTONOMOUS).logRaw( - Severity.WARNING, - "No autonomous modes were declared in AutonomousModes.java"); + Logger.get(Category.AUTONOMOUS).logRaw(Severity.WARNING, + "No autonomous modes were declared in AutonomousModes.java"); m_selectedAutonMode = null; } } - + public AutonomousMode getSelectedAutonMode() { return m_selectedAutonMode; } @@ -38,36 +36,34 @@ public AutonomousMode getSelectedAutonMode() { public String endpoint() { return ENDPOINT; } - + @Override - public String handle(Map params) { + public String handle(final Map params) { String locationReplaceScript = ""; - { - final String selectedAutonModeName = (String)params.get("AutoMode"); - if (selectedAutonModeName != null) { - final Optional selectedAutonMode = - Arrays.stream(m_autonModes).filter(m -> m.name().equals(selectedAutonModeName)).findFirst(); - if (selectedAutonMode.isEmpty()) { - Logger.get(Category.AUTONOMOUS).logData( - Severity.ERROR, + final String selectedAutonModeName = (String) params.get("AutoMode"); + if (selectedAutonModeName != null) { + final Optional selectedAutonMode = Arrays.stream(m_autonModes) + .filter(m -> m.name().equals(selectedAutonModeName)).findFirst(); + if (selectedAutonMode.isEmpty()) { + Logger.get(Category.AUTONOMOUS).logData(Severity.ERROR, "Internal framework error: Inconsistent name for selected autonomous mode (selected: %s ; available: %s). Autonomous mode will not run.", - selectedAutonModeName, - Arrays.stream(m_autonModes).map(m -> m.name()).collect(Collectors.joining(","))); - } else { - m_selectedAutonMode = selectedAutonMode.get().clone(); - } - - locationReplaceScript = ""; + selectedAutonModeName, Arrays.stream(m_autonModes).map(m -> m.name()) + .collect(Collectors.joining(","))); + } else { + m_selectedAutonMode = selectedAutonMode.get().clone(); } + + locationReplaceScript = + ""; } - - final String selectedAutonModeName = m_selectedAutonMode != null ? m_selectedAutonMode.name() : ""; + final String selectedAutonModeNameUI = + m_selectedAutonMode != null ? m_selectedAutonMode.name() : ""; return String.join("\n", new String[]{ locationReplaceScript, "

Autonomous Mode Selector

", - "

Current Mode: " + selectedAutonModeName + "

", + "

Current Mode: " + selectedAutonModeNameUI + "

", "
", - "

" + HtmlElements.buildDropDown("AutoMode", selectedAutonModeName, m_autonModeNames) + "

", + "

" + HtmlElements.buildDropDown("AutoMode", selectedAutonModeNameUI, m_autonModeNames) + "

", "
", "", - }); + private static String makePage(final String categoryName, final Iterable entries) { + return String.join("\n", + new String[] {"

Log: " + categoryName + "

", + "

", + HtmlElements.buildDropDown( + "category", categoryName, + Stream.concat(Stream + .of(ALL_ERRORS_NAME), + Arrays.stream(Category.values()).map(Category::name)) + .toArray(String[]::new)), + "", "

", + makeLogEntriesTable(entries), + "", + "", + "", + "", }); } static String makeAllErrorsPage() { - return makePage( - ALL_ERRORS_NAME, - Arrays.stream(Category.values()) - .flatMap(category -> Logger.get(category).recentEntries().stream()) - .filter(entry -> entry.getSeverity() == Severity.ERROR) - ::iterator); + return makePage(ALL_ERRORS_NAME, + Arrays.stream(Category.values()) + .flatMap(category -> Logger.get(category).recentEntries().stream()) + .filter(entry -> entry.getSeverity() == Severity.ERROR)::iterator); } @Override @@ -92,8 +77,8 @@ public String endpoint() { } @Override - public String handle(Map params) { - String categoryName = (String)params.get("category"); + public String handle(final Map params) { + String categoryName = (String) params.get("category"); if (categoryName == null || categoryName.equals(ALL_ERRORS_NAME)) { return makeAllErrorsPage(); } else { diff --git a/src/main/java/com/team766/web/ReadLogs.java b/src/main/java/com/team766/web/ReadLogs.java index 91aca8a7..acbf898e 100644 --- a/src/main/java/com/team766/web/ReadLogs.java +++ b/src/main/java/com/team766/web/ReadLogs.java @@ -27,7 +27,8 @@ public class ReadLogs implements WebServer.Handler { private HashMap readerDescriptions = new HashMap(); private HashMap> readerStreams = new HashMap>(); - private static String makeLogEntriesTable(LogReader reader, Iterator entries) { + private static String makeLogEntriesTable(final LogReader reader, + final Iterator entries) { String r = "\n"; for (int i = 0; i < ENTRIES_PER_PAGE; ++i) { if (!entries.hasNext()) { @@ -35,51 +36,42 @@ private static String makeLogEntriesTable(LogReader reader, Iterator e } LogEntry entry = entries.next(); r += String.format( - "\n", - entry.getCategory(), entry.getTime(), entry.getSeverity(), LogEntryRenderer.renderLogEntry(entry, reader)); + "\n", + entry.getCategory(), entry.getTime(), entry.getSeverity(), + LogEntryRenderer.renderLogEntry(entry, reader)); } r += "
%s%s%s%s
%s%s%s%s
"; return r; } - private String makePage(String id) { - String r = String.join("\n", new String[]{ - "

Free disk space: " - + NumberFormat.getNumberInstance(Locale.US).format( - new File(Logger.logFilePathBase).getUsableSpace()) - + "

", - "

", - HtmlElements.buildDropDown( - "logFile", - "", - Logger.logFilePathBase == null - ? new String[0] - : new File(Logger.logFilePathBase).list()), - HtmlElements.buildDropDown( - "category", - "", - Stream.concat( - Stream.of("", ALL_ERRORS_NAME), - Arrays.stream(Category.values()).map(Category::name) - ).toArray(String[]::new)), - "", - "

", - }); + private String makePage(final String id) { + String r = + String.join("\n", + new String[] { + "

Free disk space: " + NumberFormat.getNumberInstance(Locale.US) + .format(new File(Logger.logFilePathBase).getUsableSpace()) + + "

", + "

", + HtmlElements.buildDropDown("logFile", "", + Logger.logFilePathBase == null ? new String[0] + : new File(Logger.logFilePathBase).list()), + HtmlElements.buildDropDown("category", "", Stream + .concat(Stream.of("", ALL_ERRORS_NAME), + Arrays.stream(Category.values()) + .map(Category::name)) + .toArray(String[]::new)), + "", "

", }); if (id != null) { - r += String.join("\n", new String[]{ - "

Log: " + readerDescriptions.get(id) + "

", - makeLogEntriesTable(logReaders.get(id), readerStreams.get(id)), - "", - }); + r += String.join("\n", new String[] {"

Log: " + readerDescriptions.get(id) + "

", + makeLogEntriesTable(logReaders.get(id), readerStreams.get(id)), + "", }); } return r; } - private String makeReader( - String logFile, - String description, - Function, Stream> filter - ) { + private String makeReader(final String logFile, final String description, + final Function, Stream> filter) { LogReader reader; try { reader = new LogReader(new File(Logger.logFilePathBase, logFile).getAbsolutePath()); @@ -101,28 +93,18 @@ private String makeReader( return id; } - private String makeUnfilteredReader(String logFile) { - return makeReader( - logFile, - "", - s -> s - ); + private String makeUnfilteredReader(final String logFile) { + return makeReader(logFile, "", s -> s); } - private String makeCategoryReader(String logFile, Category category) { - return makeReader( - logFile, - category.name(), - s -> s.filter(e -> e.getCategory() == category) - ); + private String makeCategoryReader(final String logFile, final Category category) { + return makeReader(logFile, category.name(), + s -> s.filter(e -> e.getCategory() == category)); } - private String makeAllErrorsReader(String logFile) { - return makeReader( - logFile, - ALL_ERRORS_NAME, - s -> s.filter(entry -> entry.getSeverity() == Severity.ERROR) - ); + private String makeAllErrorsReader(final String logFile) { + return makeReader(logFile, ALL_ERRORS_NAME, + s -> s.filter(entry -> entry.getSeverity() == Severity.ERROR)); } @Override @@ -131,10 +113,10 @@ public String endpoint() { } @Override - public String handle(Map params) { - String id = (String)params.get("id"); - String logFile = (String)params.get("logFile"); - String categoryName = (String)params.get("category"); + public String handle(final Map params) { + String id = (String) params.get("id"); + String logFile = (String) params.get("logFile"); + String categoryName = (String) params.get("category"); if (!logReaders.containsKey(id)) { id = null; } diff --git a/src/main/java/com/team766/web/WebServer.java b/src/main/java/com/team766/web/WebServer.java index 56e59fed..2df18169 100644 --- a/src/main/java/com/team766/web/WebServer.java +++ b/src/main/java/com/team766/web/WebServer.java @@ -19,20 +19,24 @@ import com.sun.net.httpserver.HttpServer; /* - * Creates an HTTP Server on the robot that can change the + * Creates an HTTP Server on the robot that can change the * settings of it. It is initially just used to change robot - * values. Hopefully this will be later updated to support + * values. Hopefully this will be later updated to support * graphing and even small changes in the robot's actual code. - * + * * Can be reached at: * roboRio-766.local:5800/values */ public class WebServer { - + public interface Handler { String endpoint(); - default boolean showInMenu() { return true; } + + default boolean showInMenu() { + return true; + } + String title(); String handle(Map params); } @@ -58,17 +62,17 @@ public boolean showInMenu() { } @Override - public String handle(Map params) { + public String handle(final Map params) { return ""; } }); } - - public void addHandler(Handler handler) { + + public void addHandler(final Handler handler) { pages.put(handler.endpoint(), handler); } - public void start(){ + public void start() { try { server = HttpServer.create(new InetSocketAddress(5800), 0); } catch (IOException e) { @@ -77,7 +81,7 @@ public void start(){ for (Map.Entry page : pages.entrySet()) { HttpHandler httpHandler = new HttpHandler() { @Override - public void handle(HttpExchange exchange) throws IOException { + public void handle(final HttpExchange exchange) throws IOException { Map params = parseParams(exchange); String response = ""; response += buildPageHeader(); @@ -99,7 +103,7 @@ public void handle(HttpExchange exchange) throws IOException { addLineNumbersSvgHandler(); server.start(); } - + protected String buildPageHeader() { String result = ""; result += "\n"; result += "

\n"; for (Map.Entry page : pages.entrySet()) { - if (page.getValue().showInMenu()) - result += String.format("%s
\n", page.getKey(), page.getValue().title()); + if (page.getValue().showInMenu()) { + result += String.format("%s
\n", page.getKey(), + page.getValue().title()); + } } result += "

\n"; return result; } - + private void addLineNumbersSvgHandler() { HttpHandler httpHandler = new HttpHandler() { @Override - public void handle(HttpExchange exchange) throws IOException { + public void handle(final HttpExchange exchange) throws IOException { String response = "\n"; - response += "\n"; + response += + "\n"; response += "\n"; - response += "\n"; + response += + "\n"; for (int i = 1; i < 1000; ++i) { response += "" + i + ".\n"; } @@ -145,41 +153,40 @@ public void handle(HttpExchange exchange) throws IOException { }; server.createContext("/line_numbers.svg", httpHandler); } - - public Map parseParams(HttpExchange exchange) throws IOException { + + public Map parseParams(final HttpExchange exchange) throws IOException { Map parameters = new HashMap(); parseGetParameters(exchange, parameters); parsePostParameters(exchange, parameters); return parameters; } - private void parseGetParameters(HttpExchange exchange, Map parameters) - throws UnsupportedEncodingException { + private void parseGetParameters(final HttpExchange exchange, + final Map parameters) throws UnsupportedEncodingException { URI requestedUri = exchange.getRequestURI(); String query = requestedUri.getRawQuery(); parseQuery(query, parameters); } - private void parsePostParameters(HttpExchange exchange, Map parameters) - throws IOException { + private void parsePostParameters(final HttpExchange exchange, + final Map parameters) throws IOException { if ("post".equalsIgnoreCase(exchange.getRequestMethod())) { - InputStreamReader isr = - new InputStreamReader(exchange.getRequestBody(), "utf-8"); + InputStreamReader isr = new InputStreamReader(exchange.getRequestBody(), "utf-8"); BufferedReader br = new BufferedReader(isr); String query = br.readLine(); parseQuery(query, parameters); } } - private void parseQuery(String query, Map parameters) - throws UnsupportedEncodingException { + private void parseQuery(final String query, final Map parameters) + throws UnsupportedEncodingException { if (query != null) { - String pairs[] = query.split("[&]"); + String[] pairs = query.split("[&]"); for (String pair : pairs) { - String param[] = pair.split("[=]"); + String[] param = pair.split("[=]"); String key = null; String value = null; @@ -193,14 +200,14 @@ private void parseQuery(String query, Map parameters) if (parameters.containsKey(key)) { Object obj = parameters.get(key); - if(obj instanceof List) { + if (obj instanceof List) { @SuppressWarnings("unchecked") - List values = (List)obj; - + List values = (List) obj; + values.add(value); - } else if(obj instanceof String) { + } else if (obj instanceof String) { List values = new ArrayList(); - values.add((String)obj); + values.add((String) obj); values.add(value); parameters.put(key, values); } diff --git a/src/main/java/com/team766/web/dashboard/NewSection.java b/src/main/java/com/team766/web/dashboard/NewSection.java index 69655dea..30853f1c 100644 --- a/src/main/java/com/team766/web/dashboard/NewSection.java +++ b/src/main/java/com/team766/web/dashboard/NewSection.java @@ -7,11 +7,11 @@ public NewSection() { this("", DEFAULT_SORT_ORDER); } - public NewSection(String name) { + public NewSection(final String name) { this(name, DEFAULT_SORT_ORDER); } - public NewSection(String name, int sortOrder) { + public NewSection(final String name, final int sortOrder) { super(sortOrder); m_name = name; @@ -26,5 +26,5 @@ public String render() { page += ""; return page; } - + } diff --git a/src/main/java/com/team766/web/dashboard/StatusLight.java b/src/main/java/com/team766/web/dashboard/StatusLight.java index 57de7cb3..3ed7718f 100644 --- a/src/main/java/com/team766/web/dashboard/StatusLight.java +++ b/src/main/java/com/team766/web/dashboard/StatusLight.java @@ -7,30 +7,30 @@ public class StatusLight extends Widget { private int m_height = 150; private String m_style = ""; - public StatusLight(String name) { + public StatusLight(final String name) { this(name, DEFAULT_SORT_ORDER); } - public StatusLight(String name, int sortOrder) { + public StatusLight(final String name, final int sortOrder) { super(sortOrder); m_name = name; } - public void setName(String name) { + public void setName(final String name) { m_name = name; } - public void setSize(int width, int height) { + public void setSize(final int width, final int height) { m_width = width; m_height = height; } - public void setColor(String color) { + public void setColor(final String color) { m_color = color; } - public void setStyle(String style) { + public void setStyle(final String style) { m_style = style; } diff --git a/src/main/java/com/team766/web/dashboard/Widget.java b/src/main/java/com/team766/web/dashboard/Widget.java index 3a2573ca..913d5dbc 100644 --- a/src/main/java/com/team766/web/dashboard/Widget.java +++ b/src/main/java/com/team766/web/dashboard/Widget.java @@ -21,9 +21,9 @@ public static Iterable listWidgets() { } } - public Widget(int sortOrder) { + public Widget(final int sortOrder) { synchronized (c_widgets) { - c_widgets.put(this, (((long)sortOrder) << 32) | (c_orderCounter++)); + c_widgets.put(this, (((long) sortOrder) << 32) | (c_orderCounter++)); } } diff --git a/src/test/java/com/team766/TestCase.java b/src/test/java/com/team766/TestCase.java index a81de41c..71dec67c 100644 --- a/src/test/java/com/team766/TestCase.java +++ b/src/test/java/com/team766/TestCase.java @@ -6,16 +6,16 @@ import com.team766.hal.mock.TestRobotProvider; public abstract class TestCase extends junit.framework.TestCase { - + @Override protected void setUp() throws Exception { ConfigFileReader.instance = new ConfigFileReader(this.getClass().getClassLoader().getResource("testConfig.txt").getPath()); RobotProvider.instance = new TestRobotProvider(); - + Scheduler.getInstance().reset(); } - - protected void step(){ + + protected void step() { Scheduler.getInstance().run(); } diff --git a/src/test/java/com/team766/logging/LoggerTest.java b/src/test/java/com/team766/logging/LoggerTest.java index a287fa14..be477ad9 100644 --- a/src/test/java/com/team766/logging/LoggerTest.java +++ b/src/test/java/com/team766/logging/LoggerTest.java @@ -41,7 +41,7 @@ public void test() throws IOException, InterruptedException { .setMessageStr("Test raw log") .build()); writer.close(); - + LogReader reader = new LogReader(logFile); String logString1 = LogEntryRenderer.renderLogEntry(reader.readNext(), reader); assertEquals("num: 42 str: my string", logString1); @@ -59,7 +59,7 @@ public void stressTest() throws IOException, InterruptedException { LogWriter writer = new LogWriter(new File(workingDir.getRoot(), "stress_test.log").getPath()); ArrayList threads = new ArrayList(); for (int j = 0; j < NUM_THREADS; ++j) { - Thread t = new Thread(() ->{ + Thread t = new Thread(() -> { long end = System.currentTimeMillis() + RUN_TIME_SECONDS * 1000; while (System.currentTimeMillis() < end) { writer.logStoredFormat(