Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Java 17 #1440

Open
wants to merge 9 commits into
base: master
Choose a base branch
from
Open

Java 17 #1440

Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 2 additions & 2 deletions docs/source/docs/installation/sw_install/linux-pc.md
Original file line number Diff line number Diff line change
Expand Up @@ -8,10 +8,10 @@ You do not need to install PhotonVision on a Windows PC in order to access the w

## Installing Java

PhotonVision requires a JDK installed and on the system path. JDK 11 is needed (different versions will not work). If you don't have JDK 11 already, run the following to install it:
PhotonVision requires a JDK installed and on the system path. JDK 17 is needed (different versions will not work). If you don't have JDK 17 already, run the following to install it:

```
$ sudo apt-get install openjdk-11-jdk
$ sudo apt-get install openjdk-17-jdk
```

:::{warning}
Expand Down
4 changes: 2 additions & 2 deletions docs/source/docs/installation/sw_install/mac-os.md
Original file line number Diff line number Diff line change
Expand Up @@ -12,10 +12,10 @@ VERY Limited macOS support is available.

## Installing Java

PhotonVision requires a JDK installed and on the system path. JDK 11 is needed (different versions will not work). You may already have this if you have installed WPILib. If not, [download and install it from here](https://adoptium.net/temurin/releases?version=11).
PhotonVision requires a JDK installed and on the system path. JDK 17 is needed (different versions will not work). You may already have this if you have installed WPILib. If not, [download and install it from here](https://adoptium.net/temurin/releases?version=17).

:::{warning}
Using a JDK other than JDK11 will cause issues when running PhotonVision and is not supported.
Using a JDK other than JDK17 will cause issues when running PhotonVision and is not supported.
:::

## Downloading the Latest Stable Release of PhotonVision
Expand Down
2 changes: 1 addition & 1 deletion docs/source/docs/installation/sw_install/windows-pc.md
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@ Bonjour provides more stable networking when using Windows PCs. Install [Bonjour

## Installing Java

PhotonVision requires a JDK installed and on the system path. **JDK 11 is needed** (different versions will not work). You may already have this if you have installed WPILib, but ensure that running `java -version` shows JDK 11. If not, [download and install it from here](https://adoptium.net/temurin/releases?version=11) and ensure that the new JDK is being used.
PhotonVision requires a JDK installed and on the system path. **JDK 17 is needed** (different versions will not work). You may already have this if you have installed WPILib, but ensure that running `java -version` shows JDK 17. If not, [download and install it from here](https://adoptium.net/temurin/releases?version=17) and ensure that the new JDK is being used.

:::{warning}
Using a JDK other than JDK11 will cause issues when running PhotonVision and is not supported.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -70,16 +70,12 @@ public static ConfigManager getInstance() {
if (INSTANCE == null) {
Path rootFolder = PathManager.getInstance().getRootFolder();
switch (m_saveStrat) {
case SQL:
INSTANCE = new ConfigManager(rootFolder, new SqlConfigProvider(rootFolder));
break;
case LEGACY:
INSTANCE = new ConfigManager(rootFolder, new LegacyConfigProvider(rootFolder));
break;
case ATOMIC_ZIP:
// not yet done, fall through
default:
break;
case SQL -> INSTANCE = new ConfigManager(rootFolder, new SqlConfigProvider(rootFolder));
case LEGACY ->
INSTANCE = new ConfigManager(rootFolder, new LegacyConfigProvider(rootFolder));
case ATOMIC_ZIP -> {
// TODO: Not done yet
}
}
}
return INSTANCE;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -205,13 +205,11 @@ private void loadModel(File model) {

try {
switch (backend.get()) {
case RKNN:
case RKNN -> {
models.get(backend.get()).add(new RknnModel(model, labels));
logger.info(
"Loaded model " + model.getName() + " for backend " + backend.get().toString());
break;
default:
break;
}
}
} catch (IllegalArgumentException e) {
logger.error("Failed to load model " + model.getName(), e);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -599,9 +599,9 @@ private HashMap<String, CameraConfiguration> loadCameraConfigs(Connection conn)
result.getString(Columns.CAM_PIPELINE_JSONS), dummyList.getClass());

List<CVPipelineSettings> loadedSettings = new ArrayList<>();
for (var str : pipelineSettings) {
if (str instanceof String) {
loadedSettings.add(JacksonUtils.deserialize((String) str, CVPipelineSettings.class));
for (var setting : pipelineSettings) {
if (setting instanceof String str) {
loadedSettings.add(JacksonUtils.deserialize(str, CVPipelineSettings.class));
}
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -242,22 +242,7 @@ 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;
}
logger.error("Failed to send wave: " + error);
logger.error("Failed to send wave: " + getMessageForError(waveformId));
}
}

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 -> newLedMode = VisionLEDMode.kDefault;
case 0 -> newLedMode = VisionLEDMode.kOff;
case 1 -> newLedMode = VisionLEDMode.kOn;
case 2 -> newLedMode = 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 All @@ -164,37 +156,21 @@ private void setInternal(VisionLEDMode newLedMode, boolean fromNT) {

if (fromNT) {
switch (newLedMode) {
case kDefault:
setStateImpl(pipelineModeSupplier.getAsBoolean());
break;
case kOff:
setStateImpl(false);
break;
case kOn:
setStateImpl(true);
break;
case kBlink:
blinkImpl(85, -1);
break;
case kDefault -> setStateImpl(pipelineModeSupplier.getAsBoolean());
case kOff -> setStateImpl(false);
case kOn -> setStateImpl(true);
case kBlink -> blinkImpl(85, -1);
}
currentLedMode = newLedMode;
logger.info(
"Changing LED mode from \"" + lastLedMode.toString() + "\" to \"" + newLedMode + "\"");
} else {
if (currentLedMode == VisionLEDMode.kDefault) {
switch (newLedMode) {
case kDefault:
setStateImpl(pipelineModeSupplier.getAsBoolean());
break;
case kOff:
setStateImpl(false);
break;
case kOn:
setStateImpl(true);
break;
case kBlink:
blinkImpl(85, -1);
break;
case kDefault -> setStateImpl(pipelineModeSupplier.getAsBoolean());
case kOff -> setStateImpl(false);
case kOn -> setStateImpl(true);
case kBlink -> blinkImpl(85, -1);
}
}
logger.info("Changing LED internal state to " + newLedMode.toString());
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -51,16 +51,9 @@ public void set(T first, T second) {

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

var couple = (NumberCouple) obj;
if (!couple.first.equals(first)) {
return false;
}

return couple.second.equals(second);
return obj instanceof NumberCouple<?> couple
&& couple.first.equals(first)
&& couple.second.equals(second);
}

@JsonIgnore
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -135,20 +135,14 @@ private static String videoModeToString(VideoMode mode) {
}

private static String pixelFormatToString(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";
case kUYVY, kUnknown, kY16 -> "Unknown";
spacey-sooty marked this conversation as resolved.
Show resolved Hide resolved
};
}

@Override
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -158,18 +158,19 @@ public boolean isIntersecting(
double massX = (x0A + x0B) / 2;
double massY = (y0A + y0B) / 2;
switch (intersectionDirection) {
case Up:
case None -> {}
case Up -> {
if (intersectionY < massY) isIntersecting = true;
break;
case Down:
}
case Down -> {
if (intersectionY > massY) isIntersecting = true;
break;
case Left:
}
case Left -> {
if (intersectionX < massX) isIntersecting = true;
break;
case Right:
}
case Right -> {
if (intersectionX > massX) isIntersecting = true;
break;
}
}
intersectMatA.release();
intersectMatB.release();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,9 +17,6 @@

package org.photonvision.vision.opencv;

import java.util.EnumSet;
import java.util.HashMap;

public enum ContourShape {
Circle(0),
Custom(-1),
Expand All @@ -32,15 +29,12 @@ public enum ContourShape {
this.sides = sides;
}

private static final HashMap<Integer, ContourShape> sidesToValueMap = new HashMap<>();

static {
for (var value : EnumSet.allOf(ContourShape.class)) {
sidesToValueMap.put(value.sides, value);
}
}

public static ContourShape fromSides(int sides) {
return sidesToValueMap.get(sides);
return switch (sides) {
case 0 -> Circle;
case 3 -> Triangle;
case 4 -> Quadrilateral;
default -> Custom;
};
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -48,13 +48,14 @@ protected Void process(Pair<Mat, List<TrackedTarget>> in) {
double scale = params.frameStaticProperties.imageWidth / (double) params.divisor.value / 32.0;

switch (params.robotOffsetPointMode) {
case Single:
case None -> {}
case Single -> {
if (params.singleOffsetPoint.x != 0 && params.singleOffsetPoint.y != 0) {
x = params.singleOffsetPoint.x;
y = params.singleOffsetPoint.y;
}
break;
case Dual:
}
case Dual -> {
if (!in.getRight().isEmpty()) {
var target = in.getRight().get(0);
if (target != null) {
Expand All @@ -65,7 +66,7 @@ protected Void process(Pair<Mat, List<TrackedTarget>> in) {
y = offsetCrosshair.y;
}
}
break;
}
}

x /= (double) params.divisor.value;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -50,23 +50,7 @@ protected List<CVShape> process(List<Contour> in) {

private CVShape getShape(Contour in) {
int corners = getCorners(in);

/*The contourShape enum has predefined shapes for Circles, Triangles, and Quads
meaning any shape not fitting in those predefined shapes must be a custom shape.
*/
if (ContourShape.fromSides(corners) == null) {
return new CVShape(in, ContourShape.Custom);
}
switch (ContourShape.fromSides(corners)) {
case Circle:
return new CVShape(in, ContourShape.Circle);
case Triangle:
return new CVShape(in, ContourShape.Triangle);
case Quadrilateral:
return new CVShape(in, ContourShape.Quadrilateral);
}

return new CVShape(in, ContourShape.Custom);
return new CVShape(in, ContourShape.fromSides(corners));
}

private int getCorners(Contour contour) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -85,19 +85,29 @@ protected void setPipeParamsImpl() {
// 2023/other: best guess is 6in
double tagWidth = Units.inchesToMeters(6);
TargetModel tagModel = TargetModel.kAprilTag16h5;
switch (settings.tagFamily) {
case kTag36h11:
// 2024 tag, 6.5in
params.tagFamily = Objdetect.DICT_APRILTAG_36h11;
tagWidth = Units.inchesToMeters(6.5);
tagModel = TargetModel.kAprilTag36h11;
break;
case kTag25h9:
params.tagFamily = Objdetect.DICT_APRILTAG_25h9;
break;
default:
params.tagFamily = Objdetect.DICT_APRILTAG_16h5;
}

params.tagFamily =
switch (settings.tagFamily) {
case kTag36h11 -> {
// 2024 tag, 6.5in
tagWidth = Units.inchesToMeters(6.5);
tagModel = TargetModel.kAprilTag36h11;
yield Objdetect.DICT_APRILTAG_36h11;
}
case kTag25h9 -> Objdetect.DICT_APRILTAG_25h9;
// TODO: explicitly drop support for these
case kTag16h5,
kTagCircle21h7,
kTagCircle49h12,
kTagCustom48h11,
kTagStandard41h12,
kTagStandard52h13 -> {
// 2024 tag, 6.5in
tagWidth = Units.inchesToMeters(6.5);
tagModel = TargetModel.kAprilTag36h11;
yield Objdetect.DICT_APRILTAG_36h11;
}
};

int threshMinSize = Math.max(3, settings.threshWinSizes.getFirst());
settings.threshWinSizes.setFirst(threshMinSize);
Expand Down
Loading
Loading