diff --git a/src/main/java/frc/robot/config/CompConfig.java b/src/main/java/frc/robot/config/CompConfig.java index b9945ba..99068c7 100644 --- a/src/main/java/frc/robot/config/CompConfig.java +++ b/src/main/java/frc/robot/config/CompConfig.java @@ -98,7 +98,12 @@ class CompConfig { speakerDistanceToAngle.put(123.0, 321.0); }, 0.0, - 30.0)); // NOT TUNED + 30.0), + new VisionConfig( + 4, + 0.4, + 0.4)); + // NOT TUNED private CompConfig() {} } diff --git a/src/main/java/frc/robot/config/RobotConfig.java b/src/main/java/frc/robot/config/RobotConfig.java index 03f0aa0..72d4800 100644 --- a/src/main/java/frc/robot/config/RobotConfig.java +++ b/src/main/java/frc/robot/config/RobotConfig.java @@ -12,7 +12,8 @@ public record RobotConfig( QueuerConfig queuer, ShooterConfig shooter, IntakeConfig intake, - ArmConfig arm) { + ArmConfig arm, + VisionConfig vision) { public record SwerveConfig( PhoenixPIDController snapController, boolean invertRotation, @@ -50,6 +51,11 @@ public record ArmConfig( Consumer speakerDistanceToAngle, double minAngle, double maxAngle) {} + public record VisionConfig( + int translationHistoryArraySize, + double xyStdDev, + double thetaStdDev, + Consumer tyToNoteDistance) {} // TODO: Change this to false during events public static final boolean IS_DEVELOPMENT = true; diff --git a/src/main/java/frc/robot/localization/LocalizationState.java b/src/main/java/frc/robot/localization/LocalizationState.java new file mode 100644 index 0000000..de281e7 --- /dev/null +++ b/src/main/java/frc/robot/localization/LocalizationState.java @@ -0,0 +1,5 @@ +package frc.robot.localization; + +public enum LocalizationState { + DEFAULT_STATE; +} diff --git a/src/main/java/frc/robot/localization/LocalizationSubsystem.java b/src/main/java/frc/robot/localization/LocalizationSubsystem.java new file mode 100644 index 0000000..d8316a6 --- /dev/null +++ b/src/main/java/frc/robot/localization/LocalizationSubsystem.java @@ -0,0 +1,60 @@ +package frc.robot.localization; + +import edu.wpi.first.math.VecBuilder; +import edu.wpi.first.math.estimator.SwerveDrivePoseEstimator; +import edu.wpi.first.math.geometry.Pose2d; +import edu.wpi.first.math.geometry.Rotation2d; +import edu.wpi.first.math.kinematics.SwerveModulePosition; +import frc.robot.config.RobotConfig; +import frc.robot.imu.ImuSubsystem; +import frc.robot.util.scheduling.SubsystemPriority; +import frc.robot.util.state_machines.StateMachine; +import frc.robot.vision.VisionSubsystem; +import frc.robot.vision.LimelightHelpers.PoseEstimate; + +public class LocalizationSubsystem extends StateMachine{ + private final ImuSubsystem imu; + private final VisionSubsystem vision; + private final SwerveDrivePoseEstimator poseEstimator; + private PoseEstimate estimatepose; + private double lastAddedVisionTimestamp = 0; + + + + public LocalizationSubsystem(ImuSubsystem imu, VisionSubsystem vision) { + super(SubsystemPriority.LOCALIZATION,LocalizationState.DEFAULT_STATE); + this.imu = imu; + this.vision = vision; + poseEstimator = + new SwerveDrivePoseEstimator( + null, + imu.getRobotHeading(), + null, + new Pose2d()); + } + @Override + protected void collectInputs(){ + var maybeResults = vision.getVisionResult(); + if (maybeResults.isPresent()) { + var results = maybeResults.get(); + Pose2d visionPose = results.pose(); + + double visionTimestamp = results.timestamp(); + + if (visionTimestamp == lastAddedVisionTimestamp) { + // Don't add the same vision pose over and over + } else { + poseEstimator.addVisionMeasurement( + visionPose, + visionTimestamp, + VecBuilder.fill( + RobotConfig.get().vision().xyStdDev(), + RobotConfig.get().vision().xyStdDev(), + RobotConfig.get().vision().thetaStdDev())); + lastAddedVisionTimestamp = visionTimestamp; + } + + } + +} +} diff --git a/src/main/java/frc/robot/vision/VisionSubsystem.java b/src/main/java/frc/robot/vision/VisionSubsystem.java index 9058017..b2023b1 100644 --- a/src/main/java/frc/robot/vision/VisionSubsystem.java +++ b/src/main/java/frc/robot/vision/VisionSubsystem.java @@ -55,4 +55,5 @@ public Optional getVisionResult() { public void robotPeriodic() { super.robotPeriodic(); } + }