Skip to content

Commit

Permalink
update
Browse files Browse the repository at this point in the history
  • Loading branch information
srimanachanta committed Dec 24, 2023
1 parent 0356eee commit 184be30
Show file tree
Hide file tree
Showing 47 changed files with 170 additions and 219 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@ public class PhotonConfiguration {
private final HardwareSettings hardwareSettings;
private NetworkConfig networkConfig;
private AprilTagFieldLayout atfl;
private HashMap<String, CameraConfiguration> cameraConfigurations;
private final HashMap<String, CameraConfiguration> cameraConfigurations;

public PhotonConfiguration(
HardwareConfig hardwareConfig,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -131,10 +131,11 @@ private void initDatabase() {
try {
createGlobalTableStatement = conn.createStatement();
String sql =
"CREATE TABLE IF NOT EXISTS global (\n"
+ " filename TINYTEXT PRIMARY KEY,\n"
+ " contents mediumtext NOT NULL\n"
+ ");";
"""
CREATE TABLE IF NOT EXISTS global (
filename TINYTEXT PRIMARY KEY,
contents mediumtext NOT NULL
);""";
createGlobalTableStatement.execute(sql);
} catch (SQLException e) {
logger.error("Err creating global table", e);
Expand All @@ -144,13 +145,14 @@ private void initDatabase() {
try {
createCameraTableStatement = conn.createStatement();
var sql =
"CREATE TABLE IF NOT EXISTS cameras (\n"
+ " unique_name TINYTEXT PRIMARY KEY,\n"
+ " config_json text NOT NULL,\n"
+ " drivermode_json text NOT NULL,\n"
+ " otherpaths_json text NOT NULL,\n"
+ " pipeline_jsons mediumtext NOT NULL\n"
+ ");";
"""
CREATE TABLE IF NOT EXISTS cameras (
unique_name TINYTEXT PRIMARY KEY,
config_json text NOT NULL,
drivermode_json text NOT NULL,
otherpaths_json text NOT NULL,
pipeline_jsons mediumtext NOT NULL
);""";
createCameraTableStatement.execute(sql);
} catch (SQLException e) {
logger.error("Err creating cameras table", e);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,7 @@ public class NetworkTablesManager {

private boolean m_isRetryingConnection = false;

private StringSubscriber m_fieldLayoutSubscriber =
private final StringSubscriber m_fieldLayoutSubscriber =
kRootTable.getStringTopic(kFieldLayoutName).subscribe("");

private NetworkTablesManager() {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@ public abstract class GPIOBase {
private static final Logger logger = new Logger(GPIOBase.class, LogGroup.General);
private static final ShellExec runCommand = new ShellExec(true, true);

protected static HashMap<String, String> commands =
protected static final HashMap<String, String> commands =
new HashMap<>() {
{
put("setState", "");
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,9 +18,9 @@
package org.photonvision.common.hardware.GPIO.pi;

public class PigpioPulse {
int gpioOn;
int gpioOff;
int delayMicros;
final int gpioOn;
final int gpioOff;
final int delayMicros;

/**
* Initialises a pulse.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -242,21 +242,14 @@ public void generateAndSendWaveform(int pulseTimeMillis, int blinks, int... pins
waveSendOnce(waveformId);
}
} else {
String error = "";
switch (waveformId) {
case PI_EMPTY_WAVEFORM:
error = "Waveform empty";
break;
case PI_TOO_MANY_CBS:
error = "Too many CBS";
break;
case PI_TOO_MANY_OOL:
error = "Too many OOL";
break;
case PI_NO_WAVEFORM_ID:
error = "No waveform ID";
break;
}
String error =
switch (waveformId) {
case PI_EMPTY_WAVEFORM -> "Waveform empty";
case PI_TOO_MANY_CBS -> "Too many CBS";
case PI_TOO_MANY_OOL -> "Too many OOL";
case PI_NO_WAVEFORM_ID -> "No waveform ID";
default -> "";
};
logger.error("Failed to send wave: " + error);
}
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -134,25 +134,17 @@ void onLedModeChange(NetworkTableEvent entryNotification) {
var newLedModeRaw = (int) entryNotification.valueData.value.getInteger();
logger.debug("Got LED mode " + newLedModeRaw);
if (newLedModeRaw != currentLedMode.value) {
VisionLEDMode newLedMode;
switch (newLedModeRaw) {
case -1:
newLedMode = VisionLEDMode.kDefault;
break;
case 0:
newLedMode = VisionLEDMode.kOff;
break;
case 1:
newLedMode = VisionLEDMode.kOn;
break;
case 2:
newLedMode = VisionLEDMode.kBlink;
break;
default:
logger.warn("User supplied invalid LED mode, falling back to Default");
newLedMode = VisionLEDMode.kDefault;
break;
}
VisionLEDMode newLedMode =
switch (newLedModeRaw) {
case -1 -> VisionLEDMode.kDefault;
case 0 -> VisionLEDMode.kOff;
case 1 -> VisionLEDMode.kOn;
case 2 -> VisionLEDMode.kBlink;
default -> {
logger.warn("User supplied invalid LED mode, falling back to Default");
yield VisionLEDMode.kDefault;
}
};
setInternal(newLedMode, true);

if (modeConsumer != null) modeConsumer.accept(newLedMode.value);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -84,7 +84,7 @@ public enum WPI2019Image {
kRocketPanelAngleDark48in(1.2192),
kRocketPanelAngleDark60in(1.524);

public static double FOV = 68.5;
public static final double FOV = 68.5;

public final double distanceMeters;
public final Path path;
Expand Down Expand Up @@ -122,7 +122,7 @@ public enum WPI2020Image {
kRedLoading_084in(2.1336),
kRedLoading_108in(2.7432);

public static double FOV = 68.5;
public static final double FOV = 68.5;

public final double distanceMeters;
public final Path path;
Expand All @@ -143,7 +143,7 @@ public enum WPI2023Apriltags {
k162_36_Straight,
k383_60_Angle2;

public static double FOV = 68.5;
public static final double FOV = 68.5;

public final Translation2d approxPose;
public final Path path;
Expand All @@ -170,7 +170,7 @@ public enum WPI2022Image {
kTerminal12ft6in(Units.feetToMeters(12.5)),
kTerminal22ft6in(Units.feetToMeters(22.5));

public static double FOV = 68.5;
public static final double FOV = 68.5;

public final double distanceMeters;
public final Path path;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -51,11 +51,10 @@ public void set(T first, T second) {

@Override
public boolean equals(Object obj) {
if (!(obj instanceof NumberCouple)) {
if (!(obj instanceof NumberCouple couple)) {
return false;
}

var couple = (NumberCouple) obj;
if (!couple.first.equals(first)) {
return false;
}
Expand Down
29 changes: 10 additions & 19 deletions photon-core/src/main/java/org/photonvision/raspi/LibCameraJNI.java
Original file line number Diff line number Diff line change
Expand Up @@ -71,25 +71,16 @@ public enum SensorModel {
Unknown;

public String getFriendlyName() {
switch (this) {
case Disconnected:
return "Disconnected Camera";
case OV5647:
return "Camera Module v1";
case IMX219:
return "Camera Module v2";
case IMX708:
return "Camera Module v3";
case IMX477:
return "HQ Camera";
case OV9281:
return "OV9281";
case OV7251:
return "OV7251";
case Unknown:
default:
return "Unknown Camera";
}
return switch (this) {
case Disconnected -> "Disconnected Camera";
case OV5647 -> "Camera Module v1";
case IMX219 -> "Camera Module v2";
case IMX708 -> "Camera Module v3";
case IMX477 -> "HQ Camera";
case OV9281 -> "OV9281";
case OV7251 -> "OV7251";
default -> "Unknown Camera";
};
}
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -113,7 +113,7 @@ public static QuirkyCamera getQuirkyCamera(int usbVid, int usbPid, String baseNa
// If we have a quirkycamera we need to copy the quirks from our predefined object and create
// a quirkycamera object with the baseName.
if (qc.usbVid == usbVid && qc.usbPid == usbPid && matchesBaseName) {
List<CameraQuirk> quirks = new ArrayList<CameraQuirk>();
List<CameraQuirk> quirks = new ArrayList<>();
for (var q : CameraQuirk.values()) {
if (qc.hasQuirk(q)) quirks.add(q);
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@ public class FrameStaticProperties {
public final Point centerPoint;
public final double horizontalFocalLength;
public final double verticalFocalLength;
public CameraCalibrationCoefficients cameraCalibration;
public final CameraCalibrationCoefficients cameraCalibration;

/**
* Instantiates a new Frame static properties.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -39,8 +39,8 @@ public class FileSaveFrameConsumer implements Consumer<CVMat> {
private static final String FILE_EXTENSION = ".jpg";
private static final String NT_SUFFIX = "SaveImgCmd";

DateFormat df = new SimpleDateFormat("yyyy-MM-dd");
DateFormat tf = new SimpleDateFormat("hhmmssSS");
final DateFormat df = new SimpleDateFormat("yyyy-MM-dd");
final DateFormat tf = new SimpleDateFormat("hhmmssSS");

private final NetworkTable rootTable;
private NetworkTable subTable;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -228,20 +228,14 @@ private static String videoModeToString(VideoMode mode) {
}

private static String pixelFormatToString(VideoMode.PixelFormat pixelFormat) {
switch (pixelFormat) {
case kMJPEG:
return "MJPEG";
case kYUYV:
return "YUYV";
case kRGB565:
return "RGB565";
case kBGR:
return "BGR";
case kGray:
return "Gray";
default:
return "Unknown";
}
return switch (pixelFormat) {
case kMJPEG -> "MJPEG";
case kYUYV -> "YUYV";
case kRGB565 -> "RGB565";
case kBGR -> "BGR";
case kGray -> "Gray";
default -> "Unknown";
};
}

@Override
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -31,9 +31,9 @@

public abstract class CpuImageProcessor implements FrameProvider {
protected static class CapturedFrame {
CVMat colorImage;
FrameStaticProperties staticProps;
long captureTimestamp;
final CVMat colorImage;
final FrameStaticProperties staticProps;
final long captureTimestamp;

public CapturedFrame(
CVMat colorImage, FrameStaticProperties staticProps, long captureTimestampNanos) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -25,10 +25,8 @@
public class USBFrameProvider extends CpuImageProcessor {
private final CvSink cvSink;

@SuppressWarnings("SpellCheckingInspection")
private final VisionSourceSettables settables;

@SuppressWarnings("SpellCheckingInspection")
public USBFrameProvider(CvSink sink, VisionSourceSettables visionSettables) {
cvSink = sink;
cvSink.setEnabled(true);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@
* @param <P> Parameters type for the pipe
*/
public abstract class CVPipe<I, O, P> {
protected CVPipeResult<O> result = new CVPipeResult<>();
protected final CVPipeResult<O> result = new CVPipeResult<>();
protected P params;

public void setParams(P params) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@ public AprilTagPoseEstimatorPipe() {
super();
}

MatOfPoint2f temp = new MatOfPoint2f();
final MatOfPoint2f temp = new MatOfPoint2f();

@Override
protected AprilTagPoseEstimate process(AprilTagDetection in) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@ public class ArucoDetectionPipeParams {
*
* <p>E.g. 36h11 -> 11 * errorCorrectionRate = Max error bits
*/
public double errorCorrectionRate = 0;
public final double errorCorrectionRate = 0;

/**
* If obtained corners should be iteratively refined. This should always be on for 3D estimation.
Expand All @@ -51,7 +51,7 @@ public class ArucoDetectionPipeParams {
*/
public double refinementMinErrorPx = 0.005;

public boolean debugRefineWindow = false;
public final boolean debugRefineWindow = false;

/**
* If the 'Aruco3' speedup should be used. This is similar to AprilTag's 'decimate' value, but
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@
public class CalculateFPSPipe
extends CVPipe<Void, Integer, CalculateFPSPipe.CalculateFPSPipeParams> {
private final LinearFilter fpsFilter = LinearFilter.movingAverage(20);
StopWatch clock = new StopWatch();
final StopWatch clock = new StopWatch();

@Override
protected Integer process(Void in) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -33,9 +33,9 @@ public class CornerDetectionPipe
List<TrackedTarget>,
List<TrackedTarget>,
CornerDetectionPipe.CornerDetectionPipeParameters> {
Comparator<Point> leftRightComparator = Comparator.comparingDouble(point -> point.x);
Comparator<Point> verticalComparator = Comparator.comparingDouble(point -> point.y);
MatOfPoint2f polyOutput = new MatOfPoint2f();
final Comparator<Point> leftRightComparator = Comparator.comparingDouble(point -> point.x);
final Comparator<Point> verticalComparator = Comparator.comparingDouble(point -> point.y);
final MatOfPoint2f polyOutput = new MatOfPoint2f();

@Override
protected List<TrackedTarget> process(List<TrackedTarget> targetList) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -90,8 +90,8 @@ protected Void process(Pair<Mat, List<TrackedTarget>> in) {
}

public static class Draw2dCrosshairParams {
public boolean showCrosshair = true;
public Color crosshairColor = Color.GREEN;
public final boolean showCrosshair = true;
public final Color crosshairColor = Color.GREEN;

public final boolean shouldDraw;
public final FrameStaticProperties frameStaticProperties;
Expand Down
Loading

0 comments on commit 184be30

Please sign in to comment.