mirror of
https://github.com/Team4388/2025RidgeScape.git
synced 2026-06-09 00:38:02 -06:00
Make Vision Work
This commit is contained in:
@@ -10,6 +10,10 @@ package frc4388.robot;
|
||||
import static edu.wpi.first.units.Units.Inches;
|
||||
import static edu.wpi.first.units.Units.Rotations;
|
||||
|
||||
import java.util.ArrayList;
|
||||
import java.util.Arrays;
|
||||
import java.util.List;
|
||||
|
||||
import com.ctre.phoenix6.configs.CANcoderConfiguration;
|
||||
import com.ctre.phoenix6.configs.ClosedLoopRampsConfigs;
|
||||
import com.ctre.phoenix6.configs.CurrentLimitsConfigs;
|
||||
@@ -27,10 +31,12 @@ import com.ctre.phoenix6.swerve.SwerveModuleConstants.SteerFeedbackType;
|
||||
import com.ctre.phoenix6.swerve.SwerveModuleConstants.SteerMotorArrangement;
|
||||
import com.ctre.phoenix6.swerve.SwerveModuleConstantsFactory;
|
||||
|
||||
import edu.wpi.first.apriltag.AprilTag;
|
||||
import edu.wpi.first.apriltag.AprilTagFieldLayout;
|
||||
import edu.wpi.first.apriltag.AprilTagFields;
|
||||
import edu.wpi.first.math.Matrix;
|
||||
import edu.wpi.first.math.VecBuilder;
|
||||
import edu.wpi.first.math.geometry.Pose3d;
|
||||
import edu.wpi.first.math.geometry.Rotation2d;
|
||||
import edu.wpi.first.math.geometry.Rotation3d;
|
||||
import edu.wpi.first.math.geometry.Transform3d;
|
||||
@@ -279,9 +285,17 @@ public final class Constants {
|
||||
public static final class VisionConstants {
|
||||
public static final String CAMERA_NAME = "Camera_Module_v1";
|
||||
|
||||
public static final Transform3d CAMERA_POS = new Transform3d(new Translation3d(.3048, 0.2413, .2794), new Rotation3d(0,0.52333,Math.PI));
|
||||
public static final Transform3d CAMERA_POS = new Transform3d(new Translation3d(-.3048, 0.2413*0, .2794), new Rotation3d(0,0.52333,Math.PI));
|
||||
|
||||
public static final AprilTagFieldLayout kTagLayout = AprilTagFields.k2024Crescendo.loadAprilTagLayoutField();
|
||||
// public static final AprilTagFieldLayout kTagLayout = AprilTagFields.k2024Crescendo.loadAprilTagLayoutField();
|
||||
|
||||
|
||||
public static final AprilTagFieldLayout kTagLayout = new AprilTagFieldLayout(
|
||||
Arrays.asList(new AprilTag[] {
|
||||
new AprilTag(1, new Pose3d(
|
||||
new Translation3d(0.,0.,0.26035), new Rotation3d(0.,0.,0.)
|
||||
)),
|
||||
}), 100, 100);
|
||||
|
||||
// The standard deviations of our vision estimated poses, which affect correction rate
|
||||
// (Fake values. Experiment and determine estimation noise on an actual robot.)
|
||||
|
||||
Reference in New Issue
Block a user