Skip to content

Commit

Permalink
Remove camera trust zones, make tag layout be taken as a parameter, a…
Browse files Browse the repository at this point in the history
…dd LayoutUtil with layout loading util previously in CoreVisionConstants, and remove unneeded constants
  • Loading branch information
aidnem authored and aidnem committed Nov 23, 2024
1 parent 32ac15e commit 30ebeca
Show file tree
Hide file tree
Showing 8 changed files with 76 additions and 121 deletions.
48 changes: 2 additions & 46 deletions vision/src/main/java/coppercore/vision/Camera.java
Original file line number Diff line number Diff line change
@@ -1,29 +1,20 @@
package coppercore.vision;

import coppercore.vision.CoreVisionConstants.CameraParams;
import coppercore.vision.VisionLocalizer.CameraMeasurement;
import edu.wpi.first.math.Matrix;
import edu.wpi.first.math.VecBuilder;
import edu.wpi.first.math.numbers.N1;
import edu.wpi.first.math.numbers.N3;
import org.littletonrobotics.junction.Logger;

public class Camera {

public enum CameraTrustZone {
LEFT,
RIGHT,
MIDDLE,
}

public final String name;
public final CameraTrustZone zone;

private final CameraIO io;
private final CameraIOInputsAutoLogged inputs;

public Camera(CameraParams params, CameraIO io) {
name = params.name();
zone = params.zone();

this.io = io;
inputs = new CameraIOInputsAutoLogged();
Expand All @@ -48,42 +39,7 @@ public CameraMeasurement getLatestMeasurement() {
}

public Matrix<N3, N1> getLatestVariance() {
// If the robot is not in teleop, trust cameras based on their location relative to the tags
return CoreVisionConstants.lowCameraUncertainty;
// TODO: Actually calculate variances!
// if (!DriverStation.isTeleop()) {
// switch (zone) {
// case LEFT:
// if (AllianceUtil.isRightOfSpeaker(inputs.latestFieldToRobot.getY(), 2)) {
// return VisionConstants.lowCameraUncertainty;
// }
// break;
// case RIGHT:
// if (AllianceUtil.isLeftOfSpeaker(inputs.latestFieldToRobot.getY(), 2)) {
// return VisionConstants.lowCameraUncertainty;
// }
// break;
// case MIDDLE:
// break;
// }
// }

// // If the robot is very close, trust highly
// if (inputs.averageTagDistanceM < VisionConstants.skewCutoffDistance) {
// return DriverStation.isTeleop()
// ? VisionConstants.teleopCameraUncertainty
// : VisionConstants.lowCameraUncertainty;
// // If the robot is somewhat close, check if the cameras are at extreme angles, and
// trust
// // accordingly
// } else if (inputs.averageTagDistanceM < VisionConstants.lowUncertaintyCutoffDistance) {
// return Math.abs(inputs.averageTagYaw.getDegrees()) <
// VisionConstants.skewCutoffRotation
// ? VisionConstants.lowCameraUncertainty
// : VisionConstants.highCameraUncertainty;
// // If the robot is past the final distance cutoff, distrust
// } else {
// return VisionConstants.highCameraUncertainty;
// }
return VecBuilder.fill(0.0, 0.0, 0.0);
}
}
Original file line number Diff line number Diff line change
@@ -1,16 +1,16 @@
package coppercore.vision;

import coppercore.vision.CoreVisionConstants.CameraParams;
import edu.wpi.first.apriltag.AprilTagFieldLayout;
import java.util.ArrayList;
import java.util.List;

public class CameraContainerReal implements CameraContainer {

private List<Camera> cameras = new ArrayList<>();

public CameraContainerReal(List<CameraParams> params) {
public CameraContainerReal(List<CameraParams> params, AprilTagFieldLayout layout) {
for (CameraParams param : params) {
cameras.add(new Camera(param, CameraIOPhoton.fromRealCameraParams(param)));
cameras.add(new Camera(param, CameraIOPhoton.fromRealCameraParams(param, layout)));
}
}

Expand Down
Original file line number Diff line number Diff line change
@@ -1,6 +1,5 @@
package coppercore.vision;

import coppercore.vision.CoreVisionConstants.CameraParams;
import java.util.ArrayList;
import java.util.List;

Expand Down
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
package coppercore.vision;

import coppercore.vision.CoreVisionConstants.CameraParams;
import edu.wpi.first.apriltag.AprilTagFieldLayout;
import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.geometry.Twist2d;
Expand Down Expand Up @@ -36,12 +36,13 @@ public class CameraContainerSim implements CameraContainer {

public CameraContainerSim(
List<CameraParams> params,
AprilTagFieldLayout layout,
Pose2d initialPose,
SwerveDriveKinematics kinematics,
Supplier<SwerveModuleState[]> getModuleStates) {
this.getModuleStates = getModuleStates;

visionSim.addAprilTags(CoreVisionConstants.fieldLayout);
visionSim.addAprilTags(layout);

this.kinematics = kinematics;

Expand All @@ -53,7 +54,9 @@ public CameraContainerSim(

for (CameraParams param : params) {
cameras.add(
new Camera(param, CameraIOPhoton.fromSimCameraParams(param, visionSim, true)));
new Camera(
param,
CameraIOPhoton.fromSimCameraParams(param, layout, visionSim, true)));
}
}

Expand Down
28 changes: 17 additions & 11 deletions vision/src/main/java/coppercore/vision/CameraIOPhoton.java
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
package coppercore.vision;

import coppercore.vision.CoreVisionConstants.CameraParams;
import edu.wpi.first.apriltag.AprilTagFieldLayout;
import edu.wpi.first.math.geometry.Pose3d;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.geometry.Transform3d;
Expand All @@ -22,26 +22,26 @@ public class CameraIOPhoton implements CameraIO {

private double latestTimestampSeconds = 0.0;

public CameraIOPhoton(String name, Transform3d robotToCamera) {
this(new PhotonCamera(name), robotToCamera);
public CameraIOPhoton(String name, AprilTagFieldLayout layout, Transform3d robotToCamera) {
this(new PhotonCamera(name), layout, robotToCamera);
}

public CameraIOPhoton(PhotonCamera camera, Transform3d robotToCamera) {
public CameraIOPhoton(
PhotonCamera camera, AprilTagFieldLayout layout, Transform3d robotToCamera) {
this.camera = camera;

poseEstimator =
new PhotonPoseEstimator(
CoreVisionConstants.fieldLayout,
PoseStrategy.MULTI_TAG_PNP_ON_COPROCESSOR,
robotToCamera);
layout, PoseStrategy.MULTI_TAG_PNP_ON_COPROCESSOR, robotToCamera);
}

public static CameraIOPhoton fromRealCameraParams(CameraParams params) {
return new CameraIOPhoton(params.name(), params.robotToCamera());
public static CameraIOPhoton fromRealCameraParams(
CameraParams params, AprilTagFieldLayout layout) {
return new CameraIOPhoton(params.name(), layout, params.robotToCamera());
}

public static CameraIOPhoton fromSimCameraParams(
CameraParams params, VisionSystemSim sim, boolean stream) {
CameraParams params, AprilTagFieldLayout layout, VisionSystemSim sim, boolean stream) {
PhotonCamera camera = new PhotonCamera(params.name());

SimCameraProperties props = new SimCameraProperties();
Expand All @@ -55,7 +55,7 @@ public static CameraIOPhoton fromSimCameraParams(
cameraSim.enableRawStream(stream);
cameraSim.enableProcessedStream(stream);

return new CameraIOPhoton(camera, params.robotToCamera());
return new CameraIOPhoton(camera, layout, params.robotToCamera());
}

@Override
Expand Down Expand Up @@ -91,6 +91,7 @@ public void updateInputs(CameraIOInputs inputs) {
}

private static boolean filterPhotonPose(EstimatedRobotPose photonPose) {
// TODO: Actual pose rejection
if (photonPose.targetsUsed.size() < 2) {
return false;
}
Expand All @@ -101,6 +102,11 @@ private static boolean filterPhotonPose(EstimatedRobotPose photonPose) {
return false;
}

if (calculateAverageTagDistance(photonPose)
> CoreVisionConstants.maxAcceptedDistanceMeters) {
return false;
}

return true;
}

Expand Down
12 changes: 12 additions & 0 deletions vision/src/main/java/coppercore/vision/CameraParams.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,12 @@
package coppercore.vision;

import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.geometry.Transform3d;

public record CameraParams(
String name,
int xResolution,
int yResolution,
int fps,
Rotation2d fov,
Transform3d robotToCamera) {}
65 changes: 8 additions & 57 deletions vision/src/main/java/coppercore/vision/CoreVisionConstants.java
Original file line number Diff line number Diff line change
@@ -1,61 +1,12 @@
package coppercore.vision;

import coppercore.vision.Camera.CameraTrustZone;
import edu.wpi.first.apriltag.AprilTagFieldLayout;
import edu.wpi.first.math.Matrix;
import edu.wpi.first.math.VecBuilder;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.geometry.Transform3d;
import edu.wpi.first.math.numbers.N1;
import edu.wpi.first.math.numbers.N3;
import edu.wpi.first.math.util.Units;
import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.Filesystem;
import java.io.IOException;
import java.util.Collections;

/**
* Vision constants for coppercore's internal vision constants. Not to be confused with
* VisionConstants, which is likely your robot project's local vision constants that are configured
* per-project.
*/
public final class CoreVisionConstants {
public static final String tagLayoutName = "Pairs-Only";
public static final AprilTagFieldLayout fieldLayout = initLayout(tagLayoutName);

public static final double lowUncertaintyCutoffDistance = 6.5;

public static final double skewCutoffDistance = 5.8;
public static final double skewCutoffRotation = Units.degreesToRadians(50);

public static final Matrix<N3, N1> teleopCameraUncertainty = VecBuilder.fill(0.35, 0.35, 3.5);

public static final Matrix<N3, N1> lowCameraUncertainty = VecBuilder.fill(0.6, 1.0, 4);

public static final Matrix<N3, N1> highCameraUncertainty = VecBuilder.fill(12.0, 16.0, 40);

public static final Matrix<N3, N1> driveUncertainty = VecBuilder.fill(0.1, 0.1, 0.1);

public static record CameraParams(
String name,
int xResolution,
int yResolution,
int fps,
Rotation2d fov,
Transform3d robotToCamera,
CameraTrustZone zone) {}

private static AprilTagFieldLayout initLayout(String name) {
AprilTagFieldLayout layout;
// AprilTagFieldLayout's constructor throws an IOException, so we must catch it
// in order to initialize our layout as a static constant
try {
layout =
new AprilTagFieldLayout(
Filesystem.getDeployDirectory().getAbsolutePath()
+ "/taglayout/"
+ name
+ ".json");
} catch (IOException ioe) {
DriverStation.reportWarning(
"Failed to load AprilTag Layout: " + ioe.getLocalizedMessage(), false);
layout = new AprilTagFieldLayout(Collections.emptyList(), 0.0, 0.0);
}
return layout;
}
// TODO: Tune this value
// This value mainly exists so that this file stays named CoreVisionConstants.
public static final double maxAcceptedDistanceMeters = 10.0;
}
28 changes: 28 additions & 0 deletions vision/src/main/java/coppercore/vision/LayoutUtil.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,28 @@
package coppercore.vision;

import edu.wpi.first.apriltag.AprilTagFieldLayout;
import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.Filesystem;
import java.io.IOException;
import java.util.Collections;

public class LayoutUtil {
public static AprilTagFieldLayout initLayout(String name) {
AprilTagFieldLayout layout;
// AprilTagFieldLayout's constructor throws an IOException, so we must catch it
// in order to initialize our layout as a static constant
try {
layout =
new AprilTagFieldLayout(
Filesystem.getDeployDirectory().getAbsolutePath()
+ "/taglayout/"
+ name
+ ".json");
} catch (IOException ioe) {
DriverStation.reportWarning(
"Failed to load AprilTag Layout: " + ioe.getLocalizedMessage(), false);
layout = new AprilTagFieldLayout(Collections.emptyList(), 0.0, 0.0);
}
return layout;
}
}

0 comments on commit 30ebeca

Please sign in to comment.