diff --git a/src/main/java/com/stuypulse/robot/RobotContainer.java b/src/main/java/com/stuypulse/robot/RobotContainer.java index 0e85c723..67c36bb9 100644 --- a/src/main/java/com/stuypulse/robot/RobotContainer.java +++ b/src/main/java/com/stuypulse/robot/RobotContainer.java @@ -387,7 +387,7 @@ public void configureAutons() { ReroutableCBAED.registerBlue(autonChooser); ReroutableCBAED_RED.registerRed(autonChooser); - CBA.registerBlue(autonChooser); + CBA.registerDefaultBlue(autonChooser); CBA_RED.registerRed(autonChooser); CBF.registerBlue(autonChooser) @@ -396,7 +396,7 @@ public void configureAutons() { ReroutableCBAEF.registerBlue(autonChooser) .registerRed(autonChooser); - GC.registerDefaultBlue(autonChooser); + GC.registerBlue(autonChooser); GC_RED.registerRed(autonChooser); SmartDashboard.putData("Autonomous", autonChooser); diff --git a/src/main/java/com/stuypulse/robot/commands/auton/HGF/ThreePieceGC.java b/src/main/java/com/stuypulse/robot/commands/auton/HGF/ThreePieceGC.java index 7055c130..587e772e 100644 --- a/src/main/java/com/stuypulse/robot/commands/auton/HGF/ThreePieceGC.java +++ b/src/main/java/com/stuypulse/robot/commands/auton/HGF/ThreePieceGC.java @@ -22,15 +22,16 @@ public ThreePieceGC(PathPlannerPath... paths) { .andThen(new ShooterPodiumShot()), SwerveDriveToPose.speakerRelative(-55) - .withTolerance(0.1, 0.1, 2) + .withTolerance(0.05, 0.05, 2) ), new ShooterWaitForTarget() .withTimeout(0.25), - ConveyorShootRoutine.untilNoteShot(0.75), + ConveyorShootRoutine.untilNoteShot(1.75), new FollowPathAndIntake(paths[0]), - new FollowPathAlignAndShoot(paths[1], SwerveDriveToPose.speakerRelative(-45)), + new FollowPathAlignAndShoot(paths[1], SwerveDriveToPose.speakerRelative(-45) + .withTolerance(0.05, 0.05, 5)), new FollowPathAndIntake(paths[2]), new SwerveDriveToShoot()