Skip to content

Commit

Permalink
Java fixes
Browse files Browse the repository at this point in the history
  • Loading branch information
srimanachanta committed Oct 10, 2023
1 parent 3f862e0 commit f65d1c4
Show file tree
Hide file tree
Showing 13 changed files with 41 additions and 34 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -181,15 +181,13 @@ 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[] {});
Expand All @@ -215,8 +213,11 @@ public static List<PhotonTrackedTarget> simpleFromTrackedTargets(List<TrackedTar
}
{
var points = t.getTargetCorners();
for (int i = 0; i < points.size(); i++) {
detectedCorners.add(new TargetCorner(points.get(i).x, points.get(i).y));
for (Point point : points) {
detectedCorners.add(new TargetCorner(
point.x,
point.y
));
}
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -121,7 +121,7 @@ private void setClientMode(String ntServerAddress) {
ntInstance.stopServer();
ntInstance.startClient4("photonvision");
try {
Integer t = Integer.parseInt(ntServerAddress);
int t = Integer.parseInt(ntServerAddress);
if (!isRetryingConnection) logger.info("Starting NT Client, server team is " + t);
ntInstance.setServerTeam(t);
} catch (NumberFormatException e) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -155,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();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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;
}
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -58,7 +58,7 @@ public PhotonArucoDetector() {
ids = new Mat();
tvecs = new Mat();
rvecs = new Mat();
corners = new ArrayList<Mat>();
corners = new ArrayList<>();
tagPose = new Pose3d();
translation = new Translation3d();
rotation = new Rotation3d();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -266,12 +266,9 @@ public HashMap<Integer, VideoMode> 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) {
if (videoMode.pixelFormat == VideoMode.PixelFormat.kGray || videoMode.pixelFormat == VideoMode.PixelFormat.kUnknown) {
continue;
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -111,7 +111,11 @@ public CapturedFrame getInputMat() {
}

lastGetMillis = System.currentTimeMillis();
return new CapturedFrame(out, properties, MathUtils.wpiNanoTime());
return new CapturedFrame(
out,
properties,
MathUtils.wpiNanoTime()
);
}

@Override
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,11 @@ public CapturedFrame getInputMat() {
time = MathUtils.wpiNanoTime();
}

return new CapturedFrame(mat, settables.getFrameStaticProperties(), time);
return new CapturedFrame(
mat,
settables.getFrameStaticProperties(),
time
);
}

@Override
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -375,31 +375,34 @@ public int duplicatePipeline(int index) {

private static String createUniqueName(
String nickname, List<CVPipelineSettings> 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)");
}
}
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -29,8 +29,8 @@ public class SocketVideoStreamManager {

private final Logger logger = new Logger(SocketVideoStreamManager.class, LogGroup.Camera);

private final Map<Integer, SocketVideoStream> streams = new Hashtable<Integer, SocketVideoStream>();
private final Map<WsContext, Integer> userSubscriptions = new Hashtable<WsContext, Integer>();
private final Map<Integer, SocketVideoStream> streams = new Hashtable<>();
private final Map<WsContext, Integer> userSubscriptions = new Hashtable<>();

private static class ThreadSafeSingleton {
private static final SocketVideoStreamManager INSTANCE = new SocketVideoStreamManager();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -66,8 +66,9 @@ public void fileCleanupTest() {
Logger.cleanLogs(Path.of(testDir));

// Confirm we deleted log files
Assertions.assertTrue(
Logger.MAX_LOGS_TO_KEEP == countLogFiles(testDir),
Assertions.assertEquals(
Logger.MAX_LOGS_TO_KEEP,
countLogFiles(testDir),
"Not enough log files deleted"
);

Expand Down

0 comments on commit f65d1c4

Please sign in to comment.