Compare commits
2 Commits
9e247389e8
...
47f0de2ebb
| Author | SHA1 | Date | |
|---|---|---|---|
| 47f0de2ebb | |||
| 95e15ed75e |
@@ -22,11 +22,12 @@ public class Robot extends LoggedRobot {
|
|||||||
|
|
||||||
private final RobotContainer m_robotContainer;
|
private final RobotContainer m_robotContainer;
|
||||||
|
|
||||||
|
@SuppressWarnings("resource")
|
||||||
public Robot() {
|
public Robot() {
|
||||||
Logger.recordMetadata("ProjectName", "2026_Robot_Code");
|
Logger.recordMetadata("ProjectName", "2026_Robot_Code");
|
||||||
|
|
||||||
if(isReal()) {
|
if(isReal()) {
|
||||||
if(CompetitionConstants.logToNetworkTables) {
|
if(CompetitionConstants.kLogToNetworkTables) {
|
||||||
Logger.addDataReceiver(new NT4Publisher());
|
Logger.addDataReceiver(new NT4Publisher());
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -41,7 +42,7 @@ public class Robot extends LoggedRobot {
|
|||||||
}
|
}
|
||||||
|
|
||||||
Logger.start();
|
Logger.start();
|
||||||
|
|
||||||
m_robotContainer = new RobotContainer();
|
m_robotContainer = new RobotContainer();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
@@ -1,6 +1,13 @@
|
|||||||
package frc.robot.constants;
|
package frc.robot.constants;
|
||||||
|
|
||||||
|
import edu.wpi.first.apriltag.AprilTagFieldLayout;
|
||||||
|
import edu.wpi.first.apriltag.AprilTagFields;
|
||||||
|
|
||||||
public class CompetitionConstants {
|
public class CompetitionConstants {
|
||||||
// THIS SHOULD BE FALSE DURING COMPETITION PLAY
|
// THIS SHOULD BE FALSE DURING COMPETITION PLAY
|
||||||
public static final boolean logToNetworkTables = true;
|
public static final boolean kLogToNetworkTables = true;
|
||||||
|
|
||||||
|
public static final AprilTagFieldLayout kTagLayout = AprilTagFieldLayout.loadField(
|
||||||
|
AprilTagFields.kDefaultField
|
||||||
|
);
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -0,0 +1,10 @@
|
|||||||
|
package frc.robot.constants;
|
||||||
|
|
||||||
|
public class OIConstants {
|
||||||
|
public static final int kDriverControllerPort = 0;
|
||||||
|
public static final int kOperatorControllerPort = 1;
|
||||||
|
|
||||||
|
public static final double kDriveDeadband = .01;
|
||||||
|
|
||||||
|
public static final double kJoystickExponential = 3;
|
||||||
|
}
|
||||||
|
|||||||
@@ -17,10 +17,9 @@ public interface IAprilTagProvider {
|
|||||||
* A method to get the distance from <i>the camera</i> to the AprilTag specified
|
* A method to get the distance from <i>the camera</i> to the AprilTag specified
|
||||||
*
|
*
|
||||||
* @param id The ID of the AprilTag to give a distance to
|
* @param id The ID of the AprilTag to give a distance to
|
||||||
* @param targetHeightMeters The height of the AprilTag off the ground, in meters
|
|
||||||
* @return The distance, in meters, to the target, or OptionalDouble.empty() if the tag is not present in the camera's view
|
* @return The distance, in meters, to the target, or OptionalDouble.empty() if the tag is not present in the camera's view
|
||||||
*/
|
*/
|
||||||
public OptionalDouble getTagDistanceFromCameraByID(int id, double targetHeightMeters);
|
public OptionalDouble getTagDistanceFromCameraByID(int id);
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* A method to get the pitch from the center of the image of a particular AprilTag
|
* A method to get the pitch from the center of the image of a particular AprilTag
|
||||||
|
|||||||
@@ -13,10 +13,9 @@ import org.photonvision.PhotonUtils;
|
|||||||
import org.photonvision.targeting.PhotonPipelineResult;
|
import org.photonvision.targeting.PhotonPipelineResult;
|
||||||
import org.photonvision.targeting.PhotonTrackedTarget;
|
import org.photonvision.targeting.PhotonTrackedTarget;
|
||||||
|
|
||||||
import edu.wpi.first.apriltag.AprilTagFieldLayout;
|
|
||||||
import edu.wpi.first.apriltag.AprilTagFields;
|
|
||||||
import edu.wpi.first.math.geometry.Transform3d;
|
import edu.wpi.first.math.geometry.Transform3d;
|
||||||
import edu.wpi.first.math.util.Units;
|
import edu.wpi.first.math.util.Units;
|
||||||
|
import frc.robot.constants.CompetitionConstants;
|
||||||
import frc.robot.interfaces.IAprilTagProvider;
|
import frc.robot.interfaces.IAprilTagProvider;
|
||||||
import frc.robot.interfaces.IVisualPoseProvider;
|
import frc.robot.interfaces.IVisualPoseProvider;
|
||||||
|
|
||||||
@@ -35,9 +34,7 @@ public class PhotonVision implements IAprilTagProvider,IVisualPoseProvider {
|
|||||||
camera = new PhotonCamera(cameraName);
|
camera = new PhotonCamera(cameraName);
|
||||||
|
|
||||||
photonPoseEstimator = new PhotonPoseEstimator(
|
photonPoseEstimator = new PhotonPoseEstimator(
|
||||||
AprilTagFieldLayout.loadFromResource(
|
CompetitionConstants.kTagLayout,
|
||||||
AprilTagFields.kDefaultField.m_resourceFile
|
|
||||||
),
|
|
||||||
PoseStrategy.MULTI_TAG_PNP_ON_COPROCESSOR,
|
PoseStrategy.MULTI_TAG_PNP_ON_COPROCESSOR,
|
||||||
robotToCam
|
robotToCam
|
||||||
);
|
);
|
||||||
@@ -78,7 +75,7 @@ public class PhotonVision implements IAprilTagProvider,IVisualPoseProvider {
|
|||||||
}
|
}
|
||||||
|
|
||||||
@Override
|
@Override
|
||||||
public OptionalDouble getTagDistanceFromCameraByID(int id, double targetHeightMeters) {
|
public OptionalDouble getTagDistanceFromCameraByID(int id) {
|
||||||
if (latestResult == null) {
|
if (latestResult == null) {
|
||||||
return OptionalDouble.empty();
|
return OptionalDouble.empty();
|
||||||
}
|
}
|
||||||
@@ -88,7 +85,7 @@ public class PhotonVision implements IAprilTagProvider,IVisualPoseProvider {
|
|||||||
}
|
}
|
||||||
|
|
||||||
Optional<PhotonTrackedTarget> desiredTarget = getTargetFromList(latestResult.getTargets(), id);
|
Optional<PhotonTrackedTarget> desiredTarget = getTargetFromList(latestResult.getTargets(), id);
|
||||||
|
|
||||||
if (desiredTarget.isEmpty()) {
|
if (desiredTarget.isEmpty()) {
|
||||||
return OptionalDouble.empty();
|
return OptionalDouble.empty();
|
||||||
}
|
}
|
||||||
@@ -96,7 +93,7 @@ public class PhotonVision implements IAprilTagProvider,IVisualPoseProvider {
|
|||||||
return OptionalDouble.of(
|
return OptionalDouble.of(
|
||||||
PhotonUtils.calculateDistanceToTargetMeters(
|
PhotonUtils.calculateDistanceToTargetMeters(
|
||||||
cameraHeightMeters,
|
cameraHeightMeters,
|
||||||
targetHeightMeters,
|
CompetitionConstants.kTagLayout.getTagPose(id).get().getZ(),
|
||||||
cameraPitchRadians,
|
cameraPitchRadians,
|
||||||
Units.degreesToRadians(desiredTarget.get().getPitch()))
|
Units.degreesToRadians(desiredTarget.get().getPitch()))
|
||||||
);
|
);
|
||||||
|
|||||||
Reference in New Issue
Block a user