diff --git a/src/main/java/frc/robot/driver/DriverXbox.java b/src/main/java/frc/robot/driver/DriverXbox.java index e7ed896..41b492e 100644 --- a/src/main/java/frc/robot/driver/DriverXbox.java +++ b/src/main/java/frc/robot/driver/DriverXbox.java @@ -1,5 +1,9 @@ package frc.robot.driver; +import static frc.robot.vision.VisionConfig.AlignmentConfig.Cblue; +import static frc.robot.vision.VisionConfig.AlignmentConfig.Dblue; + +import edu.wpi.first.math.estimator.PoseEstimator; import edu.wpi.first.math.geometry.Translation2d; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.ConditionalCommand; @@ -16,6 +20,7 @@ import frc.robot.auton.AutonMaster; import frc.robot.commands.RobotCommands; import frc.robot.drivetrain.CommandSwerveDrivetrain; +import frc.robot.drivetrain.commands.DriveToPoseCommand; import frc.robot.elevator.ElevatorSubsystem; import frc.robot.elevator.commands.ElevatorCommands; import frc.robot.elevator.commands.SetElevatorState; @@ -26,6 +31,8 @@ import frc.robot.rushinator.commands.SetWristState; import frc.robot.rushinator.commands.ToggleWristState; import frc.robot.rushinator.commands.SetRollersVoltage; +import frc.robot.vision.PoseEstimatorSubsystem; +import frc.robot.vision.VisionConfig; import frc.robot.vision.commands.AutoAlign; import frc.robot.vision.commands.LineupCommand; @@ -102,8 +109,14 @@ public void setupTeleopButtons() { controller.leftTrigger().whileTrue(new SetAngleAlgaePivot(AlgaeSubsystem.State.kFloorIntake)); controller.leftTrigger().whileTrue(new SetElevatorState(ElevatorSubsystem.State.kAlgaeIntake)); - // controller.povLeft().whileTrue(new LineupCommand(true)); - // controller.povRight().whileTrue(new LineupCommand(false)); + //Align to Reef + controller.povLeft().whileTrue(new DriveToPoseCommand( + CommandSwerveDrivetrain.getInstance(), + () -> PoseEstimatorSubsystem.getInstance().getCurrentPose(), + Cblue)); + controller.povRight().whileTrue(new DriveToPoseCommand(CommandSwerveDrivetrain.getInstance(), + () -> PoseEstimatorSubsystem.getInstance().getCurrentPose(), + Dblue)); // // Toggle Wrist Left and Right diff --git a/src/main/java/frc/robot/drivetrain/commands/DriveToPoseCommand.java b/src/main/java/frc/robot/drivetrain/commands/DriveToPoseCommand.java index f61bdef..08d2f37 100644 --- a/src/main/java/frc/robot/drivetrain/commands/DriveToPoseCommand.java +++ b/src/main/java/frc/robot/drivetrain/commands/DriveToPoseCommand.java @@ -57,8 +57,11 @@ public class DriveToPoseCommand extends Command { * @param drivetrainSubsystem drivetrain subsystem * @param goalPose goal pose to drive to */ - public DriveToPoseCommand(CommandSwerveDrivetrain drivetrainSubsystem, Supplier poseProvider) { + public DriveToPoseCommand(CommandSwerveDrivetrain drivetrainSubsystem, Supplier poseProvider, Pose2d goalPose) { this(drivetrainSubsystem, poseProvider, DEFAULT_XY_CONSTRAINTS, DEFAULT_OMEGA_CONSTRAINTS); + thetaController.setGoal(goalPose.getRotation().getRadians()); + xController.setGoal(goalPose.getX()); + yController.setGoal(goalPose.getY()); } /**