Skip to content

Commit

Permalink
changed cam configs so sim doesn't crash
Browse files Browse the repository at this point in the history
  • Loading branch information
sigalrmp committed Sep 4, 2024
1 parent dff9391 commit 6609665
Show file tree
Hide file tree
Showing 2 changed files with 6 additions and 5 deletions.
2 changes: 1 addition & 1 deletion src/main/java/org/sciborgs1155/robot/vision/Vision.java
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,7 @@ public static record PoseEstimate(EstimatedRobotPose estimatedPose, Matrix<N3, N

/** A factory to create new vision classes with our two configured cameras. */
public static Vision create() {
return new Vision();
return new Vision(BACK_LEFT_CAMERA, BACK_RIGHT_CAMERA, FRONT_LEFT_CAMERA, FRONT_RIGHT_CAMERA);
}

public Vision(CameraConfig... configs) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@
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.Rotation3d;
import edu.wpi.first.math.geometry.Transform3d;
import edu.wpi.first.math.numbers.N1;
import edu.wpi.first.math.numbers.N3;
Expand All @@ -16,14 +17,14 @@ public class VisionConstants {

/** TODO: Create cameras with updated constants; be sure to add in {@link Vision#create} */
public static final CameraConfig BACK_LEFT_CAMERA =
new CameraConfig("back left", new Transform3d());
new CameraConfig("back left", new Transform3d(1, 1, 1, new Rotation3d()));

public static final CameraConfig BACK_RIGHT_CAMERA =
new CameraConfig("back right", new Transform3d());
new CameraConfig("back right", new Transform3d(1, 1, 1, new Rotation3d()));
public static final CameraConfig FRONT_LEFT_CAMERA =
new CameraConfig("front left", new Transform3d());
new CameraConfig("front left", new Transform3d(1, 1, 1, new Rotation3d()));
public static final CameraConfig FRONT_RIGHT_CAMERA =
new CameraConfig("front right", new Transform3d());
new CameraConfig("front right", new Transform3d(1, 1, 1, new Rotation3d()));

// OV9281 constants for our configuration
public static final int WIDTH = 1280;
Expand Down

0 comments on commit 6609665

Please sign in to comment.