diff --git a/photon-core/src/main/java/org/photonvision/common/configuration/ConfigManager.java b/photon-core/src/main/java/org/photonvision/common/configuration/ConfigManager.java index f3cb9c1eb1..48a6e011bf 100644 --- a/photon-core/src/main/java/org/photonvision/common/configuration/ConfigManager.java +++ b/photon-core/src/main/java/org/photonvision/common/configuration/ConfigManager.java @@ -28,7 +28,8 @@ import java.time.LocalDateTime; import java.time.format.DateTimeFormatter; import java.time.temporal.TemporalAccessor; -import java.util.*; +import java.util.Date; +import java.util.List; import org.photonvision.common.logging.LogGroup; import org.photonvision.common.logging.Logger; import org.photonvision.common.util.file.FileUtils; @@ -47,13 +48,13 @@ public class ConfigManager { private final ConfigProvider m_provider; - private Thread settingsSaveThread; + private final Thread settingsSaveThread; private long saveRequestTimestamp = -1; enum ConfigSaveStrategy { SQL, LEGACY, - ATOMIC_ZIP; + ATOMIC_ZIP } // This logic decides which kind of ConfigManager we load as the default. If we want @@ -115,9 +116,8 @@ private void translateLegacyIfPresent(Path folderPath) { e1.printStackTrace(); } - // So we can't save the old config, and we couldn't copy the folder - // But we've loaded the config. So just try to delete the directory so we don't try to load - // form it next time. That does mean we have no backup recourse, tho + // Delete the directory because we were successfully able to load the config but were unable + // to save or copy the folder. if (maybeCams.exists()) FileUtils.deleteDirectory(maybeCams.toPath()); } @@ -225,7 +225,7 @@ public String taToLogFname(TemporalAccessor date) { } public Date logFnameToDate(String fname) throws ParseException { - // Strip away known unneded portions of the log file name + // Strip away known unneeded portions of the log file name fname = fname.replace(LOG_PREFIX, "").replace(LOG_EXT, ""); DateFormat format = new SimpleDateFormat(LOG_DATE_TIME_FORMAT); return format.parse(fname); diff --git a/photon-core/src/main/java/org/photonvision/common/configuration/LegacyConfigProvider.java b/photon-core/src/main/java/org/photonvision/common/configuration/LegacyConfigProvider.java index 7051ab7ef9..6dca0ddcb2 100644 --- a/photon-core/src/main/java/org/photonvision/common/configuration/LegacyConfigProvider.java +++ b/photon-core/src/main/java/org/photonvision/common/configuration/LegacyConfigProvider.java @@ -55,7 +55,7 @@ class LegacyConfigProvider extends ConfigProvider { final File configDirectoryFile; private long saveRequestTimestamp = -1; - private Thread settingsSaveThread; + private final Thread settingsSaveThread; public static void saveUploadedSettingsZip(File uploadPath) { var folderPath = Path.of(System.getProperty("java.io.tmpdir"), "photonvision").toFile(); @@ -67,7 +67,6 @@ public static void saveUploadedSettingsZip(File uploadPath) { logger.info("Copied settings successfully!"); } catch (IOException e) { logger.error("Exception copying uploaded settings!", e); - return; } } @@ -371,7 +370,7 @@ public String taToLogFname(TemporalAccessor date) { } public Date logFnameToDate(String fname) throws ParseException { - // Strip away known unneded portions of the log file name + // Strip away known unneeded portions of the log file name fname = fname.replace(LOG_PREFIX, "").replace(LOG_EXT, ""); DateFormat format = new SimpleDateFormat(LOG_DATE_TIME_FORMAT); return format.parse(fname); diff --git a/photon-core/src/main/java/org/photonvision/common/configuration/NetworkConfig.java b/photon-core/src/main/java/org/photonvision/common/configuration/NetworkConfig.java index a623120711..36e1efe8e3 100644 --- a/photon-core/src/main/java/org/photonvision/common/configuration/NetworkConfig.java +++ b/photon-core/src/main/java/org/photonvision/common/configuration/NetworkConfig.java @@ -30,7 +30,7 @@ import org.photonvision.common.util.file.JacksonUtils; public class NetworkConfig { - // Can be a integer team number, or a IP address + // Can be an integer team number, or an IP address public String ntServerAddress = "0"; public NetworkMode connectionType = NetworkMode.DHCP; public String staticIp = ""; @@ -58,7 +58,7 @@ public NetworkConfig() { .orElse("Wired connection 1"); } - // We can (usually) manage networking on Linux devices, and if we can we should try to. Command + // We can (usually) manage networking on Linux devices, and if we can, we should try to. Command // line inhibitions happen at a level above this class setShouldManage(deviceCanManageNetwork()); } diff --git a/photon-core/src/main/java/org/photonvision/common/configuration/PhotonConfiguration.java b/photon-core/src/main/java/org/photonvision/common/configuration/PhotonConfiguration.java index f0cc2bfa1a..262cdd7111 100644 --- a/photon-core/src/main/java/org/photonvision/common/configuration/PhotonConfiguration.java +++ b/photon-core/src/main/java/org/photonvision/common/configuration/PhotonConfiguration.java @@ -33,10 +33,10 @@ // TODO rename this class public class PhotonConfiguration { - private HardwareConfig hardwareConfig; - private HardwareSettings hardwareSettings; + private final HardwareConfig hardwareConfig; + private final HardwareSettings hardwareSettings; private NetworkConfig networkConfig; - private HashMap cameraConfigurations; + private final HashMap cameraConfigurations; public PhotonConfiguration( HardwareConfig hardwareConfig, @@ -113,7 +113,7 @@ public Map toHashMap() { var lightingConfig = new UILightingConfig(); lightingConfig.brightness = hardwareSettings.ledBrightnessPercentage; - lightingConfig.supported = (hardwareConfig.ledPins.size() != 0); + lightingConfig.supported = !hardwareConfig.ledPins.isEmpty(); settingsSubmap.put("lighting", SerializationUtils.objectToHashMap(lightingConfig)); var generalSubmap = new HashMap(); diff --git a/photon-core/src/main/java/org/photonvision/common/configuration/SqlConfigProvider.java b/photon-core/src/main/java/org/photonvision/common/configuration/SqlConfigProvider.java index e9957eb161..df63b27588 100644 --- a/photon-core/src/main/java/org/photonvision/common/configuration/SqlConfigProvider.java +++ b/photon-core/src/main/java/org/photonvision/common/configuration/SqlConfigProvider.java @@ -21,11 +21,7 @@ import java.io.IOException; import java.nio.file.Files; import java.nio.file.Path; -import java.sql.Connection; -import java.sql.DriverManager; -import java.sql.PreparedStatement; -import java.sql.SQLException; -import java.sql.Statement; +import java.sql.*; import java.util.ArrayList; import java.util.HashMap; import java.util.List; @@ -255,8 +251,7 @@ private String getOneConfigFile(Connection conn, String filename) { var result = query.executeQuery(); while (result.next()) { - var contents = result.getString("contents"); - return contents; + return result.getString("contents"); } } catch (SQLException e) { logger.error("SQL Err getting file " + filename, e); @@ -286,7 +281,7 @@ private void saveCameras(Connection conn) { statement.setString(2, JacksonUtils.serializeToString(config)); statement.setString(3, JacksonUtils.serializeToString(config.driveModeSettings)); - // Serializing a list of abstract classes sucks. Instead, make it into a array + // Serializing a list of abstract classes sucks. Instead, make it into an array // of strings, which we can later unpack back into individual settings List settings = config.pipelineSettings.stream() @@ -424,7 +419,7 @@ public boolean saveUploadedNetworkConfig(Path uploadPath) { private HashMap loadCameraConfigs(Connection conn) { HashMap loadedConfigurations = new HashMap<>(); - // Querry every single row of the cameras db + // Query every single row of the cameras db PreparedStatement query = null; try { query = diff --git a/photon-core/src/main/java/org/photonvision/common/dataflow/DataChangeSubscriber.java b/photon-core/src/main/java/org/photonvision/common/dataflow/DataChangeSubscriber.java index 9ebbd61052..92a06fdb67 100644 --- a/photon-core/src/main/java/org/photonvision/common/dataflow/DataChangeSubscriber.java +++ b/photon-core/src/main/java/org/photonvision/common/dataflow/DataChangeSubscriber.java @@ -21,7 +21,6 @@ import java.util.Objects; import org.photonvision.common.dataflow.events.DataChangeEvent; -@SuppressWarnings("rawtypes") public abstract class DataChangeSubscriber { public final List wantedSources; public final List wantedDestinations; diff --git a/photon-core/src/main/java/org/photonvision/common/dataflow/networktables/NTDataPublisher.java b/photon-core/src/main/java/org/photonvision/common/dataflow/networktables/NTDataPublisher.java index 0f7c3caa64..56bae44bd7 100644 --- a/photon-core/src/main/java/org/photonvision/common/dataflow/networktables/NTDataPublisher.java +++ b/photon-core/src/main/java/org/photonvision/common/dataflow/networktables/NTDataPublisher.java @@ -41,7 +41,7 @@ public class NTDataPublisher implements CVPipelineResultConsumer { private final NetworkTable rootTable = NetworkTablesManager.getInstance().kRootTable; - private NTTopicSet ts = new NTTopicSet(); + private final NTTopicSet ts = new NTTopicSet(); NTDataChangeListener pipelineIndexListener; private final Supplier pipelineIndexSupplier; @@ -181,15 +181,12 @@ public void accept(CVPipelineResult result) { } // Something in the result can sometimes be null -- so check probably too many things - if (result != null - && result.inputAndOutputFrame != null + if (result.inputAndOutputFrame != null && result.inputAndOutputFrame.frameStaticProperties != null && result.inputAndOutputFrame.frameStaticProperties.cameraCalibration != null) { var fsp = result.inputAndOutputFrame.frameStaticProperties; - if (fsp.cameraCalibration != null) { - ts.cameraIntrinsicsPublisher.accept(fsp.cameraCalibration.getIntrinsicsArr()); - ts.cameraDistortionPublisher.accept(fsp.cameraCalibration.getExtrinsicsArr()); - } + ts.cameraIntrinsicsPublisher.accept(fsp.cameraCalibration.getIntrinsicsArr()); + ts.cameraDistortionPublisher.accept(fsp.cameraCalibration.getExtrinsicsArr()); } else { ts.cameraIntrinsicsPublisher.accept(new double[] {}); ts.cameraDistortionPublisher.accept(new double[] {}); @@ -215,8 +212,8 @@ public static List simpleFromTrackedTargets(List pulses) throws PigpioException // ## extension ## // III on/off/delay * pulses - if (pulses == null || pulses.size() == 0) return 0; + if (pulses == null || pulses.isEmpty()) return 0; try { ByteBuffer bb = ByteBuffer.allocate(pulses.size() * 12); diff --git a/photon-core/src/main/java/org/photonvision/common/hardware/HardwareManager.java b/photon-core/src/main/java/org/photonvision/common/hardware/HardwareManager.java index c640730a7d..008724e9b7 100644 --- a/photon-core/src/main/java/org/photonvision/common/hardware/HardwareManager.java +++ b/photon-core/src/main/java/org/photonvision/common/hardware/HardwareManager.java @@ -48,9 +48,9 @@ public class HardwareManager { private final StatusLED statusLED; @SuppressWarnings("FieldCanBeLocal") - private IntegerSubscriber ledModeRequest; + private final IntegerSubscriber ledModeRequest; - private IntegerPublisher ledModeState; + private final IntegerPublisher ledModeState; @SuppressWarnings({"FieldCanBeLocal", "unused"}) private final NTDataChangeListener ledModeListener; diff --git a/photon-core/src/main/java/org/photonvision/common/hardware/PiVersion.java b/photon-core/src/main/java/org/photonvision/common/hardware/PiVersion.java index f0817f70ce..dbf23ac7e4 100644 --- a/photon-core/src/main/java/org/photonvision/common/hardware/PiVersion.java +++ b/photon-core/src/main/java/org/photonvision/common/hardware/PiVersion.java @@ -34,7 +34,7 @@ public enum PiVersion { private static final ShellExec shell = new ShellExec(true, false); private static final PiVersion currentPiVersion = calcPiVersion(); - private PiVersion(String s) { + PiVersion(String s) { this.identifier = s.toLowerCase(); } diff --git a/photon-core/src/main/java/org/photonvision/common/hardware/Platform.java b/photon-core/src/main/java/org/photonvision/common/hardware/Platform.java index 5644b53e0c..1c500ab722 100644 --- a/photon-core/src/main/java/org/photonvision/common/hardware/Platform.java +++ b/photon-core/src/main/java/org/photonvision/common/hardware/Platform.java @@ -17,7 +17,6 @@ package org.photonvision.common.hardware; -import com.jogamp.common.os.Platform.OSType; import edu.wpi.first.util.RuntimeDetector; import java.io.BufferedReader; import java.io.IOException; diff --git a/photon-core/src/main/java/org/photonvision/common/hardware/VisionLED.java b/photon-core/src/main/java/org/photonvision/common/hardware/VisionLED.java index 96d9937504..7d1d5273b3 100644 --- a/photon-core/src/main/java/org/photonvision/common/hardware/VisionLED.java +++ b/photon-core/src/main/java/org/photonvision/common/hardware/VisionLED.java @@ -46,7 +46,7 @@ public class VisionLED { private int mappedBrightnessPercentage; - private Consumer modeConsumer; + private final Consumer modeConsumer; public VisionLED( List ledPins, @@ -179,11 +179,7 @@ private void setInternal(VisionLEDMode newLedMode, boolean fromNT) { } currentLedMode = newLedMode; logger.info( - "Changing LED mode from \"" - + lastLedMode.toString() - + "\" to \"" - + newLedMode.toString() - + "\""); + "Changing LED mode from \"" + lastLedMode.toString() + "\" to \"" + newLedMode + "\""); } else { if (currentLedMode == VisionLEDMode.kDefault) { switch (newLedMode) { diff --git a/photon-core/src/main/java/org/photonvision/common/hardware/metrics/MetricsManager.java b/photon-core/src/main/java/org/photonvision/common/hardware/metrics/MetricsManager.java index f0320910e2..d38b527187 100644 --- a/photon-core/src/main/java/org/photonvision/common/hardware/metrics/MetricsManager.java +++ b/photon-core/src/main/java/org/photonvision/common/hardware/metrics/MetricsManager.java @@ -37,7 +37,7 @@ public class MetricsManager { CmdBase cmds; - private ShellExec runCommand = new ShellExec(true, true); + private final ShellExec runCommand = new ShellExec(true, true); public void setConfig(HardwareConfig config) { if (config.hasCommandsConfigured()) { @@ -153,8 +153,8 @@ public synchronized String execute(String command) { + "\nExit code: " + runCommand.getExitCode() + "\n Exception: " - + e.toString() - + sw.toString()); + + e + + sw); return ""; } } diff --git a/photon-core/src/main/java/org/photonvision/common/hardware/metrics/cmds/CmdBase.java b/photon-core/src/main/java/org/photonvision/common/hardware/metrics/cmds/CmdBase.java index 298ca7dd5d..69473ad9e1 100644 --- a/photon-core/src/main/java/org/photonvision/common/hardware/metrics/cmds/CmdBase.java +++ b/photon-core/src/main/java/org/photonvision/common/hardware/metrics/cmds/CmdBase.java @@ -35,6 +35,6 @@ public class CmdBase { public String diskUsageCommand = ""; public void initCmds(HardwareConfig config) { - return; // default - do nothing + // default - do nothing } } diff --git a/photon-core/src/main/java/org/photonvision/common/logging/Logger.java b/photon-core/src/main/java/org/photonvision/common/logging/Logger.java index 5972e3c750..b06fea13fa 100644 --- a/photon-core/src/main/java/org/photonvision/common/logging/Logger.java +++ b/photon-core/src/main/java/org/photonvision/common/logging/Logger.java @@ -21,12 +21,7 @@ import java.nio.file.Path; import java.text.ParseException; import java.text.SimpleDateFormat; -import java.util.ArrayList; -import java.util.Arrays; -import java.util.Date; -import java.util.HashMap; -import java.util.LinkedList; -import java.util.List; +import java.util.*; import java.util.function.Supplier; import org.apache.commons.lang3.tuple.Pair; import org.photonvision.common.configuration.ConfigManager; @@ -54,7 +49,7 @@ public class Logger { private static final List> uiBacklog = new ArrayList<>(); private static boolean connected = false; - private static UILogAppender uiLogAppender = new UILogAppender(); + private static final UILogAppender uiLogAppender = new UILogAppender(); private final String className; private final LogGroup group; @@ -133,7 +128,7 @@ public static void cleanLogs(Path folderToClean) { HashMap logFileStartDateMap = new HashMap<>(); // Remove any files from the list for which we can't parse a start date from their name. - // Simultaneously populate our HashMap with Date objects repeseting the file-name + // Simultaneously populate our HashMap with Date objects representing the file-name // indicated log start time. logFileList.removeIf( (File arg0) -> { @@ -160,7 +155,6 @@ public static void cleanLogs(Path folderToClean) { if (logCounter < MAX_LOGS_TO_KEEP) { // Skip over the first MAX_LOGS_TO_KEEP files logCounter++; - continue; } else { // Delete this file. file.delete(); @@ -332,7 +326,7 @@ public FileLogAppender(Path logFilePath) { 3000L); } catch (FileNotFoundException e) { out = null; - System.err.println("Unable to log to file " + logFilePath.toString()); + System.err.println("Unable to log to file " + logFilePath); } } diff --git a/photon-core/src/main/java/org/photonvision/common/networking/NetworkManager.java b/photon-core/src/main/java/org/photonvision/common/networking/NetworkManager.java index 6b6a13b031..22543c4bb3 100644 --- a/photon-core/src/main/java/org/photonvision/common/networking/NetworkManager.java +++ b/photon-core/src/main/java/org/photonvision/common/networking/NetworkManager.java @@ -54,7 +54,7 @@ public void initialize(boolean shouldManage) { } // always set hostname - if (config.hostname.length() > 0) { + if (!config.hostname.isEmpty()) { try { var shell = new ShellExec(true, false); shell.executeBashCommand("cat /etc/hostname | tr -d \" \\t\\n\\r\""); @@ -107,7 +107,7 @@ public void initialize(boolean shouldManage) { } } else if (config.connectionType == NetworkMode.STATIC) { var shell = new ShellExec(); - if (config.staticIp.length() > 0) { + if (!config.staticIp.isEmpty()) { try { shell.executeBashCommand( config @@ -116,7 +116,7 @@ public void initialize(boolean shouldManage) { .replace(NetworkConfig.NM_IP_STRING, config.staticIp)); if (Platform.isRaspberryPi()) { - // Pi's need to manually have their interface adjusted?? and the 5 second sleep is + // Pi's need to manually have their interface adjusted?? and the 5-second sleep is // integral in my testing (Matt) shell.executeBashCommand( "sh -c 'nmcli con down " @@ -125,7 +125,7 @@ public void initialize(boolean shouldManage) { + config.getEscapedInterfaceName() + "'"); } else { - // for now just bring down /up -- more testing needed on beelink et al + // for now just bring down /up -- more testing needed on beelink et al. shell.executeBashCommand( "sh -c 'nmcli con down " + config.getEscapedInterfaceName() diff --git a/photon-core/src/main/java/org/photonvision/common/networking/NetworkUtils.java b/photon-core/src/main/java/org/photonvision/common/networking/NetworkUtils.java index 2bcf0072a0..cf84309e57 100644 --- a/photon-core/src/main/java/org/photonvision/common/networking/NetworkUtils.java +++ b/photon-core/src/main/java/org/photonvision/common/networking/NetworkUtils.java @@ -31,12 +31,12 @@ public class NetworkUtils { private static final Logger logger = new Logger(NetworkUtils.class, LogGroup.General); - public static enum NMType { + public enum NMType { NMTYPE_ETHERNET("ethernet"), NMTYPE_WIFI("wifi"), NMTYPE_UNKNOWN(""); - private NMType(String id) { + NMType(String id) { identifier = id; } @@ -59,7 +59,7 @@ public NMDeviceInfo(String c, String d, String type) { nmType = NMType.typeForString(type); } - public final String connName; // Human readable name used by "nmcli con" + public final String connName; // Human-readable name used by "nmcli con" public final String devName; // underlying device, used by dhclient public final NMType nmType; @@ -108,15 +108,15 @@ public static List getAllInterfaces() { logger.error("Could not get active NM ifaces!", e); } - logger.debug("Found network interfaces:\n" + ret.toString()); + logger.debug("Found network interfaces:\n" + ret); allInterfaces = ret; return ret; } public static List getAllActiveInterfaces() { - // Seems like if a interface exists but isn't actually connected, the connection name will be an - // empty string. Check here and only return connections with non-empty names + // Seems like if an interface exists but isn't actually connected, the connection name will be + // an empty string. Check here and only return connections with non-empty names return getAllInterfaces().stream() .filter(it -> !it.connName.trim().isEmpty()) .collect(Collectors.toList()); diff --git a/photon-core/src/main/java/org/photonvision/common/networking/RoborioFinder.java b/photon-core/src/main/java/org/photonvision/common/networking/RoborioFinder.java index f94beb6123..e6b42112fc 100644 --- a/photon-core/src/main/java/org/photonvision/common/networking/RoborioFinder.java +++ b/photon-core/src/main/java/org/photonvision/common/networking/RoborioFinder.java @@ -42,7 +42,7 @@ public static RoborioFinder getInstance() { public void findRios() { HashMap map = new HashMap<>(); var subMap = new HashMap(); - // Seperate from the above so we don't hold stuff up + // Separate from the above so we don't hold stuff up System.setProperty("java.net.preferIPv4Stack", "true"); subMap.put( "deviceips", diff --git a/photon-core/src/main/java/org/photonvision/common/util/ShellExec.java b/photon-core/src/main/java/org/photonvision/common/util/ShellExec.java index 159be868ea..c8433ec158 100644 --- a/photon-core/src/main/java/org/photonvision/common/util/ShellExec.java +++ b/photon-core/src/main/java/org/photonvision/common/util/ShellExec.java @@ -22,12 +22,13 @@ import org.photonvision.common.logging.Logger; /** Execute external process and optionally read output buffer. */ -@SuppressWarnings({"unused", "ConstantConditions"}) +@SuppressWarnings({"unused"}) public class ShellExec { private static final Logger logger = new Logger(ShellExec.class, LogGroup.General); private int exitCode; - private boolean readOutput, readError; + private final boolean readOutput; + private final boolean readError; private StreamGobbler errorGobbler, outputGobbler; public ShellExec() { @@ -55,7 +56,7 @@ public int executeBashCommand(String command, boolean wait) throws IOException { boolean success = false; Runtime r = Runtime.getRuntime(); - // Use bash -c so we can handle things like multi commands separated by ; and + // Use bash -c, so we can handle things like multi commands separated by ; and // things like quotes, $, |, and \. My tests show that command comes as // one argument to bash, so we do not need to quote it to make it one thing. // Also, exec may object if it does not have an executable file as the first thing, @@ -160,8 +161,8 @@ public String getError() { */ @SuppressWarnings("WeakerAccess") private static class StreamGobbler extends Thread { - private InputStream is; - private StringBuilder output; + private final InputStream is; + private final StringBuilder output; private volatile boolean completed; // mark volatile to guarantee a thread safety public StreamGobbler(InputStream is, boolean readStream) { diff --git a/photon-core/src/main/java/org/photonvision/common/util/TestUtils.java b/photon-core/src/main/java/org/photonvision/common/util/TestUtils.java index f547ba71ca..d109f97834 100644 --- a/photon-core/src/main/java/org/photonvision/common/util/TestUtils.java +++ b/photon-core/src/main/java/org/photonvision/common/util/TestUtils.java @@ -245,7 +245,7 @@ Path getPath() { } public static Path getResourcesFolderPath(boolean testMode) { - System.out.println("CWD: " + Path.of("").toAbsolutePath().toString()); + System.out.println("CWD: " + Path.of("").toAbsolutePath()); // VSCode likes to make this path relative to the wrong root directory, so a fun hack to tell // if it's wrong @@ -362,7 +362,7 @@ public static CameraCalibrationCoefficients getLaptop() { return getCoeffs("laptop.json", true); } - private static int DefaultTimeoutMillis = 5000; + private static final int DefaultTimeoutMillis = 5000; public static void showImage(Mat frame, String title, int timeoutMs) { if (frame.empty()) return; diff --git a/photon-core/src/main/java/org/photonvision/common/util/TimedTaskManager.java b/photon-core/src/main/java/org/photonvision/common/util/TimedTaskManager.java index 4b613bdeb5..7107faae32 100644 --- a/photon-core/src/main/java/org/photonvision/common/util/TimedTaskManager.java +++ b/photon-core/src/main/java/org/photonvision/common/util/TimedTaskManager.java @@ -40,9 +40,7 @@ private static class CaughtThreadFactory implements ThreadFactory { public Thread newThread(@NotNull Runnable r) { Thread thread = defaultThreadFactory.newThread(r); thread.setUncaughtExceptionHandler( - (t, e) -> { - logger.error("TimedTask threw uncaught exception!", e); - }); + (t, e) -> logger.error("TimedTask threw uncaught exception!", e)); return thread; } } diff --git a/photon-core/src/main/java/org/photonvision/common/util/math/MathUtils.java b/photon-core/src/main/java/org/photonvision/common/util/math/MathUtils.java index 01bff3237c..526311afc5 100644 --- a/photon-core/src/main/java/org/photonvision/common/util/math/MathUtils.java +++ b/photon-core/src/main/java/org/photonvision/common/util/math/MathUtils.java @@ -20,11 +20,7 @@ import edu.wpi.first.math.MatBuilder; import edu.wpi.first.math.Nat; import edu.wpi.first.math.VecBuilder; -import edu.wpi.first.math.geometry.CoordinateSystem; -import edu.wpi.first.math.geometry.Pose3d; -import edu.wpi.first.math.geometry.Quaternion; -import edu.wpi.first.math.geometry.Rotation3d; -import edu.wpi.first.math.geometry.Transform3d; +import edu.wpi.first.math.geometry.*; import edu.wpi.first.math.util.Units; import edu.wpi.first.util.WPIUtilJNI; import java.util.Arrays; @@ -92,7 +88,7 @@ public static double getPercentile(List list, double p) { throw new IllegalArgumentException("invalid quantile value: " + p); } - if (list.size() == 0) { + if (list.isEmpty()) { return Double.NaN; } if (list.size() == 1) { @@ -206,7 +202,7 @@ public static Pose3d convertOpenCVtoPhotonPose(Transform3d cameraToTarget3d) { new Rotation3d(VecBuilder.fill(1, 0, 0), Units.degreesToRadians(180)); /** - * Apply a 180 degree rotation about X to the rotation component of a given Apriltag pose. This + * Apply a 180-degree rotation about X to the rotation component of a given Apriltag pose. This * aligns it with the OpenCV poses we use in other places. */ public static Transform3d convertApriltagtoOpenCV(Transform3d pose) { diff --git a/photon-core/src/main/java/org/photonvision/common/util/numbers/NumberCouple.java b/photon-core/src/main/java/org/photonvision/common/util/numbers/NumberCouple.java index e555e361f9..9a6047c797 100644 --- a/photon-core/src/main/java/org/photonvision/common/util/numbers/NumberCouple.java +++ b/photon-core/src/main/java/org/photonvision/common/util/numbers/NumberCouple.java @@ -60,11 +60,7 @@ public boolean equals(Object obj) { return false; } - if (!couple.second.equals(second)) { - return false; - } - - return true; + return couple.second.equals(second); } @JsonIgnore diff --git a/photon-core/src/main/java/org/photonvision/raspi/LibCameraJNI.java b/photon-core/src/main/java/org/photonvision/raspi/LibCameraJNI.java index 4ebc2c8735..a75ae2e579 100644 --- a/photon-core/src/main/java/org/photonvision/raspi/LibCameraJNI.java +++ b/photon-core/src/main/java/org/photonvision/raspi/LibCameraJNI.java @@ -28,7 +28,7 @@ public class LibCameraJNI { private static boolean libraryLoaded = false; - private static Logger logger = new Logger(LibCameraJNI.class, LogGroup.Camera); + private static final Logger logger = new Logger(LibCameraJNI.class, LogGroup.Camera); public static final Object CAMERA_LOCK = new Object(); @@ -120,7 +120,7 @@ public static boolean isSupported() { /** * Starts the camera thresholder and display threads running. Make sure that this function is - * called syncronously with stopCamera and returnFrame! + * called synchronously with stopCamera and returnFrame! */ public static native boolean startCamera(); @@ -141,7 +141,7 @@ public static native boolean setThresholds( // Exposure time, in microseconds public static native boolean setExposure(int exposureUs); - // Set brighness on [-1, 1] + // Set brightness on [-1, 1] public static native boolean setBrightness(double brightness); // Unknown ranges for red and blue AWB gain @@ -164,18 +164,18 @@ public static native boolean setThresholds( // Analog gain multiplier to apply to all color channels, on [1, Big Number] public static native boolean setAnalogGain(double analog); - /** Block until a new frame is avaliable from native code. */ + /** Block until a new frame is available from native code. */ public static native boolean awaitNewFrame(); /** - * Get a pointer to the most recent color mat generated. Call this immediatly after awaitNewFrame, - * and call onlly once per new frame! + * Get a pointer to the most recent color mat generated. Call this immediately after + * awaitNewFrame, and call only once per new frame! */ public static native long takeColorFrame(); /** - * Get a pointer to the most recent processed mat generated. Call this immediatly after - * awaitNewFrame, and call onlly once per new frame! + * Get a pointer to the most recent processed mat generated. Call this immediately after + * awaitNewFrame, and call only once per new frame! */ public static native long takeProcessedFrame(); @@ -186,6 +186,6 @@ public static native boolean setThresholds( public static native int getGpuProcessType(); - // /** Release a frame pointer back to the libcamera driver code to be filled again */ + // Release a frame pointer back to the libcamera driver code to be filled again */ // public static native long returnFrame(long frame); } diff --git a/photon-core/src/main/java/org/photonvision/vision/apriltag/AprilTagFamily.java b/photon-core/src/main/java/org/photonvision/vision/apriltag/AprilTagFamily.java index afbfc463a2..8fbda02683 100644 --- a/photon-core/src/main/java/org/photonvision/vision/apriltag/AprilTagFamily.java +++ b/photon-core/src/main/java/org/photonvision/vision/apriltag/AprilTagFamily.java @@ -28,7 +28,7 @@ public enum AprilTagFamily { kTagCustom48h11; public String getNativeName() { - // We wanna strip the leading kT and replace with "t" + // We want to strip the leading kT and replace with "t" return this.name().replaceFirst("kT", "t"); } } diff --git a/photon-core/src/main/java/org/photonvision/vision/aruco/ArucoDetectorParams.java b/photon-core/src/main/java/org/photonvision/vision/aruco/ArucoDetectorParams.java index f6af5d3047..24ea8dafab 100644 --- a/photon-core/src/main/java/org/photonvision/vision/aruco/ArucoDetectorParams.java +++ b/photon-core/src/main/java/org/photonvision/vision/aruco/ArucoDetectorParams.java @@ -48,9 +48,9 @@ public void setDecimation(float decimate) { logger.info("Setting decimation from " + m_decimate + " to " + decimate); - // We only need to mutate the parameters -- the detector keeps a poitner to the parameters + // We only need to mutate the parameters -- the detector keeps a pointer to the parameters // object internally, so it should automatically update - parameters.set_aprilTagQuadDecimate((float) decimate); + parameters.set_aprilTagQuadDecimate(decimate); m_decimate = decimate; } diff --git a/photon-core/src/main/java/org/photonvision/vision/aruco/PhotonArucoDetector.java b/photon-core/src/main/java/org/photonvision/vision/aruco/PhotonArucoDetector.java index 0963a2812a..6bb10f7baa 100644 --- a/photon-core/src/main/java/org/photonvision/vision/aruco/PhotonArucoDetector.java +++ b/photon-core/src/main/java/org/photonvision/vision/aruco/PhotonArucoDetector.java @@ -58,7 +58,7 @@ public PhotonArucoDetector() { ids = new Mat(); tvecs = new Mat(); rvecs = new Mat(); - corners = new ArrayList(); + corners = new ArrayList<>(); tagPose = new Pose3d(); translation = new Translation3d(); rotation = new Rotation3d(); diff --git a/photon-core/src/main/java/org/photonvision/vision/camera/FileVisionSource.java b/photon-core/src/main/java/org/photonvision/vision/camera/FileVisionSource.java index e028dfe369..951135fcf4 100644 --- a/photon-core/src/main/java/org/photonvision/vision/camera/FileVisionSource.java +++ b/photon-core/src/main/java/org/photonvision/vision/camera/FileVisionSource.java @@ -35,7 +35,7 @@ public class FileVisionSource extends VisionSource { public FileVisionSource(CameraConfiguration cameraConfiguration) { super(cameraConfiguration); var calibration = - cameraConfiguration.calibrations.size() > 0 + !cameraConfiguration.calibrations.isEmpty() ? cameraConfiguration.calibrations.get(0) : null; frameProvider = diff --git a/photon-core/src/main/java/org/photonvision/vision/camera/LibcameraGpuSettables.java b/photon-core/src/main/java/org/photonvision/vision/camera/LibcameraGpuSettables.java index 22c76131aa..7e0bd5c5c7 100644 --- a/photon-core/src/main/java/org/photonvision/vision/camera/LibcameraGpuSettables.java +++ b/photon-core/src/main/java/org/photonvision/vision/camera/LibcameraGpuSettables.java @@ -132,7 +132,7 @@ public void setExposure(double exposure) { // If we set exposure too low, libcamera crashes or slows down // Very weird and smelly // For now, band-aid this by just not setting it lower than the "it breaks" limit - // Limit is different depending on camera. + // is different depending on camera. if (sensorModel == LibCameraJNI.SensorModel.OV9281) { if (exposure < 6.0) { exposure = 6.0; diff --git a/photon-core/src/main/java/org/photonvision/vision/camera/QuirkyCamera.java b/photon-core/src/main/java/org/photonvision/vision/camera/QuirkyCamera.java index 780a12786e..da2dc835cb 100644 --- a/photon-core/src/main/java/org/photonvision/vision/camera/QuirkyCamera.java +++ b/photon-core/src/main/java/org/photonvision/vision/camera/QuirkyCamera.java @@ -105,7 +105,7 @@ public static QuirkyCamera getQuirkyCamera(int usbVid, int usbPid) { public static QuirkyCamera getQuirkyCamera(int usbVid, int usbPid, String baseName) { for (var qc : quirkyCameras) { - boolean hasBaseName = !qc.baseName.equals(""); + boolean hasBaseName = !qc.baseName.isEmpty(); boolean matchesBaseName = qc.baseName.equals(baseName) || !hasBaseName; if (qc.usbVid == usbVid && qc.usbPid == usbPid && matchesBaseName) { return qc; diff --git a/photon-core/src/main/java/org/photonvision/vision/camera/USBCameraSource.java b/photon-core/src/main/java/org/photonvision/vision/camera/USBCameraSource.java index cdad1ca24e..ad235da26a 100644 --- a/photon-core/src/main/java/org/photonvision/vision/camera/USBCameraSource.java +++ b/photon-core/src/main/java/org/photonvision/vision/camera/USBCameraSource.java @@ -18,7 +18,10 @@ package org.photonvision.vision.camera; import edu.wpi.first.cameraserver.CameraServer; -import edu.wpi.first.cscore.*; +import edu.wpi.first.cscore.CvSink; +import edu.wpi.first.cscore.UsbCamera; +import edu.wpi.first.cscore.VideoException; +import edu.wpi.first.cscore.VideoMode; import java.util.*; import java.util.stream.Collectors; import org.photonvision.common.configuration.CameraConfiguration; @@ -120,8 +123,8 @@ public void setAutoExposure(boolean cameraAutoExposure) { if (!cameraAutoExposure) { // Pick a bunch of reasonable setting defaults for vision processing retroreflective camera.getProperty("auto_exposure_bias").set(0); - camera.getProperty("iso_sensitivity_auto").set(0); // Disable auto ISO adjustement - camera.getProperty("iso_sensitivity").set(0); // Manual ISO adjustement + camera.getProperty("iso_sensitivity_auto").set(0); // Disable auto ISO adjustment + camera.getProperty("iso_sensitivity").set(0); // Manual ISO adjustment camera.getProperty("white_balance_auto_preset").set(2); // Auto white-balance disabled camera.getProperty("auto_exposure").set(1); // auto exposure disabled } else { @@ -129,7 +132,7 @@ public void setAutoExposure(boolean cameraAutoExposure) { // nice-for-humans camera.getProperty("auto_exposure_bias").set(12); camera.getProperty("iso_sensitivity_auto").set(1); - camera.getProperty("iso_sensitivity").set(1); // Manual ISO adjustement by default + camera.getProperty("iso_sensitivity").set(1); // Manual ISO adjustment by default camera.getProperty("white_balance_auto_preset").set(1); // Auto white-balance enabled camera.getProperty("auto_exposure").set(0); // auto exposure enabled } @@ -179,15 +182,14 @@ public void setExposure(double exposure) { try { int scaledExposure = 1; if (cameraQuirks.hasQuirk(CameraQuirk.PiCam)) { - scaledExposure = - (int) Math.round(timeToPiCamRawExposure(pctToExposureTimeUs(exposure))); - logger.debug("Setting camera raw exposure to " + Integer.toString(scaledExposure)); + scaledExposure = Math.round(timeToPiCamRawExposure(pctToExposureTimeUs(exposure))); + logger.debug("Setting camera raw exposure to " + scaledExposure); camera.getProperty("raw_exposure_time_absolute").set(scaledExposure); camera.getProperty("raw_exposure_time_absolute").set(scaledExposure); } else { scaledExposure = (int) Math.round(exposure); - logger.debug("Setting camera exposure to " + Integer.toString(scaledExposure)); + logger.debug("Setting camera exposure to " + scaledExposure); camera.setExposureManual(scaledExposure); camera.setExposureManual(scaledExposure); } @@ -264,9 +266,7 @@ public HashMap getAllVideoModes() { } else { modes = camera.enumerateVideoModes(); } - for (int i = 0; i < modes.length; i++) { - var videoMode = modes[i]; - + for (VideoMode videoMode : modes) { // Filter grey modes if (videoMode.pixelFormat == VideoMode.PixelFormat.kGray || videoMode.pixelFormat == VideoMode.PixelFormat.kUnknown) { diff --git a/photon-core/src/main/java/org/photonvision/vision/frame/FrameProvider.java b/photon-core/src/main/java/org/photonvision/vision/frame/FrameProvider.java index 3c405632de..70de9c5115 100644 --- a/photon-core/src/main/java/org/photonvision/vision/frame/FrameProvider.java +++ b/photon-core/src/main/java/org/photonvision/vision/frame/FrameProvider.java @@ -24,15 +24,15 @@ public interface FrameProvider extends Supplier { String getName(); - /** Ask the camera to produce a certain kind of processed image (eg HSV or greyscale) */ - public void requestFrameThresholdType(FrameThresholdType type); + /** Ask the camera to produce a certain kind of processed image (e.g. HSV or greyscale) */ + void requestFrameThresholdType(FrameThresholdType type); /** Ask the camera to rotate frames it outputs */ - public void requestFrameRotation(ImageRotationMode rotationMode); + void requestFrameRotation(ImageRotationMode rotationMode); /** Ask the camera to provide either the input, output, or both frames. */ - public void requestFrameCopies(boolean copyInput, boolean copyOutput); + void requestFrameCopies(boolean copyInput, boolean copyOutput); /** Ask the camera to rotate frames it outputs */ - public void requestHsvSettings(HSVPipe.HSVParams params); + void requestHsvSettings(HSVPipe.HSVParams params); } diff --git a/photon-core/src/main/java/org/photonvision/vision/frame/consumer/FileSaveFrameConsumer.java b/photon-core/src/main/java/org/photonvision/vision/frame/consumer/FileSaveFrameConsumer.java index e9773122a0..2552b5fbdb 100644 --- a/photon-core/src/main/java/org/photonvision/vision/frame/consumer/FileSaveFrameConsumer.java +++ b/photon-core/src/main/java/org/photonvision/vision/frame/consumer/FileSaveFrameConsumer.java @@ -33,8 +33,8 @@ public class FileSaveFrameConsumer implements Consumer { // Formatters to generate unique, timestamped file names - private static String FILE_PATH = ConfigManager.getInstance().getImageSavePath().toString(); - private static String FILE_EXTENSION = ".jpg"; + private static final String FILE_PATH = ConfigManager.getInstance().getImageSavePath().toString(); + private static final String FILE_EXTENSION = ".jpg"; DateFormat df = new SimpleDateFormat("yyyy-MM-dd"); DateFormat tf = new SimpleDateFormat("hhmmssSS"); private final String NT_SUFFIX = "SaveImgCmd"; @@ -44,7 +44,7 @@ public class FileSaveFrameConsumer implements Consumer { private final Logger logger; private long imgSaveCountInternal = 0; private String camNickname; - private String fnamePrefix; + private final String fnamePrefix; private IntegerEntry entry; public FileSaveFrameConsumer(String camNickname, String streamPrefix) { diff --git a/photon-core/src/main/java/org/photonvision/vision/frame/consumer/MJPGFrameConsumer.java b/photon-core/src/main/java/org/photonvision/vision/frame/consumer/MJPGFrameConsumer.java index b070e372d5..06f9bf986b 100644 --- a/photon-core/src/main/java/org/photonvision/vision/frame/consumer/MJPGFrameConsumer.java +++ b/photon-core/src/main/java/org/photonvision/vision/frame/consumer/MJPGFrameConsumer.java @@ -106,7 +106,6 @@ public class MJPGFrameConsumer { private CvSource cvSource; private MjpegServer mjpegServer; - @SuppressWarnings("FieldCanBeLocal") private VideoListener listener; private final NetworkTable table; diff --git a/photon-core/src/main/java/org/photonvision/vision/frame/provider/CpuImageProcessor.java b/photon-core/src/main/java/org/photonvision/vision/frame/provider/CpuImageProcessor.java index f9f28c0a51..034ae6615e 100644 --- a/photon-core/src/main/java/org/photonvision/vision/frame/provider/CpuImageProcessor.java +++ b/photon-core/src/main/java/org/photonvision/vision/frame/provider/CpuImageProcessor.java @@ -30,7 +30,7 @@ import org.photonvision.vision.pipe.impl.RotateImagePipe; public abstract class CpuImageProcessor implements FrameProvider { - protected class CapturedFrame { + protected static class CapturedFrame { CVMat colorImage; FrameStaticProperties staticProps; long captureTimestamp; @@ -119,6 +119,5 @@ public void requestHsvSettings(HSVPipe.HSVParams params) { @Override public void requestFrameCopies(boolean copyInput, boolean copyOutput) { // We don't actually do zero-copy, so this method is a no-op - return; } } diff --git a/photon-core/src/main/java/org/photonvision/vision/frame/provider/FileFrameProvider.java b/photon-core/src/main/java/org/photonvision/vision/frame/provider/FileFrameProvider.java index 8c7272ba21..315e4e3de3 100644 --- a/photon-core/src/main/java/org/photonvision/vision/frame/provider/FileFrameProvider.java +++ b/photon-core/src/main/java/org/photonvision/vision/frame/provider/FileFrameProvider.java @@ -63,7 +63,7 @@ public FileFrameProvider(Path path, double fov, CameraCalibrationCoefficients ca public FileFrameProvider( Path path, double fov, int maxFPS, CameraCalibrationCoefficients calibration) { if (!Files.exists(path)) - throw new RuntimeException("Invalid path for image: " + path.toAbsolutePath().toString()); + throw new RuntimeException("Invalid path for image: " + path.toAbsolutePath()); this.path = path; this.millisDelay = 1000 / maxFPS; diff --git a/photon-core/src/main/java/org/photonvision/vision/opencv/CVShape.java b/photon-core/src/main/java/org/photonvision/vision/opencv/CVShape.java index 71f21cc1d4..99b8c2f107 100644 --- a/photon-core/src/main/java/org/photonvision/vision/opencv/CVShape.java +++ b/photon-core/src/main/java/org/photonvision/vision/opencv/CVShape.java @@ -32,7 +32,7 @@ public class CVShape implements Releasable { private MatOfPoint3f customTarget = null; - private MatOfPoint2f approxCurve = new MatOfPoint2f(); + private final MatOfPoint2f approxCurve = new MatOfPoint2f(); public CVShape(Contour contour, ContourShape shape) { this.contour = contour; diff --git a/photon-core/src/main/java/org/photonvision/vision/opencv/Contour.java b/photon-core/src/main/java/org/photonvision/vision/opencv/Contour.java index ea89c8b50a..181de0b3b3 100644 --- a/photon-core/src/main/java/org/photonvision/vision/opencv/Contour.java +++ b/photon-core/src/main/java/org/photonvision/vision/opencv/Contour.java @@ -21,13 +21,7 @@ import java.util.Collection; import java.util.Comparator; import org.jetbrains.annotations.Nullable; -import org.opencv.core.CvType; -import org.opencv.core.MatOfInt; -import org.opencv.core.MatOfPoint; -import org.opencv.core.MatOfPoint2f; -import org.opencv.core.Point; -import org.opencv.core.Rect; -import org.opencv.core.RotatedRect; +import org.opencv.core.*; import org.opencv.imgproc.Imgproc; import org.opencv.imgproc.Moments; import org.photonvision.common.util.math.MathUtils; diff --git a/photon-core/src/main/java/org/photonvision/vision/opencv/ContourSortMode.java b/photon-core/src/main/java/org/photonvision/vision/opencv/ContourSortMode.java index d4cf359e49..2ceff908ec 100644 --- a/photon-core/src/main/java/org/photonvision/vision/opencv/ContourSortMode.java +++ b/photon-core/src/main/java/org/photonvision/vision/opencv/ContourSortMode.java @@ -35,7 +35,7 @@ public enum ContourSortMode { (Math.pow(rect.getMinAreaRect().center.y, 2) + Math.pow(rect.getMinAreaRect().center.x, 2)))); - private Comparator m_comparator; + private final Comparator m_comparator; ContourSortMode(Comparator comparator) { m_comparator = comparator; diff --git a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/AprilTagDetectionPipeParams.java b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/AprilTagDetectionPipeParams.java index f7c8ab2b20..ab52d7bcfb 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/AprilTagDetectionPipeParams.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/AprilTagDetectionPipeParams.java @@ -46,8 +46,7 @@ public boolean equals(Object obj) { AprilTagDetectionPipeParams other = (AprilTagDetectionPipeParams) obj; if (family != other.family) return false; if (detectorParams == null) { - if (other.detectorParams != null) return false; - } else if (!detectorParams.equals(other.detectorParams)) return false; - return true; + return other.detectorParams == null; + } else return detectorParams.equals(other.detectorParams); } } diff --git a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/AprilTagPoseEstimatorPipe.java b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/AprilTagPoseEstimatorPipe.java index 1dc118a3eb..9738202e3e 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/AprilTagPoseEstimatorPipe.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/AprilTagPoseEstimatorPipe.java @@ -46,7 +46,7 @@ public AprilTagPoseEstimatorPipe() { @Override protected AprilTagPoseEstimate process(AprilTagDetection in) { // Save the corner points of our detection to an array - Point corners[] = new Point[4]; + Point[] corners = new Point[4]; for (int i = 0; i < 4; i++) { corners[i] = new Point(in.getCornerX(i), in.getCornerY(i)); } @@ -128,8 +128,7 @@ public boolean equals(Object obj) { if (config == null) { if (other.config != null) return false; } else if (!config.equals(other.config)) return false; - if (nIters != other.nIters) return false; - return true; + return nIters == other.nIters; } } } diff --git a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/CalculateFPSPipe.java b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/CalculateFPSPipe.java index 7789c70b60..113da4d357 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/CalculateFPSPipe.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/CalculateFPSPipe.java @@ -23,7 +23,7 @@ public class CalculateFPSPipe extends CVPipe { - private LinearFilter fpsFilter = LinearFilter.movingAverage(20); + private final LinearFilter fpsFilter = LinearFilter.movingAverage(20); StopWatch clock = new StopWatch(); @Override diff --git a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/Calibrate3dPipe.java b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/Calibrate3dPipe.java index a454400bb9..bfca09d6fd 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/Calibrate3dPipe.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/Calibrate3dPipe.java @@ -24,7 +24,9 @@ import java.util.stream.Collectors; import org.apache.commons.lang3.tuple.Triple; import org.opencv.calib3d.Calib3d; -import org.opencv.core.*; +import org.opencv.core.Mat; +import org.opencv.core.MatOfDouble; +import org.opencv.core.Size; import org.photonvision.common.logging.LogGroup; import org.photonvision.common.logging.Logger; import org.photonvision.vision.calibration.CameraCalibrationCoefficients; @@ -38,24 +40,24 @@ public class Calibrate3dPipe Calibrate3dPipe.CalibratePipeParams> { // Camera matrix stores the center of the image and focal length across the x and y-axis in a 3x3 // matrix - private Mat cameraMatrix = new Mat(); + private final Mat cameraMatrix = new Mat(); // Stores the radical and tangential distortion in a 5x1 matrix - private MatOfDouble distortionCoefficients = new MatOfDouble(); + private final MatOfDouble distortionCoefficients = new MatOfDouble(); - // For loggging + // For logging private static final Logger logger = new Logger(Calibrate3dPipe.class, LogGroup.General); // Translational and rotational matrices - private List rvecs = new ArrayList<>(); - private List tvecs = new ArrayList<>(); + private final List rvecs = new ArrayList<>(); + private final List tvecs = new ArrayList<>(); // The Standard deviation of the estimated parameters - private Mat stdDeviationsIntrinsics = new Mat(); - private Mat stdDeviationsExtrinsics = new Mat(); + private final Mat stdDeviationsIntrinsics = new Mat(); + private final Mat stdDeviationsExtrinsics = new Mat(); // Contains the re projection error of each snapshot by re projecting the corners we found and - // finding the euclidean distance between the actual corners. - private Mat perViewErrors = new Mat(); + // finding the Euclidean distance between the actual corners. + private final Mat perViewErrors = new Mat(); // RMS of the calibration private double calibrationAccuracy; @@ -135,7 +137,7 @@ protected CameraCalibrationCoefficients process(List> in) } // Calculate standard deviation of the RMS error of the snapshots - private static double calculateSD(double numArray[]) { + private static double calculateSD(double[] numArray) { double sum = 0.0, standardDeviation = 0.0; int length = numArray.length; diff --git a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/CornerDetectionPipe.java b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/CornerDetectionPipe.java index ed3ae46e54..ff7f6fd3ea 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/CornerDetectionPipe.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/CornerDetectionPipe.java @@ -18,10 +18,7 @@ package org.photonvision.vision.pipe.impl; import edu.wpi.first.math.geometry.Translation2d; -import java.util.ArrayList; -import java.util.Arrays; -import java.util.Comparator; -import java.util.List; +import java.util.*; import org.opencv.core.MatOfPoint2f; import org.opencv.core.Point; import org.opencv.imgproc.Imgproc; @@ -42,18 +39,10 @@ protected List process(List targetList) { for (var target : targetList) { // detect corners. Might implement more algorithms later but // APPROX_POLY_DP_AND_EXTREME_CORNERS should be year agnostic - switch (params.cornerDetectionStrategy) { - case APPROX_POLY_DP_AND_EXTREME_CORNERS: - { - var targetCorners = - detectExtremeCornersByApproxPolyDp(target, params.calculateConvexHulls); - target.setTargetCorners(targetCorners); - break; - } - default: - { - break; - } + if (Objects.requireNonNull(params.cornerDetectionStrategy) + == DetectionStrategy.APPROX_POLY_DP_AND_EXTREME_CORNERS) { + var targetCorners = detectExtremeCornersByApproxPolyDp(target, params.calculateConvexHulls); + target.setTargetCorners(targetCorners); } } return targetList; @@ -133,7 +122,7 @@ private List detectExtremeCornersByApproxPolyDp(TrackedTarget target, boo we want a number between 0 and 0.16 out of a percentage from 0 to 100 so take accuracy and divide by 600 - Furthermore, we know that the contour is open if we haven't done convex hulls + Furthermore, we know that the contour is open if we haven't done convex hulls, and it has subcontours. */ var isOpen = !convexHull && target.hasSubContours(); @@ -158,7 +147,7 @@ private List detectExtremeCornersByApproxPolyDp(TrackedTarget target, boo var distanceToTrComparator = Comparator.comparingDouble((Point p) -> distanceBetween(p, boundingBoxCorners.get(3))); - // top left and top right are the poly corners closest to the bouding box tl and tr + // top left and top right are the poly corners closest to the bounding box tl and tr pointList.sort(distanceToTlComparator); var tl = pointList.get(0); pointList.remove(tl); diff --git a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/Draw2dCrosshairPipe.java b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/Draw2dCrosshairPipe.java index 913ad5dd22..53f5852e72 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/Draw2dCrosshairPipe.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/Draw2dCrosshairPipe.java @@ -17,7 +17,7 @@ package org.photonvision.vision.pipe.impl; -import java.awt.Color; +import java.awt.*; import java.util.List; import org.apache.commons.lang3.tuple.Pair; import org.opencv.core.Mat; @@ -62,7 +62,7 @@ protected Void process(Pair> in) { } break; case Dual: - if (in.getRight().size() >= 1) { + if (!in.getRight().isEmpty()) { var target = in.getRight().get(0); if (target != null) { var area = target.getArea(); diff --git a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/Draw3dTargetsPipe.java b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/Draw3dTargetsPipe.java index a3668f99de..b88bd0ba17 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/Draw3dTargetsPipe.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/Draw3dTargetsPipe.java @@ -22,12 +22,8 @@ import java.util.List; import org.apache.commons.lang3.tuple.Pair; import org.opencv.calib3d.Calib3d; -import org.opencv.core.Mat; -import org.opencv.core.MatOfPoint; -import org.opencv.core.MatOfPoint2f; -import org.opencv.core.MatOfPoint3f; +import org.opencv.core.*; import org.opencv.core.Point; -import org.opencv.core.Point3; import org.opencv.imgproc.Imgproc; import org.photonvision.common.logging.LogGroup; import org.photonvision.common.logging.Logger; @@ -95,7 +91,7 @@ protected Void process(Pair> in) { jac); if (params.redistortPoints) { - // Distort the points so they match the image they're being overlaid on + // Distort the points, so they match the image they're being overlaid on distortPoints(tempMat, tempMat); } @@ -111,7 +107,7 @@ protected Void process(Pair> in) { jac); if (params.redistortPoints) { - // Distort the points so they match the image they're being overlaid on + // Distort the points, so they match the image they're being overlaid on distortPoints(tempMat, tempMat); } var topPoints = tempMat.toList(); @@ -119,7 +115,7 @@ protected Void process(Pair> in) { dividePointList(bottomPoints); dividePointList(topPoints); - // floor, then pillers, then top + // floor, then pillars, then top for (int i = 0; i < bottomPoints.size(); i++) { Imgproc.line( in.getLeft(), @@ -241,11 +237,11 @@ private void distortPoints(MatOfPoint2f src, MatOfPoint2f dst) { double r2 = x * x + y * y; // square of the radius from center - // Radial distorsion + // Radial distortion double xDistort = x * (1 + k1 * r2 + k2 * r2 * r2 + k3 * r2 * r2 * r2); double yDistort = y * (1 + k1 * r2 + k2 * r2 * r2 + k3 * r2 * r2 * r2); - // Tangential distorsion + // Tangential distortion xDistort = xDistort + (2 * p1 * x * y + p2 * (r2 + 2 * x * x)); yDistort = yDistort + (p1 * (r2 + 2 * y * y) + 2 * p2 * x * y); diff --git a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/FindBoardCornersPipe.java b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/FindBoardCornersPipe.java index 9a5e38fac7..678566c707 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/FindBoardCornersPipe.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/FindBoardCornersPipe.java @@ -39,8 +39,8 @@ public class FindBoardCornersPipe Size imageSize; Size patternSize; - // Configure the optimizations used while using openCV's find corners algorithm - // Since we return results in real-time, we want ensure it goes as fast as possible + // Configure the optimizations used while using OpenCV's find corners algorithm + // Since we return results in real-time, we want to ensure it goes as fast as possible // and fails as fast as possible. final int findChessboardFlags = Calib3d.CALIB_CB_NORMALIZE_IMAGE @@ -48,9 +48,9 @@ public class FindBoardCornersPipe | Calib3d.CALIB_CB_FILTER_QUADS | Calib3d.CALIB_CB_FAST_CHECK; - private MatOfPoint2f boardCorners = new MatOfPoint2f(); + private final MatOfPoint2f boardCorners = new MatOfPoint2f(); - // Intermedeate result mat's + // Intermediate result mat's Mat smallerInFrame = new Mat(); MatOfPoint2f smallerBoardCorners = new MatOfPoint2f(); @@ -213,7 +213,7 @@ private Size getWindowSize(MatOfPoint2f inPoints) { } /** - * Find chessboard corners given a input mat and output mat to draw on + * Find chessboard corners given an input mat and output mat to draw on * * @return Frame resolution, object points, board corners */ @@ -223,7 +223,7 @@ private Triple findBoardCorners(Pair in) { var inFrame = in.getLeft(); var outFrame = in.getRight(); - // Convert the inFrame to grayscale to increase contrast + // Convert the inFrame too grayscale to increase contrast Imgproc.cvtColor(inFrame, inFrame, Imgproc.COLOR_BGR2GRAY); boolean boardFound = false; @@ -328,8 +328,7 @@ public boolean equals(Object obj) { if (type != other.type) return false; if (Double.doubleToLongBits(gridSize) != Double.doubleToLongBits(other.gridSize)) return false; - if (divisor != other.divisor) return false; - return true; + return divisor == other.divisor; } } } diff --git a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/FindCirclesPipe.java b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/FindCirclesPipe.java index 8113ce35dd..07ec9ecd82 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/FindCirclesPipe.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/FindCirclesPipe.java @@ -70,7 +70,7 @@ protected List process(Pair> in) { Math.max(1.0, params.accuracy), minRadius, maxRadius); - // Great, we now found the center point of the circle and it's radius, but we have no idea what + // Great, we now found the center point of the circle, and it's radius, but we have no idea what // contour it corresponds to // Each contour can only match to one circle, so we keep a list of unmatched contours around and // only match against them @@ -121,7 +121,7 @@ public static class FindCirclePipeParams { * If the parameter is too small, multiple neighbor circles may be falsely detected in addition to a true one. If it is too large, some circles may be missed. * * @param maxCannyThresh -First method-specific parameter. In case of #HOUGH_GRADIENT and #HOUGH_GRADIENT_ALT, it is the higher threshold of the two passed to the Canny edge detector (the lower one is twice smaller). - * Note that #HOUGH_GRADIENT_ALT uses #Scharr algorithm to compute image derivatives, so the threshold value shough normally be higher, such as 300 or normally exposed and contrasty images. + * Note that #HOUGH_GRADIENT_ALT uses #Scharr algorithm to compute image derivatives, so the threshold value should normally be higher, such as 300 or normally exposed and contrasty images. * * * @param allowableThreshold - When finding the corresponding contour, this is used to see how close a center should be to a contour for it to be considered THAT contour. diff --git a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/FindPolygonPipe.java b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/FindPolygonPipe.java index 01db9a3480..dfadfda53f 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/FindPolygonPipe.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/FindPolygonPipe.java @@ -19,7 +19,6 @@ import java.util.ArrayList; import java.util.List; -import org.opencv.core.*; import org.opencv.imgproc.Imgproc; import org.photonvision.vision.opencv.CVShape; import org.photonvision.vision.opencv.Contour; diff --git a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/GPUAcceleratedHSVPipe.java b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/GPUAcceleratedHSVPipe.java index 42e8a8567c..5b49faf641 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/GPUAcceleratedHSVPipe.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/GPUAcceleratedHSVPipe.java @@ -76,7 +76,7 @@ public class GPUAcceleratedHSVPipe extends CVPipe { "", "void main() {", " vec2 uv = gl_FragCoord.xy/resolution;", - // Important! We do this .bgr swizzle because the image comes in as BGR but we pretend + // Important! We do this .bgr swizzle because the image comes in as BGR, but we pretend // it's RGB for convenience+speed " vec3 col = texture2D(texture0, uv).bgr;", // Only the first value in the vec4 gets used for GL_RED, and only the last value gets @@ -230,7 +230,7 @@ public GPUAcceleratedHSVPipe(PBOMode pboMode) { + "', version '" + gl.glGetString(GL.GL_VERSION) + "', and profile '" - + profile.toString() + + profile + "'"); var fmt = GLBuffers.newDirectIntBuffer(1); @@ -242,7 +242,7 @@ public GPUAcceleratedHSVPipe(PBOMode pboMode) { // index for the generic position input) gl.glBindAttribLocation(programId, 0, "position"); - // Compile and setup our two shaders with our program + // Compile and set up our two shaders with our program final int vertexId = createShader(gl, programId, k_vertexShader, GL_VERTEX_SHADER); final int fragmentId = createShader(gl, programId, k_fragmentShader, GL_FRAGMENT_SHADER); @@ -298,7 +298,10 @@ public GPUAcceleratedHSVPipe(PBOMode pboMode) { FloatBuffer vertexBuffer = GLBuffers.newDirectFloatBuffer(k_vertexPositions); gl.glBindBuffer(GL_ARRAY_BUFFER, vertexVBOIds.get(0)); gl.glBufferData( - GL_ARRAY_BUFFER, vertexBuffer.capacity() * Float.BYTES, vertexBuffer, GL_STATIC_DRAW); + GL_ARRAY_BUFFER, + (long) vertexBuffer.capacity() * Float.BYTES, + vertexBuffer, + GL_STATIC_DRAW); // Set up pixel unpack buffer (a PBO to transfer image data to the GPU) if (pboMode != PBOMode.NONE) { @@ -389,12 +392,18 @@ protected Mat process(Mat in) { if (pboMode != PBOMode.NONE) { gl.glBindBuffer(GLES3.GL_PIXEL_PACK_BUFFER, packPBOIds.get(0)); gl.glBufferData( - GLES3.GL_PIXEL_PACK_BUFFER, in.width() * in.height(), null, GLES3.GL_STREAM_READ); + GLES3.GL_PIXEL_PACK_BUFFER, + (long) in.width() * in.height(), + null, + GLES3.GL_STREAM_READ); if (pboMode == PBOMode.DOUBLE_BUFFERED) { gl.glBindBuffer(GLES3.GL_PIXEL_PACK_BUFFER, packPBOIds.get(1)); gl.glBufferData( - GLES3.GL_PIXEL_PACK_BUFFER, in.width() * in.height(), null, GLES3.GL_STREAM_READ); + GLES3.GL_PIXEL_PACK_BUFFER, + (long) in.width() * in.height(), + null, + GLES3.GL_STREAM_READ); } } } @@ -459,14 +468,17 @@ protected Mat process(Mat in) { // GPU // This causes the previous data in the PBO to be discarded gl.glBufferData( - GLES3.GL_PIXEL_UNPACK_BUFFER, in.width() * in.height() * 3, null, GLES3.GL_STREAM_DRAW); + GLES3.GL_PIXEL_UNPACK_BUFFER, + (long) in.width() * in.height() * 3, + null, + GLES3.GL_STREAM_DRAW); - // Map the a buffer of GPU memory into a place that's accessible by us + // Map the buffer of GPU memory into a place that's accessible by us var buf = gl.glMapBufferRange( GLES3.GL_PIXEL_UNPACK_BUFFER, 0, - in.width() * in.height() * 3, + (long) in.width() * in.height() * 3, GLES3.GL_MAP_WRITE_BIT); buf.put(inputBytes); @@ -527,7 +539,8 @@ private Mat saveMatPBO(GLES3 gl, int width, int height, boolean doubleBuffered) // Map the PBO into the CPU's memory gl.glBindBuffer(GLES3.GL_PIXEL_PACK_BUFFER, packPBOIds.get(packNextIndex)); var buf = - gl.glMapBufferRange(GLES3.GL_PIXEL_PACK_BUFFER, 0, width * height, GLES3.GL_MAP_READ_BIT); + gl.glMapBufferRange( + GLES3.GL_PIXEL_PACK_BUFFER, 0, (long) width * height, GLES3.GL_MAP_READ_BIT); buf.get(outputBytes); outputMat.put(0, 0, outputBytes); gl.glUnmapBuffer(GLES3.GL_PIXEL_PACK_BUFFER); diff --git a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/HSVPipe.java b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/HSVPipe.java index 162c975d16..e0ba36ce0e 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/HSVPipe.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/HSVPipe.java @@ -40,7 +40,6 @@ protected Mat process(Mat in) { Scalar firstLower = params.getHsvLower().clone(); Scalar firstUpper = params.getHsvUpper().clone(); firstLower.val[0] = params.getHsvUpper().val[0]; - ; firstUpper.val[0] = 180; var lowerThresholdMat = new Mat(); diff --git a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/SortContoursPipe.java b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/SortContoursPipe.java index c1f6f57126..7bdc9bf0d6 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/SortContoursPipe.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/SortContoursPipe.java @@ -37,7 +37,7 @@ protected List process(List in) { } m_sortedContours.clear(); - if (in.size() > 0) { + if (!in.isEmpty()) { m_sortedContours.addAll(in); if (params.getSortMode() != ContourSortMode.Centermost) { m_sortedContours.sort(params.getSortMode().getComparator()); diff --git a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/SpeckleRejectPipe.java b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/SpeckleRejectPipe.java index 2349eef735..4f4c5ce547 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/SpeckleRejectPipe.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/SpeckleRejectPipe.java @@ -33,7 +33,7 @@ protected List process(List in) { } m_despeckledContours.clear(); - if (in.size() > 0) { + if (!in.isEmpty()) { double averageArea = 0.0; for (Contour c : in) { averageArea += c.getArea(); diff --git a/photon-core/src/main/java/org/photonvision/vision/pipeline/AprilTagPipeline.java b/photon-core/src/main/java/org/photonvision/vision/pipeline/AprilTagPipeline.java index 4e773605f4..af1c5145d4 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipeline/AprilTagPipeline.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipeline/AprilTagPipeline.java @@ -29,13 +29,15 @@ import org.photonvision.vision.frame.Frame; import org.photonvision.vision.frame.FrameThresholdType; import org.photonvision.vision.pipe.CVPipe.CVPipeResult; -import org.photonvision.vision.pipe.impl.*; +import org.photonvision.vision.pipe.impl.AprilTagDetectionPipe; +import org.photonvision.vision.pipe.impl.AprilTagDetectionPipeParams; +import org.photonvision.vision.pipe.impl.AprilTagPoseEstimatorPipe; import org.photonvision.vision.pipe.impl.AprilTagPoseEstimatorPipe.AprilTagPoseEstimatorPipeParams; +import org.photonvision.vision.pipe.impl.CalculateFPSPipe; import org.photonvision.vision.pipeline.result.CVPipelineResult; import org.photonvision.vision.target.TrackedTarget; import org.photonvision.vision.target.TrackedTarget.TargetCalculationParameters; -@SuppressWarnings("DuplicatedCode") public class AprilTagPipeline extends CVPipeline { private final AprilTagDetectionPipe aprilTagDetectionPipe = new AprilTagDetectionPipe(); private final AprilTagPoseEstimatorPipe poseEstimatorPipe = new AprilTagPoseEstimatorPipe(); diff --git a/photon-core/src/main/java/org/photonvision/vision/pipeline/ArucoPipeline.java b/photon-core/src/main/java/org/photonvision/vision/pipeline/ArucoPipeline.java index 69ca5f9341..26a5c60151 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipeline/ArucoPipeline.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipeline/ArucoPipeline.java @@ -48,7 +48,6 @@ import org.photonvision.vision.target.TrackedTarget; import org.photonvision.vision.target.TrackedTarget.TargetCalculationParameters; -@SuppressWarnings("DuplicatedCode") public class ArucoPipeline extends CVPipeline { private final RotateImagePipe rotateImagePipe = new RotateImagePipe(); private final GrayscalePipe grayscalePipe = new GrayscalePipe(); diff --git a/photon-core/src/main/java/org/photonvision/vision/pipeline/CVPipelineSettings.java b/photon-core/src/main/java/org/photonvision/vision/pipeline/CVPipelineSettings.java index 077b4254a1..f836e30999 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipeline/CVPipelineSettings.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipeline/CVPipelineSettings.java @@ -40,7 +40,7 @@ public class CVPipelineSettings implements Cloneable { public ImageRotationMode inputImageRotationMode = ImageRotationMode.DEG_0; public String pipelineNickname = "New Pipeline"; public boolean cameraAutoExposure = false; - // manual exposure only used if cameraAutoExposure if false + // manual exposure only used if cameraAutoExposure is false public double cameraExposure = 20; public int cameraBrightness = 50; // Currently only used by a few cameras (notably the zero-copy Pi Camera driver) with the Gain diff --git a/photon-core/src/main/java/org/photonvision/vision/pipeline/Calibrate3dPipeline.java b/photon-core/src/main/java/org/photonvision/vision/pipeline/Calibrate3dPipeline.java index fecb36d071..261b8fd522 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipeline/Calibrate3dPipeline.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipeline/Calibrate3dPipeline.java @@ -46,7 +46,7 @@ public class Calibrate3dPipeline extends CVPipeline { - // For loggging + // For logging private static final Logger logger = new Logger(Calibrate3dPipeline.class, LogGroup.General); // Only 2 pipes needed, one for finding the board corners and one for actually calibrating @@ -63,7 +63,7 @@ public class Calibrate3dPipeline /// Output of the calibration, getter method is set for this. private CVPipeResult calibrationOutput; - private int minSnapshots; + private final int minSnapshots; private boolean calibrating = false; diff --git a/photon-core/src/main/java/org/photonvision/vision/pipeline/ColoredShapePipeline.java b/photon-core/src/main/java/org/photonvision/vision/pipeline/ColoredShapePipeline.java index df108d7b2f..190de9e68b 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipeline/ColoredShapePipeline.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipeline/ColoredShapePipeline.java @@ -24,14 +24,16 @@ import org.opencv.core.Point; import org.photonvision.vision.frame.Frame; import org.photonvision.vision.frame.FrameThresholdType; -import org.photonvision.vision.opencv.*; +import org.photonvision.vision.opencv.CVShape; +import org.photonvision.vision.opencv.Contour; +import org.photonvision.vision.opencv.ContourShape; +import org.photonvision.vision.opencv.DualOffsetValues; import org.photonvision.vision.pipe.CVPipe.CVPipeResult; import org.photonvision.vision.pipe.impl.*; import org.photonvision.vision.pipeline.result.CVPipelineResult; import org.photonvision.vision.target.PotentialTarget; import org.photonvision.vision.target.TrackedTarget; -@SuppressWarnings({"DuplicatedCode"}) public class ColoredShapePipeline extends CVPipeline { private final SpeckleRejectPipe speckleRejectPipe = new SpeckleRejectPipe(); diff --git a/photon-core/src/main/java/org/photonvision/vision/pipeline/OutputStreamPipeline.java b/photon-core/src/main/java/org/photonvision/vision/pipeline/OutputStreamPipeline.java index 666ecd8ce2..0474b6b562 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipeline/OutputStreamPipeline.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipeline/OutputStreamPipeline.java @@ -150,7 +150,7 @@ public CVPipelineResult process( if (!(settings instanceof AprilTagPipelineSettings) && !(settings instanceof ArucoPipelineSettings)) { - // If we're processing anything other than Apriltags.. + // If we're processing anything other than Apriltags... var draw2dCrosshairResultOnOutput = draw2dCrosshairPipe.run(Pair.of(outMat, targetsToDraw)); sumPipeNanosElapsed += pipeProfileNanos[4] = draw2dCrosshairResultOnOutput.nanosElapsed; diff --git a/photon-core/src/main/java/org/photonvision/vision/pipeline/ReflectivePipeline.java b/photon-core/src/main/java/org/photonvision/vision/pipeline/ReflectivePipeline.java index cea2e31422..e961488b78 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipeline/ReflectivePipeline.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipeline/ReflectivePipeline.java @@ -30,7 +30,6 @@ import org.photonvision.vision.target.TrackedTarget; /** Represents a pipeline for tracking retro-reflective targets. */ -@SuppressWarnings({"DuplicatedCode"}) public class ReflectivePipeline extends CVPipeline { private final FindContoursPipe findContoursPipe = new FindContoursPipe(); private final SpeckleRejectPipe speckleRejectPipe = new SpeckleRejectPipe(); diff --git a/photon-core/src/main/java/org/photonvision/vision/processes/PipelineManager.java b/photon-core/src/main/java/org/photonvision/vision/processes/PipelineManager.java index f898aad573..e4f6df3a97 100644 --- a/photon-core/src/main/java/org/photonvision/vision/processes/PipelineManager.java +++ b/photon-core/src/main/java/org/photonvision/vision/processes/PipelineManager.java @@ -21,7 +21,6 @@ import java.util.Arrays; import java.util.Comparator; import java.util.List; -import org.opencv.aruco.Aruco; import org.photonvision.common.configuration.CameraConfiguration; import org.photonvision.common.configuration.ConfigManager; import org.photonvision.common.dataflow.DataChangeService; @@ -67,7 +66,7 @@ public PipelineManager( this.driverModePipeline.setSettings(driverSettings); - if (userPipelines.size() < 1) addPipeline(PipelineType.Reflective); + if (userPipelines.isEmpty()) addPipeline(PipelineType.Reflective); } public PipelineManager(CameraConfiguration config) { @@ -247,9 +246,9 @@ public void setDriverMode(boolean state) { } /** - * Returns whether or not driver mode is active. + * Returns whether driver mode is active. * - * @return Whether or not driver mode is active. + * @return Whether driver mode is active. */ public boolean getDriverMode() { return currentPipelineIndex == DRIVERMODE_INDEX; @@ -261,7 +260,7 @@ public boolean getDriverMode() { /** * Sorts the pipeline list by index, and reassigns their indexes to match the new order.
*
- * I don't like this but I have no other ideas, and it works so + * I don't like this, but I have no other ideas, and it works so */ private void reassignIndexes() { userPipelineSettings.sort(PipelineSettingsIndexComparator); @@ -314,7 +313,7 @@ private CVPipelineSettings createSettingsForType(PipelineType type, String nickn } default: { - logger.error("Got invalid pipeline type: " + type.toString()); + logger.error("Got invalid pipeline type: " + type); return null; } } @@ -376,31 +375,31 @@ public int duplicatePipeline(int index) { private static String createUniqueName( String nickname, List existingSettings) { - String uniqueName = nickname; + StringBuilder uniqueName = new StringBuilder(nickname); while (true) { - String finalUniqueName = uniqueName; // To get around lambda capture + String finalUniqueName = uniqueName.toString(); // To get around lambda capture var conflictingName = existingSettings.stream().anyMatch(it -> it.pipelineNickname.equals(finalUniqueName)); if (!conflictingName) { // If no conflict, we're done - return uniqueName; + return uniqueName.toString(); } else { // Otherwise, we need to add a suffix to the name // If the string doesn't already end in "([0-9]*)", we'll add it // If it does, we'll increment the number in the suffix - if (uniqueName.matches(".*\\([0-9]*\\)")) { + if (uniqueName.toString().matches(".*\\([0-9]*\\)")) { // Because java strings are immutable, we have to do this curstedness // This is like doing "New pipeline (" + 2 + ")" - var parenStart = uniqueName.lastIndexOf('('); + var parenStart = uniqueName.toString().lastIndexOf('('); var parenEnd = uniqueName.length() - 1; var number = Integer.parseInt(uniqueName.substring(parenStart + 1, parenEnd)) + 1; - uniqueName = uniqueName.substring(0, parenStart + 1) + number + ")"; + uniqueName = new StringBuilder(uniqueName.substring(0, parenStart + 1) + number + ")"); } else { - uniqueName += " (1)"; + uniqueName.append(" (1)"); } } } @@ -442,7 +441,7 @@ public void changePipelineType(int newType) { return; } - logger.info("Adding new pipe of type " + type.toString() + " at idx " + idx); + logger.info("Adding new pipe of type " + type + " at idx " + idx); newSettings.pipelineIndex = idx; userPipelineSettings.set(idx, newSettings); setPipelineInternal(idx); diff --git a/photon-core/src/main/java/org/photonvision/vision/processes/VisionModule.java b/photon-core/src/main/java/org/photonvision/vision/processes/VisionModule.java index bf0ac94427..d246a45b52 100644 --- a/photon-core/src/main/java/org/photonvision/vision/processes/VisionModule.java +++ b/photon-core/src/main/java/org/photonvision/vision/processes/VisionModule.java @@ -20,7 +20,10 @@ import edu.wpi.first.cscore.VideoException; import edu.wpi.first.math.util.Units; import io.javalin.websocket.WsContext; -import java.util.*; +import java.util.ArrayList; +import java.util.HashMap; +import java.util.LinkedList; +import java.util.List; import java.util.function.BiConsumer; import org.photonvision.common.configuration.CameraConfiguration; import org.photonvision.common.configuration.ConfigManager; @@ -294,7 +297,7 @@ public void setFov(double fov) { var settables = visionSource.getSettables(); logger.trace(() -> "Setting " + settables.getConfiguration().nickname + ") FOV (" + fov + ")"); - // Only set FOV if we have no vendor JSON and we aren't using a PiCAM + // Only set FOV if we have no vendor JSON, and we aren't using a PiCAM if (isVendorCamera()) { logger.info("Cannot set FOV on a vendor device! Ignoring..."); } else { diff --git a/photon-core/src/main/java/org/photonvision/vision/processes/VisionModuleManager.java b/photon-core/src/main/java/org/photonvision/vision/processes/VisionModuleManager.java index 4ddcd74d5c..d75e62cb7e 100644 --- a/photon-core/src/main/java/org/photonvision/vision/processes/VisionModuleManager.java +++ b/photon-core/src/main/java/org/photonvision/vision/processes/VisionModuleManager.java @@ -65,18 +65,15 @@ public List addSources(List visionSources) { addedModules.put(visionSource.getCameraConfiguration().streamIndex, module); } - var sortedModulesList = - addedModules.entrySet().stream() - .sorted(Comparator.comparingInt(Map.Entry::getKey)) // sort by stream index - .map(Map.Entry::getValue) // map to Stream of VisionModule - .collect(Collectors.toList()); // collect in a List - - return sortedModulesList; + return addedModules.entrySet().stream() + .sorted(Comparator.comparingInt(Map.Entry::getKey)) // sort by stream index + .map(Map.Entry::getValue) // map to Stream of VisionModule + .collect(Collectors.toList()); // collect in a List } private void assignCameraIndex(List config) { - // We won't necessarily have already added all of the cameras we need to at this point - // But by operating on the list, we have a fairly good idea of which we need to change + // We won't necessarily have already added all the cameras we need to at this point + // But by operating on the list, we have a fairly good idea of which we need to change, // but it's not guaranteed that we change the correct one // The best we can do is try to avoid a case where the stream index runs away to infinity // since we can only stream 5 cameras at once diff --git a/photon-core/src/main/java/org/photonvision/vision/processes/VisionSourceManager.java b/photon-core/src/main/java/org/photonvision/vision/processes/VisionSourceManager.java index bcb75e7f32..4b31ba0691 100644 --- a/photon-core/src/main/java/org/photonvision/vision/processes/VisionSourceManager.java +++ b/photon-core/src/main/java/org/photonvision/vision/processes/VisionSourceManager.java @@ -19,7 +19,10 @@ import edu.wpi.first.cscore.UsbCamera; import edu.wpi.first.cscore.UsbCameraInfo; -import java.util.*; +import java.util.ArrayList; +import java.util.Arrays; +import java.util.Collection; +import java.util.List; import java.util.concurrent.CopyOnWriteArrayList; import java.util.function.Supplier; import java.util.stream.Collectors; diff --git a/photon-core/src/main/java/org/photonvision/vision/target/TargetCalculations.java b/photon-core/src/main/java/org/photonvision/vision/target/TargetCalculations.java index 2079abc560..60b278aae4 100644 --- a/photon-core/src/main/java/org/photonvision/vision/target/TargetCalculations.java +++ b/photon-core/src/main/java/org/photonvision/vision/target/TargetCalculations.java @@ -33,7 +33,6 @@ public static double calculatePitch( return -Math.toDegrees(Math.atan((offsetCenterY - targetCenterY) / verticalFocalLength)); } - @SuppressWarnings("DuplicatedCode") public static double calculateSkew(boolean isLandscape, RotatedRect minAreaRect) { // https://namkeenman.wordpress.com/2015/12/18/open-cv-determine-angle-of-rotatedrect-minarearect/ var angle = minAreaRect.angle; diff --git a/photon-core/src/main/java/org/photonvision/vision/target/TargetModel.java b/photon-core/src/main/java/org/photonvision/vision/target/TargetModel.java index 4ead2f7784..ea06638af8 100644 --- a/photon-core/src/main/java/org/photonvision/vision/target/TargetModel.java +++ b/photon-core/src/main/java/org/photonvision/vision/target/TargetModel.java @@ -127,8 +127,8 @@ public enum TargetModel implements Releasable { Units.inchesToMeters(3 * 2)); @JsonIgnore private MatOfPoint3f realWorldTargetCoordinates; - @JsonIgnore private MatOfPoint3f visualizationBoxBottom = new MatOfPoint3f(); - @JsonIgnore private MatOfPoint3f visualizationBoxTop = new MatOfPoint3f(); + @JsonIgnore private final MatOfPoint3f visualizationBoxBottom = new MatOfPoint3f(); + @JsonIgnore private final MatOfPoint3f visualizationBoxTop = new MatOfPoint3f(); @JsonProperty("realWorldCoordinatesArray") private List realWorldCoordinatesArray; diff --git a/photon-core/src/main/java/org/photonvision/vision/target/TrackedTarget.java b/photon-core/src/main/java/org/photonvision/vision/target/TrackedTarget.java index 4bb7997047..72c5cdf600 100644 --- a/photon-core/src/main/java/org/photonvision/vision/target/TrackedTarget.java +++ b/photon-core/src/main/java/org/photonvision/vision/target/TrackedTarget.java @@ -24,16 +24,14 @@ import edu.wpi.first.math.geometry.Translation3d; import java.util.HashMap; import java.util.List; -import org.opencv.core.CvType; -import org.opencv.core.Mat; -import org.opencv.core.MatOfPoint; -import org.opencv.core.MatOfPoint2f; -import org.opencv.core.Point; -import org.opencv.core.RotatedRect; +import org.opencv.core.*; import org.photonvision.common.util.math.MathUtils; import org.photonvision.vision.aruco.ArucoDetectionResult; import org.photonvision.vision.frame.FrameStaticProperties; -import org.photonvision.vision.opencv.*; +import org.photonvision.vision.opencv.CVShape; +import org.photonvision.vision.opencv.Contour; +import org.photonvision.vision.opencv.DualOffsetValues; +import org.photonvision.vision.opencv.Releasable; public class TrackedTarget implements Releasable { public final Contour m_mainContour; @@ -126,11 +124,9 @@ public TrackedTarget( tvec.put( 0, 0, - new double[] { - bestPose.getTranslation().getX(), - bestPose.getTranslation().getY(), - bestPose.getTranslation().getZ() - }); + bestPose.getTranslation().getX(), + bestPose.getTranslation().getY(), + bestPose.getTranslation().getZ()); setCameraRelativeTvec(tvec); // Opencv expects a 3d vector with norm = angle and direction = axis @@ -185,10 +181,9 @@ public TrackedTarget(ArucoDetectionResult result, TargetCalculationParameters pa var axisangle = VecBuilder.fill(result.getRvec()[0], result.getRvec()[1], result.getRvec()[2]); Rotation3d rotation = new Rotation3d(axisangle, axisangle.normF()); - Transform3d targetPose = - MathUtils.convertOpenCVtoPhotonTransform(new Transform3d(translation, rotation)); - m_bestCameraToTarget3d = targetPose; + m_bestCameraToTarget3d = + MathUtils.convertOpenCVtoPhotonTransform(new Transform3d(translation, rotation)); } } @@ -209,7 +204,7 @@ public double getPoseAmbiguity() { } /** - * Set the approximate bouding polygon. + * Set the approximate bounding polygon. * * @param boundingPolygon List of points to copy. Not modified. */ @@ -262,7 +257,7 @@ public void calculateValues(TargetCalculationParameters params) { params.dualOffsetValues, params.robotOffsetPointMode); - // order of this stuff doesnt matter though + // order of this stuff doesn't matter though m_pitch = TargetCalculations.calculatePitch( m_targetOffsetPoint.y, m_robotOffsetPoint.y, params.verticalFocalLength); diff --git a/photon-core/src/main/java/org/photonvision/vision/videoStream/SocketVideoStream.java b/photon-core/src/main/java/org/photonvision/vision/videoStream/SocketVideoStream.java index 3a9eed25f1..dae270e9f6 100644 --- a/photon-core/src/main/java/org/photonvision/vision/videoStream/SocketVideoStream.java +++ b/photon-core/src/main/java/org/photonvision/vision/videoStream/SocketVideoStream.java @@ -35,7 +35,7 @@ public class SocketVideoStream implements Consumer { // Gets set to true when another class reads out valid jpeg bytes at least once // Set back to false when another frame is freshly converted - // Should eliminate synchronization issues of differeing rates of putting frames in + // Should eliminate synchronization issues of differing rates of putting frames in // and taking them back out boolean frameWasConsumed = false; @@ -53,8 +53,7 @@ public SocketVideoStream(int portID) { this.portID = portID; oldSchoolServer = new MJPGFrameConsumer( - CameraServerJNI.getHostname() + "_Port_" + Integer.toString(portID) + "_MJPEG_Server", - portID); + CameraServerJNI.getHostname() + "_Port_" + portID + "_MJPEG_Server", portID); } @Override @@ -64,7 +63,7 @@ public void accept(CVMat image) { .tryLock()) { // we assume frames are coming in frequently. Just skip this frame if we're // locked doing something else. try { - // Does a single-shot frame recieve and convert to JPEG for efficency + // Does a single-shot frame receive and convert to JPEG for efficiency // Will not capture/convert again until convertNextFrame() is called if (image != null && !image.getMat().empty() && jpegBytes == null) { frameWasConsumed = false; diff --git a/photon-core/src/main/java/org/photonvision/vision/videoStream/SocketVideoStreamManager.java b/photon-core/src/main/java/org/photonvision/vision/videoStream/SocketVideoStreamManager.java index 258c8805ff..ceb84feab6 100644 --- a/photon-core/src/main/java/org/photonvision/vision/videoStream/SocketVideoStreamManager.java +++ b/photon-core/src/main/java/org/photonvision/vision/videoStream/SocketVideoStreamManager.java @@ -29,8 +29,8 @@ public class SocketVideoStreamManager { private final Logger logger = new Logger(SocketVideoStreamManager.class, LogGroup.Camera); - private Map streams = new Hashtable(); - private Map userSubscriptions = new Hashtable(); + private final Map streams = new Hashtable<>(); + private final Map userSubscriptions = new Hashtable<>(); private static class ThreadSafeSingleton { private static final SocketVideoStreamManager INSTANCE = new SocketVideoStreamManager(); @@ -45,13 +45,13 @@ private SocketVideoStreamManager() {} // Register a new available camera stream public void addStream(SocketVideoStream newStream) { streams.put(newStream.portID, newStream); - logger.debug("Added new stream for port " + Integer.toString(newStream.portID)); + logger.debug("Added new stream for port " + newStream.portID); } // Remove a previously-added camera stream, and unsubscribe all users public void removeStream(SocketVideoStream oldStream) { streams.remove(oldStream.portID); - logger.debug("Removed stream for port " + Integer.toString(oldStream.portID)); + logger.debug("Removed stream for port " + oldStream.portID); } // Indicate a user would like to subscribe to a camera stream and get frames from it periodically @@ -61,8 +61,7 @@ public void addSubscription(WsContext user, int streamPortID) { userSubscriptions.put(user, streamPortID); stream.addUser(); } else { - logger.error( - "User attempted to subscribe to non-existent port " + Integer.toString(streamPortID)); + logger.error("User attempted to subscribe to non-existent port " + streamPortID); } } @@ -92,7 +91,7 @@ public ByteBuffer getSendFrame(WsContext user) { } } - // Causes all streams to "re-trigger" and recieve and convert their next mjpeg frame + // Causes all streams to "re-trigger" and receive and convert their next mjpeg frame // Only invoke this after all returned jpeg Strings have been used. public void allStreamConvertNextFrame() { for (SocketVideoStream stream : streams.values()) { diff --git a/photon-core/src/test/java/org/photonvision/common/configuration/ConfigTest.java b/photon-core/src/test/java/org/photonvision/common/configuration/ConfigTest.java index 8aa1456002..beaae0e4d9 100644 --- a/photon-core/src/test/java/org/photonvision/common/configuration/ConfigTest.java +++ b/photon-core/src/test/java/org/photonvision/common/configuration/ConfigTest.java @@ -107,13 +107,13 @@ public void deserializeConfig() { Assertions.assertTrue( reflectivePipelineSettings instanceof ReflectivePipelineSettings, - "Conig loaded pipeline settings for index 0 not of expected type ReflectivePipelineSettings!"); + "Config loaded pipeline settings for index 0 not of expected type ReflectivePipelineSettings!"); Assertions.assertTrue( coloredShapePipelineSettings instanceof ColoredShapePipelineSettings, - "Conig loaded pipeline settings for index 1 not of expected type ColoredShapePipelineSettings!"); + "Config loaded pipeline settings for index 1 not of expected type ColoredShapePipelineSettings!"); Assertions.assertTrue( apriltagPipelineSettings instanceof AprilTagPipelineSettings, - "Conig loaded pipeline settings for index 2 not of expected type AprilTagPipelineSettings!"); + "Config loaded pipeline settings for index 2 not of expected type AprilTagPipelineSettings!"); } @AfterAll diff --git a/photon-core/src/test/java/org/photonvision/common/configuration/SQLConfigTest.java b/photon-core/src/test/java/org/photonvision/common/configuration/SQLConfigTest.java index ad2567bc3f..18d4ae5b6a 100644 --- a/photon-core/src/test/java/org/photonvision/common/configuration/SQLConfigTest.java +++ b/photon-core/src/test/java/org/photonvision/common/configuration/SQLConfigTest.java @@ -21,7 +21,8 @@ import java.nio.file.Path; import java.util.List; -import org.junit.jupiter.api.*; +import org.junit.jupiter.api.BeforeAll; +import org.junit.jupiter.api.Test; import org.photonvision.common.util.TestUtils; import org.photonvision.vision.camera.CameraType; import org.photonvision.vision.pipeline.AprilTagPipelineSettings; diff --git a/photon-core/src/test/java/org/photonvision/common/util/LogFileManagementTest.java b/photon-core/src/test/java/org/photonvision/common/util/LogFileManagementTest.java index bfd36a6aea..e834874641 100644 --- a/photon-core/src/test/java/org/photonvision/common/util/LogFileManagementTest.java +++ b/photon-core/src/test/java/org/photonvision/common/util/LogFileManagementTest.java @@ -57,17 +57,15 @@ public void fileCleanupTest() { } // Confirm new log files were created - Assertions.assertEquals( - true, - Logger.MAX_LOGS_TO_KEEP + 5 <= countLogFiles(testDir), - "Not enough log files discovered"); + Assertions.assertTrue( + Logger.MAX_LOGS_TO_KEEP + 5 <= countLogFiles(testDir), "Not enough log files discovered"); // Run the log cleanup routine Logger.cleanLogs(Path.of(testDir)); // Confirm we deleted log files Assertions.assertEquals( - true, Logger.MAX_LOGS_TO_KEEP == countLogFiles(testDir), "Not enough log files deleted"); + Logger.MAX_LOGS_TO_KEEP, countLogFiles(testDir), "Not enough log files deleted"); // Clean uptest directory org.photonvision.common.util.file.FileUtils.deleteDirectory(Path.of(testDir)); diff --git a/photon-core/src/test/java/org/photonvision/hardware/HardwareTest.java b/photon-core/src/test/java/org/photonvision/hardware/HardwareTest.java index 8f6924d755..9d371d25f8 100644 --- a/photon-core/src/test/java/org/photonvision/hardware/HardwareTest.java +++ b/photon-core/src/test/java/org/photonvision/hardware/HardwareTest.java @@ -17,7 +17,8 @@ package org.photonvision.hardware; -import static org.junit.jupiter.api.Assertions.*; +import static org.junit.jupiter.api.Assertions.assertFalse; +import static org.junit.jupiter.api.Assertions.assertTrue; import org.junit.jupiter.api.Test; import org.photonvision.common.hardware.GPIO.CustomGPIO; diff --git a/photon-core/src/test/java/org/photonvision/vision/pipeline/AprilTagTest.java b/photon-core/src/test/java/org/photonvision/vision/pipeline/AprilTagTest.java index 23f494428d..1ece69fc55 100644 --- a/photon-core/src/test/java/org/photonvision/vision/pipeline/AprilTagTest.java +++ b/photon-core/src/test/java/org/photonvision/vision/pipeline/AprilTagTest.java @@ -60,7 +60,7 @@ public void testApriltagFacingCamera() { pipelineResult = pipeline.run(frameProvider.get(), QuirkyCamera.DefaultCamera); printTestResults(pipelineResult); } catch (RuntimeException e) { - // For now, will throw coz rotation3d ctor + // For now, will throw because of the Rotation3d ctor return; } @@ -116,7 +116,7 @@ public void testApriltagDistorted() { pipelineResult = pipeline.run(frameProvider.get(), QuirkyCamera.DefaultCamera); printTestResults(pipelineResult); } catch (RuntimeException e) { - // For now, will throw coz rotation3d ctor + // For now, will throw because of the Rotation3d ctor return; } diff --git a/photon-core/src/test/java/org/photonvision/vision/pipeline/ArucoPipelineTest.java b/photon-core/src/test/java/org/photonvision/vision/pipeline/ArucoPipelineTest.java index 06d2fb4f5a..168b7b92e9 100644 --- a/photon-core/src/test/java/org/photonvision/vision/pipeline/ArucoPipelineTest.java +++ b/photon-core/src/test/java/org/photonvision/vision/pipeline/ArucoPipelineTest.java @@ -59,7 +59,7 @@ public void testApriltagFacingCameraAruco() { pipelineResult = pipeline.run(frameProvider.get(), QuirkyCamera.DefaultCamera); printTestResults(pipelineResult); } catch (RuntimeException e) { - // For now, will throw coz rotation3d ctor + // For now, will throw because of the Rotation3d ctor return; } diff --git a/photon-core/src/test/java/org/photonvision/vision/pipeline/Calibrate3dPipeTest.java b/photon-core/src/test/java/org/photonvision/vision/pipeline/Calibrate3dPipeTest.java index bec81b2c49..72547829f1 100644 --- a/photon-core/src/test/java/org/photonvision/vision/pipeline/Calibrate3dPipeTest.java +++ b/photon-core/src/test/java/org/photonvision/vision/pipeline/Calibrate3dPipeTest.java @@ -17,7 +17,8 @@ package org.photonvision.vision.pipeline; -import static org.junit.jupiter.api.Assertions.*; +import static org.junit.jupiter.api.Assertions.assertNotNull; +import static org.junit.jupiter.api.Assertions.assertTrue; import edu.wpi.first.math.util.Units; import java.io.File; @@ -310,7 +311,7 @@ public void calibrateSquaresCommon( assertTrue(centerYErrPct < 10.0); System.out.println("Per View Errors: " + Arrays.toString(cal.perViewErrors)); - System.out.println("Camera Intrinsics: " + cal.cameraIntrinsics.toString()); + System.out.println("Camera Intrinsics: " + cal.cameraIntrinsics); System.out.println("Dist Coeffs: " + cal.distCoeffs.toString()); System.out.println("Standard Deviation: " + cal.standardDeviation); System.out.println( diff --git a/photon-core/src/test/java/org/photonvision/vision/pipeline/CirclePNPTest.java b/photon-core/src/test/java/org/photonvision/vision/pipeline/CirclePNPTest.java index 14a51b230e..5a4bc4fcd5 100644 --- a/photon-core/src/test/java/org/photonvision/vision/pipeline/CirclePNPTest.java +++ b/photon-core/src/test/java/org/photonvision/vision/pipeline/CirclePNPTest.java @@ -17,7 +17,8 @@ package org.photonvision.vision.pipeline; -import static org.junit.jupiter.api.Assertions.*; +import static org.junit.jupiter.api.Assertions.assertEquals; +import static org.junit.jupiter.api.Assertions.assertNotNull; import java.util.stream.Collectors; import org.junit.jupiter.api.BeforeEach; diff --git a/photon-core/src/test/java/org/photonvision/vision/processes/VisionModuleManagerTest.java b/photon-core/src/test/java/org/photonvision/vision/processes/VisionModuleManagerTest.java index 9e16b6c75d..e0a8376159 100644 --- a/photon-core/src/test/java/org/photonvision/vision/processes/VisionModuleManagerTest.java +++ b/photon-core/src/test/java/org/photonvision/vision/processes/VisionModuleManagerTest.java @@ -24,7 +24,9 @@ import java.util.HashMap; import java.util.List; import java.util.stream.Collectors; -import org.junit.jupiter.api.*; +import org.junit.jupiter.api.Assertions; +import org.junit.jupiter.api.BeforeAll; +import org.junit.jupiter.api.Test; import org.photonvision.common.configuration.CameraConfiguration; import org.photonvision.common.configuration.ConfigManager; import org.photonvision.common.dataflow.CVPipelineResultConsumer; @@ -169,7 +171,6 @@ public void testMultipleStreamIndex() { Arrays.toString( modules.stream() .map(it -> it.visionSource.getCameraConfiguration().streamIndex) - .collect(Collectors.toList()) .toArray())); var idxs = modules.stream() diff --git a/photon-core/src/test/java/org/photonvision/vision/target/TargetCalculationsTest.java b/photon-core/src/test/java/org/photonvision/vision/target/TargetCalculationsTest.java index 29ecd7654d..0dd36d90e9 100644 --- a/photon-core/src/test/java/org/photonvision/vision/target/TargetCalculationsTest.java +++ b/photon-core/src/test/java/org/photonvision/vision/target/TargetCalculationsTest.java @@ -21,8 +21,10 @@ import org.junit.jupiter.api.Assertions; import org.junit.jupiter.api.BeforeEach; import org.junit.jupiter.api.Test; -import org.opencv.core.*; +import org.opencv.core.MatOfPoint2f; import org.opencv.core.Point; +import org.opencv.core.RotatedRect; +import org.opencv.core.Size; import org.opencv.imgproc.Imgproc; import org.photonvision.common.util.TestUtils; import org.photonvision.common.util.numbers.DoubleCouple; @@ -31,8 +33,9 @@ public class TargetCalculationsTest { - private static Size imageSize = new Size(800, 600); - private static Point imageCenterPoint = new Point(imageSize.width / 2, imageSize.height / 2); + private static final Size imageSize = new Size(800, 600); + private static final Point imageCenterPoint = + new Point(imageSize.width / 2, imageSize.height / 2); private static final double diagFOV = Math.toRadians(70.0); private static final FrameStaticProperties props =