diff --git a/src/main/java/competition/subsystems/pose/PoseSubsystem.java b/src/main/java/competition/subsystems/pose/PoseSubsystem.java index bef1710b..73316894 100644 --- a/src/main/java/competition/subsystems/pose/PoseSubsystem.java +++ b/src/main/java/competition/subsystems/pose/PoseSubsystem.java @@ -51,8 +51,9 @@ public class PoseSubsystem extends BasePoseSubsystem { private final DriveSubsystem drive; private final AprilTagVisionSubsystemExtended aprilTagVisionSubsystem; private final BooleanProperty useVisionAssistedPose; - private final BooleanProperty useDeadwheelAssistedPose; - private final BooleanProperty continueUpdatingSwerveTelemetry; + private final BooleanProperty useDeadwheelsForNonVisionPose; + private final BooleanProperty useDeadwheelsForVisionPose; + private final BooleanProperty updateSecondaryPoseEstimatorWithVisionData; private final BooleanProperty reportCameraPoses; private final CoprocessorCommunicationSubsystem coprocessorComms; @@ -99,8 +100,9 @@ public PoseSubsystem(XGyroFactory gyroFactory, propManager.setPrefix(this); propManager.setDefaultLevel(Property.PropertyLevel.Important); useVisionAssistedPose = propManager.createPersistentProperty("UseVisionAssistedPose", true); - useDeadwheelAssistedPose = propManager.createPersistentProperty("useDeadwheelAssistedPose", false); - continueUpdatingSwerveTelemetry = propManager.createPersistentProperty("continueUpdatingSwerveTelemetry", true); + useDeadwheelsForVisionPose = propManager.createPersistentProperty("useDeadwheelsForVisionPose", false); + useDeadwheelsForNonVisionPose = propManager.createPersistentProperty("useDeadwheelsForNonVisionPose", false); + updateSecondaryPoseEstimatorWithVisionData = propManager.createPersistentProperty("updateSecondaryPoseEstimatorWithVision", true); reportCameraPoses = propManager.createPersistentProperty("ReportCameraPoses", false); } @@ -126,34 +128,43 @@ private SwerveDrivePoseEstimator initializeSwerveOdometry() { getSwerveModulePositions(), new Pose2d()); } + @SuppressWarnings("unchecked") private PoseEstimator getPrimaryPoseEstimator() { - return (PoseEstimator) (this.useDeadwheelAssistedPose.get() + return (PoseEstimator) (this.useDeadwheelsForVisionPose.get() ? this.fullDeadwheelOdometry : this.fullSwerveOdometry); } + @SuppressWarnings("unchecked") private PoseEstimator getPrimaryOdometryOnlyPoseEstimator() { - return (PoseEstimator) (this.useDeadwheelAssistedPose.get() + return (PoseEstimator) (this.useDeadwheelsForNonVisionPose.get() ? this.onlyWheelsGyroSwerveOdometry : this.onlyDeadwheelOdometry); } - private boolean shouldAlsoUpdateFullSwerve() { - return this.useDeadwheelAssistedPose.get() && this.continueUpdatingSwerveTelemetry.get(); + @SuppressWarnings("unchecked") + private PoseEstimator getSecondaryPoseEstimator() { + return (PoseEstimator) (!this.useDeadwheelsForVisionPose.get() + ? this.fullDeadwheelOdometry + : this.fullSwerveOdometry); + } + + @SuppressWarnings("unchecked") + private PoseEstimator getSecondaryOdometryOnlyPoseEstimator() { + return (PoseEstimator) (!this.useDeadwheelsForNonVisionPose.get() + ? this.onlyWheelsGyroSwerveOdometry + : this.onlyDeadwheelOdometry); } private void updateOdometryWithVision() { - // Also update full swerve if we should add swerve and it's not already being - // updated. this.aprilTagVisionSubsystem.getAllPoseObservations().forEach(observation -> { this.getPrimaryPoseEstimator().addVisionMeasurement( observation.visionRobotPoseMeters(), observation.timestampSeconds(), observation.visionMeasurementStdDevs()); - - if (this.shouldAlsoUpdateFullSwerve()) { - this.fullSwerveOdometry.addVisionMeasurement( + if (updateSecondaryPoseEstimatorWithVisionData.get()) { + this.getSecondaryPoseEstimator().addVisionMeasurement( observation.visionRobotPoseMeters(), observation.timestampSeconds(), observation.visionMeasurementStdDevs()); @@ -169,36 +180,34 @@ protected void updateOdometry() { BatchedPushRequests batchedPushRequests = new BatchedPushRequests(); // Update pose estimators - onlyWheelsGyroSwerveOdometry.update( - this.getCurrentHeadingGyroOnly(), - getSwerveModulePositions()); - aKitLog.record("WheelsOnlyEstimate", onlyWheelsGyroSwerveOdometry.getEstimatedPosition()); - // DeadWheel pose estimator deadWheelSubsystem.update(); - batchedPushRequests.putPose2d(xtablesPrefix + ".WheelsOnlyEstimate", - onlyWheelsGyroSwerveOdometry.getEstimatedPosition()); - if (this.useDeadwheelAssistedPose.get()) { - fullDeadwheelOdometry.update( - this.getCurrentHeadingGyroOnly(), - this.deadWheelSubsystem.getLeftAdjustedDistance().in(Meters), - this.deadWheelSubsystem.getRightAdjustedDistance().in(Meters), - this.deadWheelSubsystem.getFrontAdjustedDistance().in(Meters), - this.deadWheelSubsystem.getRearAdjustedDistance().in(Meters)); + this.onlyWheelsGyroSwerveOdometry.update( + this.getCurrentHeadingGyroOnly(), + getSwerveModulePositions()); - } - if (!this.useDeadwheelAssistedPose.get() || this.shouldAlsoUpdateFullSwerve()) { - this.fullSwerveOdometry.update( - this.getCurrentHeadingGyroOnly(), - getSwerveModulePositions()); - } + this.fullSwerveOdometry.update( + this.getCurrentHeadingGyroOnly(), + getSwerveModulePositions()); this.onlyDeadwheelOdometry.update( this.getCurrentHeading(), getDeadwheelPositions()); + this.fullDeadwheelOdometry.update( + this.getCurrentHeadingGyroOnly(), + getDeadwheelPositions()); + this.updateOdometryWithVision(); + + var wheelsOnlyPose = onlyWheelsGyroSwerveOdometry.getEstimatedPosition(); + aKitLog.record("WheelsOnlyEstimate", wheelsOnlyPose); + batchedPushRequests.putPose2d(xtablesPrefix + ".WheelsOnlyEstimate", + wheelsOnlyPose); + + aKitLog.record("SwerveVisionEnhancedPose", fullSwerveOdometry.getEstimatedPosition()); + aKitLog.record("DeadwheelOnlyEstimate", onlyDeadwheelOdometry.getEstimatedPosition()); aKitLog.record("FullVisionDeadwheelEstimate", fullDeadwheelOdometry.getEstimatedPosition()); @@ -209,10 +218,6 @@ protected void updateOdometry() { aKitLog.record("OdometryOnlyRobotPose", swerveOnlyPosition); batchedPushRequests.putPose2d(xtablesPrefix + ".OdometryOnlyRobotPose", swerveOnlyPosition); - Pose2d fullSwervePosiiton = new Pose2d( - fullSwerveOdometry.getEstimatedPosition().getTranslation(), - fullSwerveOdometry.getEstimatedPosition().getRotation()); - aKitLog.record("SwerveVisionEnhancedPose", fullSwervePosiiton); Pose2d visionEnhancedPosition = new Pose2d( this.getPrimaryPoseEstimator().getEstimatedPosition().getTranslation(),