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

Changes sim to use 36h11 tags #1056

Merged
merged 13 commits into from
Jan 2, 2024
Merged
2 changes: 1 addition & 1 deletion build.gradle
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@ allprojects {
apply from: "versioningHelper.gradle"

ext {
wpilibVersion = "2024.1.1-beta-4"
wpilibVersion = "2024.1.1-beta-4-35-g141241d"
wpimathVersion = wpilibVersion
openCVversion = "4.8.0-2"
joglVersion = "2.4.0-rc-20200307"
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@
package org.photonvision.vision.camera;

import edu.wpi.first.cscore.VideoMode;
import edu.wpi.first.cscore.VideoMode.PixelFormat;
import edu.wpi.first.util.PixelFormat;
import java.nio.file.Path;
import java.util.HashMap;
import org.photonvision.common.configuration.CameraConfiguration;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@

import edu.wpi.first.cscore.VideoMode;
import edu.wpi.first.math.Pair;
import edu.wpi.first.util.PixelFormat;
import java.util.HashMap;
import org.photonvision.common.configuration.CameraConfiguration;
import org.photonvision.common.util.math.MathUtils;
Expand Down Expand Up @@ -59,30 +60,19 @@ public LibcameraGpuSettables(CameraConfiguration configuration) {

if (sensorModel == LibCameraJNI.SensorModel.IMX219) {
// Settings for the IMX219 sensor, which is used on the Pi Camera Module v2
videoModes.put(
0, new FPSRatedVideoMode(VideoMode.PixelFormat.kUnknown, 320, 240, 120, 120, .39));
videoModes.put(
1, new FPSRatedVideoMode(VideoMode.PixelFormat.kUnknown, 320, 240, 30, 30, .39));
videoModes.put(
2, new FPSRatedVideoMode(VideoMode.PixelFormat.kUnknown, 640, 480, 65, 90, .39));
videoModes.put(
3, new FPSRatedVideoMode(VideoMode.PixelFormat.kUnknown, 640, 480, 30, 30, .39));
videoModes.put(0, new FPSRatedVideoMode(PixelFormat.kUnknown, 320, 240, 120, 120, .39));
videoModes.put(1, new FPSRatedVideoMode(PixelFormat.kUnknown, 320, 240, 30, 30, .39));
videoModes.put(2, new FPSRatedVideoMode(PixelFormat.kUnknown, 640, 480, 65, 90, .39));
videoModes.put(3, new FPSRatedVideoMode(PixelFormat.kUnknown, 640, 480, 30, 30, .39));
// TODO: fix 1280x720 in the native code and re-add it
videoModes.put(
4, new FPSRatedVideoMode(VideoMode.PixelFormat.kUnknown, 1920, 1080, 15, 20, .53));
videoModes.put(
5, new FPSRatedVideoMode(VideoMode.PixelFormat.kUnknown, 3280 / 2, 2464 / 2, 15, 20, 1));
videoModes.put(
6, new FPSRatedVideoMode(VideoMode.PixelFormat.kUnknown, 3280 / 4, 2464 / 4, 15, 20, 1));
videoModes.put(4, new FPSRatedVideoMode(PixelFormat.kUnknown, 1920, 1080, 15, 20, .53));
videoModes.put(5, new FPSRatedVideoMode(PixelFormat.kUnknown, 3280 / 2, 2464 / 2, 15, 20, 1));
videoModes.put(6, new FPSRatedVideoMode(PixelFormat.kUnknown, 3280 / 4, 2464 / 4, 15, 20, 1));
} else if (sensorModel == LibCameraJNI.SensorModel.OV9281) {
videoModes.put(
0, new FPSRatedVideoMode(VideoMode.PixelFormat.kUnknown, 320, 240, 30, 30, .39));
videoModes.put(
1, new FPSRatedVideoMode(VideoMode.PixelFormat.kUnknown, 1280 / 2, 800 / 2, 60, 60, 1));
videoModes.put(
2, new FPSRatedVideoMode(VideoMode.PixelFormat.kUnknown, 640, 480, 65, 90, .39));
videoModes.put(
3, new FPSRatedVideoMode(VideoMode.PixelFormat.kUnknown, 1280, 800, 60, 60, 1));
videoModes.put(0, new FPSRatedVideoMode(PixelFormat.kUnknown, 320, 240, 30, 30, .39));
videoModes.put(1, new FPSRatedVideoMode(PixelFormat.kUnknown, 1280 / 2, 800 / 2, 60, 60, 1));
videoModes.put(2, new FPSRatedVideoMode(PixelFormat.kUnknown, 640, 480, 65, 90, .39));
videoModes.put(3, new FPSRatedVideoMode(PixelFormat.kUnknown, 1280, 800, 60, 60, 1));

} else {
if (sensorModel == LibCameraJNI.SensorModel.IMX477) {
Expand All @@ -97,17 +87,13 @@ public LibcameraGpuSettables(CameraConfiguration configuration) {
}

// Settings for the OV5647 sensor, which is used by the Pi Camera Module v1
videoModes.put(0, new FPSRatedVideoMode(VideoMode.PixelFormat.kUnknown, 320, 240, 90, 90, 1));
videoModes.put(1, new FPSRatedVideoMode(VideoMode.PixelFormat.kUnknown, 640, 480, 85, 90, 1));
videoModes.put(
2, new FPSRatedVideoMode(VideoMode.PixelFormat.kUnknown, 960, 720, 45, 49, 0.74));
videoModes.put(0, new FPSRatedVideoMode(PixelFormat.kUnknown, 320, 240, 90, 90, 1));
videoModes.put(1, new FPSRatedVideoMode(PixelFormat.kUnknown, 640, 480, 85, 90, 1));
videoModes.put(2, new FPSRatedVideoMode(PixelFormat.kUnknown, 960, 720, 45, 49, 0.74));
// Half the size of the active areas on the OV5647
videoModes.put(
3, new FPSRatedVideoMode(VideoMode.PixelFormat.kUnknown, 2592 / 2, 1944 / 2, 20, 20, 1));
videoModes.put(
4, new FPSRatedVideoMode(VideoMode.PixelFormat.kUnknown, 1280, 720, 30, 45, 0.91));
videoModes.put(
5, new FPSRatedVideoMode(VideoMode.PixelFormat.kUnknown, 1920, 1080, 15, 20, 0.72));
videoModes.put(3, new FPSRatedVideoMode(PixelFormat.kUnknown, 2592 / 2, 1944 / 2, 20, 20, 1));
videoModes.put(4, new FPSRatedVideoMode(PixelFormat.kUnknown, 1280, 720, 30, 45, 0.91));
videoModes.put(5, new FPSRatedVideoMode(PixelFormat.kUnknown, 1920, 1080, 15, 20, 0.72));
}

// TODO need to add more video modes for new sensors here
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@
package org.photonvision.vision.camera;

import edu.wpi.first.cscore.VideoMode;
import edu.wpi.first.util.PixelFormat;
import org.photonvision.common.configuration.CameraConfiguration;
import org.photonvision.common.configuration.ConfigManager;
import org.photonvision.common.logging.LogGroup;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,7 @@
import edu.wpi.first.cscore.VideoException;
import edu.wpi.first.cscore.VideoMode;
import edu.wpi.first.cscore.VideoProperty.Kind;
import edu.wpi.first.util.PixelFormat;
import java.util.*;
import java.util.stream.Collectors;
import org.photonvision.common.configuration.CameraConfiguration;
Expand Down Expand Up @@ -280,33 +281,33 @@ public HashMap<Integer, VideoMode> getAllVideoModes() {
if (cameraQuirks.hasQuirk(CameraQuirk.PiCam)) {
modes =
new VideoMode[] {
new VideoMode(VideoMode.PixelFormat.kBGR, 320, 240, 90),
new VideoMode(VideoMode.PixelFormat.kBGR, 320, 240, 30),
new VideoMode(VideoMode.PixelFormat.kBGR, 320, 240, 15),
new VideoMode(VideoMode.PixelFormat.kBGR, 320, 240, 10),
new VideoMode(VideoMode.PixelFormat.kBGR, 640, 480, 90),
new VideoMode(VideoMode.PixelFormat.kBGR, 640, 480, 45),
new VideoMode(VideoMode.PixelFormat.kBGR, 640, 480, 30),
new VideoMode(VideoMode.PixelFormat.kBGR, 640, 480, 15),
new VideoMode(VideoMode.PixelFormat.kBGR, 640, 480, 10),
new VideoMode(VideoMode.PixelFormat.kBGR, 960, 720, 60),
new VideoMode(VideoMode.PixelFormat.kBGR, 960, 720, 10),
new VideoMode(VideoMode.PixelFormat.kBGR, 1280, 720, 45),
new VideoMode(VideoMode.PixelFormat.kBGR, 1920, 1080, 20),
new VideoMode(PixelFormat.kBGR, 320, 240, 90),
new VideoMode(PixelFormat.kBGR, 320, 240, 30),
new VideoMode(PixelFormat.kBGR, 320, 240, 15),
new VideoMode(PixelFormat.kBGR, 320, 240, 10),
new VideoMode(PixelFormat.kBGR, 640, 480, 90),
new VideoMode(PixelFormat.kBGR, 640, 480, 45),
new VideoMode(PixelFormat.kBGR, 640, 480, 30),
new VideoMode(PixelFormat.kBGR, 640, 480, 15),
new VideoMode(PixelFormat.kBGR, 640, 480, 10),
new VideoMode(PixelFormat.kBGR, 960, 720, 60),
new VideoMode(PixelFormat.kBGR, 960, 720, 10),
new VideoMode(PixelFormat.kBGR, 1280, 720, 45),
new VideoMode(PixelFormat.kBGR, 1920, 1080, 20),
};
} else {
modes = camera.enumerateVideoModes();
}
for (VideoMode videoMode : modes) {
// Filter grey modes
if (videoMode.pixelFormat == VideoMode.PixelFormat.kGray
|| videoMode.pixelFormat == VideoMode.PixelFormat.kUnknown) {
if (videoMode.pixelFormat == PixelFormat.kGray
|| videoMode.pixelFormat == PixelFormat.kUnknown) {
continue;
}

// On picam, filter non-bgr modes for performance
if (cameraQuirks.hasQuirk(CameraQuirk.PiCam)) {
if (videoMode.pixelFormat != VideoMode.PixelFormat.kBGR) {
if (videoMode.pixelFormat != PixelFormat.kBGR) {
continue;
}
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@
import edu.wpi.first.cscore.*;
import edu.wpi.first.networktables.NetworkTable;
import edu.wpi.first.networktables.NetworkTableInstance;
import edu.wpi.first.util.PixelFormat;
import java.awt.*;
import java.util.ArrayList;
import org.opencv.core.CvType;
Expand Down Expand Up @@ -118,7 +119,7 @@ public class MJPGFrameConsumer implements AutoCloseable {
boolean isDisabled = false;

public MJPGFrameConsumer(String sourceName, int width, int height, int port) {
this.cvSource = new CvSource(sourceName, VideoMode.PixelFormat.kMJPEG, width, height, 30);
this.cvSource = new CvSource(sourceName, PixelFormat.kMJPEG, width, height, 30);
this.table =
NetworkTableInstance.getDefault().getTable("/CameraPublisher").getSubTable(sourceName);

Expand Down Expand Up @@ -188,7 +189,7 @@ public void accept(CVMat image) {

public void disabledTick() {
if (!isDisabled) {
cvSource.setVideoMode(VideoMode.PixelFormat.kMJPEG, EMPTY_MAT.width(), EMPTY_MAT.height(), 0);
cvSource.setVideoMode(PixelFormat.kMJPEG, EMPTY_MAT.width(), EMPTY_MAT.height(), 0);
isDisabled = true;
}

Expand Down Expand Up @@ -227,7 +228,7 @@ private static String videoModeToString(VideoMode mode) {
+ " fps";
}

private static String pixelFormatToString(VideoMode.PixelFormat pixelFormat) {
private static String pixelFormatToString(PixelFormat pixelFormat) {
switch (pixelFormat) {
case kMJPEG:
return "MJPEG";
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -28,11 +28,11 @@
import edu.wpi.first.apriltag.AprilTagFields;
import edu.wpi.first.cameraserver.CameraServer;
import edu.wpi.first.cscore.CvSource;
import edu.wpi.first.cscore.VideoMode.PixelFormat;
import edu.wpi.first.cscore.VideoSource.ConnectionStrategy;
import edu.wpi.first.math.MathUtil;
import edu.wpi.first.math.Pair;
import edu.wpi.first.math.geometry.Pose3d;
import edu.wpi.first.util.PixelFormat;
import edu.wpi.first.util.WPIUtilJNI;
import java.util.ArrayList;
import java.util.List;
Expand Down Expand Up @@ -464,7 +464,7 @@ public PhotonPipelineResult process(
var corn = pair.getSecond();

if (tgt.fiducialID >= 0) { // apriltags
VideoSimUtil.warp16h5TagImage(tgt.fiducialID, corn, true, videoSimFrameRaw);
VideoSimUtil.warp36h11TagImage(tgt.fiducialID, corn, true, videoSimFrameRaw);
} else if (!tgt.getModel().isSpherical) { // non-spherical targets
var contour = corn;
if (!tgt.getModel()
Expand Down Expand Up @@ -529,7 +529,7 @@ public PhotonPipelineResult process(
prop.getDistCoeffs(),
detectableTgts,
tagLayout,
TargetModel.kAprilTag16h5);
TargetModel.kAprilTag36h11);
multitagResult = new MultiTargetPNPResult(pnpResult, usedIDs);
}

Expand Down
Loading