Skip to content

Commit

Permalink
Formatting fixes
Browse files Browse the repository at this point in the history
  • Loading branch information
srimanachanta committed Oct 10, 2023
1 parent 14cd3fc commit acbdd8f
Show file tree
Hide file tree
Showing 19 changed files with 46 additions and 63 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -181,8 +181,7 @@ public void accept(CVPipelineResult result) {
}

// Something in the result can sometimes be null -- so check probably too many things
if (
result.inputAndOutputFrame != null
if (result.inputAndOutputFrame != null
&& result.inputAndOutputFrame.frameStaticProperties != null
&& result.inputAndOutputFrame.frameStaticProperties.cameraCalibration != null) {
var fsp = result.inputAndOutputFrame.frameStaticProperties;
Expand Down Expand Up @@ -214,10 +213,7 @@ public static List<PhotonTrackedTarget> simpleFromTrackedTargets(List<TrackedTar
{
var points = t.getTargetCorners();
for (Point point : points) {
detectedCorners.add(new TargetCorner(
point.x,
point.y
));
detectedCorners.add(new TargetCorner(point.x, point.y));
}
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -179,11 +179,7 @@ private void setInternal(VisionLEDMode newLedMode, boolean fromNT) {
}
currentLedMode = newLedMode;
logger.info(
"Changing LED mode from \""
+ lastLedMode.toString()
+ "\" to \""
+ newLedMode
+ "\"");
"Changing LED mode from \"" + lastLedMode.toString() + "\" to \"" + newLedMode + "\"");
} else {
if (currentLedMode == VisionLEDMode.kDefault) {
switch (newLedMode) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -115,8 +115,8 @@ public static List<NMDeviceInfo> getAllInterfaces() {
}

public static List<NMDeviceInfo> getAllActiveInterfaces() {
// 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
// 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());
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@
import org.photonvision.common.logging.Logger;

/** Execute external process and optionally read output buffer. */
@SuppressWarnings({"unused" })
@SuppressWarnings({"unused"})
public class ShellExec {
private static final Logger logger = new Logger(ShellExec.class, LogGroup.General);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -168,8 +168,8 @@ public static native boolean setThresholds(
public static native boolean awaitNewFrame();

/**
* Get a pointer to the most recent color mat generated. Call this immediately after awaitNewFrame,
* and call only 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();

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,8 @@ public class FileVisionSource extends VisionSource {

public FileVisionSource(CameraConfiguration cameraConfiguration) {
super(cameraConfiguration);
var calibration = !cameraConfiguration.calibrations.isEmpty()
var calibration =
!cameraConfiguration.calibrations.isEmpty()
? cameraConfiguration.calibrations.get(0)
: null;
frameProvider =
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -268,7 +268,8 @@ public HashMap<Integer, VideoMode> getAllVideoModes() {
}
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 @@ -111,11 +111,7 @@ 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,11 +48,7 @@ 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 @@ -47,7 +47,6 @@ public boolean equals(Object obj) {
if (family != other.family) return false;
if (detectorParams == null) {
return other.detectorParams == null;
} else
return detectorParams.equals(other.detectorParams);
} else return detectorParams.equals(other.detectorParams);
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -18,9 +18,7 @@
package org.photonvision.vision.pipe.impl;

import edu.wpi.first.math.geometry.Translation2d;

import java.util.*;

import org.opencv.core.MatOfPoint2f;
import org.opencv.core.Point;
import org.opencv.imgproc.Imgproc;
Expand All @@ -41,11 +39,9 @@ protected List<TrackedTarget> process(List<TrackedTarget> targetList) {
for (var target : targetList) {
// detect corners. Might implement more algorithms later but
// APPROX_POLY_DP_AND_EXTREME_CORNERS should be year agnostic
if (Objects.requireNonNull(params.cornerDetectionStrategy) == DetectionStrategy.APPROX_POLY_DP_AND_EXTREME_CORNERS) {
var targetCorners = detectExtremeCornersByApproxPolyDp(
target,
params.calculateConvexHulls
);
if (Objects.requireNonNull(params.cornerDetectionStrategy)
== DetectionStrategy.APPROX_POLY_DP_AND_EXTREME_CORNERS) {
var targetCorners = detectExtremeCornersByApproxPolyDp(target, params.calculateConvexHulls);
target.setTargetCorners(targetCorners);
}
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -299,7 +299,9 @@ public GPUAcceleratedHSVPipe(PBOMode pboMode) {
gl.glBindBuffer(GL_ARRAY_BUFFER, vertexVBOIds.get(0));
gl.glBufferData(
GL_ARRAY_BUFFER,
(long) vertexBuffer.capacity() * Float.BYTES, vertexBuffer, GL_STATIC_DRAW);
(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) {
Expand Down Expand Up @@ -391,13 +393,17 @@ protected Mat process(Mat in) {
gl.glBindBuffer(GLES3.GL_PIXEL_PACK_BUFFER, packPBOIds.get(0));
gl.glBufferData(
GLES3.GL_PIXEL_PACK_BUFFER,
(long) in.width() * in.height(), null, GLES3.GL_STREAM_READ);
(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,
(long) in.width() * in.height(), null, GLES3.GL_STREAM_READ);
(long) in.width() * in.height(),
null,
GLES3.GL_STREAM_READ);
}
}
}
Expand Down Expand Up @@ -463,7 +469,9 @@ protected Mat process(Mat in) {
// This causes the previous data in the PBO to be discarded
gl.glBufferData(
GLES3.GL_PIXEL_UNPACK_BUFFER,
(long) in.width() * in.height() * 3, null, GLES3.GL_STREAM_DRAW);
(long) in.width() * in.height() * 3,
null,
GLES3.GL_STREAM_DRAW);

// Map the buffer of GPU memory into a place that's accessible by us
var buf =
Expand Down Expand Up @@ -531,8 +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,
(long) 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);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -397,10 +397,7 @@ private static String createUniqueName(
var parenEnd = uniqueName.length() - 1;
var number = Integer.parseInt(uniqueName.substring(parenStart + 1, parenEnd)) + 1;

uniqueName = new StringBuilder(uniqueName.substring(
0,
parenStart + 1
) + number + ")");
uniqueName = new StringBuilder(uniqueName.substring(0, parenStart + 1) + number + ")");
} else {
uniqueName.append(" (1)");
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -126,8 +126,7 @@ public TrackedTarget(
0,
bestPose.getTranslation().getX(),
bestPose.getTranslation().getY(),
bestPose.getTranslation().getZ()
);
bestPose.getTranslation().getZ());
setCameraRelativeTvec(tvec);

// Opencv expects a 3d vector with norm = angle and direction = axis
Expand Down Expand Up @@ -183,7 +182,8 @@ public TrackedTarget(ArucoDetectionResult result, TargetCalculationParameters pa
VecBuilder.fill(result.getRvec()[0], result.getRvec()[1], result.getRvec()[2]);
Rotation3d rotation = new Rotation3d(axisangle, axisangle.normF());

m_bestCameraToTarget3d = MathUtils.convertOpenCVtoPhotonTransform(new Transform3d(translation, rotation));
m_bestCameraToTarget3d =
MathUtils.convertOpenCVtoPhotonTransform(new Transform3d(translation, rotation));
}
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -53,8 +53,7 @@ public SocketVideoStream(int portID) {
this.portID = portID;
oldSchoolServer =
new MJPGFrameConsumer(
CameraServerJNI.getHostname() + "_Port_" + portID + "_MJPEG_Server",
portID);
CameraServerJNI.getHostname() + "_Port_" + portID + "_MJPEG_Server", portID);
}

@Override
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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 " + streamPortID);
logger.error("User attempted to subscribe to non-existent port " + streamPortID);
}
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -58,19 +58,14 @@ public void fileCleanupTest() {

// Confirm new log files were created
Assertions.assertTrue(
Logger.MAX_LOGS_TO_KEEP + 5 <= countLogFiles(testDir),
"Not enough log files discovered"
);
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(
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));
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -168,7 +168,10 @@ public void testMultipleStreamIndex() {
var modules = vmm.addSources(List.of(testSource, testSource2, testSource3));

System.out.println(
Arrays.toString(modules.stream().map(it -> it.visionSource.getCameraConfiguration().streamIndex).toArray()));
Arrays.toString(
modules.stream()
.map(it -> it.visionSource.getCameraConfiguration().streamIndex)
.toArray()));
var idxs =
modules.stream()
.map(it -> it.visionSource.getCameraConfiguration().streamIndex)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,8 @@
public class TargetCalculationsTest {

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 Point imageCenterPoint =
new Point(imageSize.width / 2, imageSize.height / 2);
private static final double diagFOV = Math.toRadians(70.0);

private static final FrameStaticProperties props =
Expand Down

0 comments on commit acbdd8f

Please sign in to comment.