This commit is contained in:
2026-03-17 19:02:03 -04:00
16 changed files with 354 additions and 49 deletions

View File

@@ -13,6 +13,8 @@ import org.littletonrobotics.junction.Logger;
import com.pathplanner.lib.auto.AutoBuilder;
import com.pathplanner.lib.auto.NamedCommands;
import com.pathplanner.lib.events.EventTrigger;
import com.pathplanner.lib.path.EventMarker;
import edu.wpi.first.math.MathUtil;
import edu.wpi.first.math.geometry.Pose2d;
@@ -24,6 +26,7 @@ import edu.wpi.first.wpilibj.Timer;
import edu.wpi.first.wpilibj.smartdashboard.SendableChooser;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.Commands;
import edu.wpi.first.wpilibj2.command.InstantCommand;
import edu.wpi.first.wpilibj2.command.PrintCommand;
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
@@ -79,7 +82,7 @@ public class RobotContainer {
resetOdometryToVisualPose = false;
vision.addPoseEstimateConsumer(drivetrain::consumeVisualPose);
//vision.addPoseEstimateConsumer(drivetrain::consumeVisualPose);
vision.addPoseEstimateConsumer((vp) -> {
Logger.recordOutput(
"Vision/" + vp.cameraName() + "/Pose",
@@ -349,7 +352,7 @@ public class RobotContainer {
NamedCommands.registerCommand(
"intake down",
intakePivot.manualSpeed(()->-0.75)
intakePivot.manualSpeed(()->0.75)
.withTimeout(1)
);
@@ -361,7 +364,33 @@ public class RobotContainer {
spindexer.spinToShooter()
.alongWith(shooter.maintainSpeed(ShooterSpeeds.kHubSpeed))
.alongWith(hood.trackToAngle(() -> Units.degreesToRadians(10)))
.withTimeout(3));
.withTimeout(3).andThen(spindexer.instantaneousStop()));
// NamedCommands.registerCommand("Intake Start", intakeRoller.runIn());
new EventTrigger("Intake Start")
.onTrue(intakeRoller.runIn());
NamedCommands.registerCommand("stop spindexer", spindexer.instantaneousStop());
NamedCommands.registerCommand("jimmy",
Commands.repeatingSequence(
intakePivot.manualSpeed(() -> -0.75).withTimeout(0.2)
.andThen(intakePivot.manualSpeed(() -> 0.75).withTimeout(0.2))
)
);
NamedCommands.registerCommand("shoot N jimmy",
Commands.parallel(
Commands.repeatingSequence(
intakePivot.manualSpeed(() -> -0.75).withTimeout(0.5),
intakePivot.manualSpeed(() -> 0.75).withTimeout(0.5)
),
spindexer.spinToShooter()
.alongWith(shooter.maintainSpeed(ShooterSpeeds.kHubSpeed),
hood.trackToAngle(() -> Units.degreesToRadians(10)))
).withTimeout(3).andThen(spindexer.instantaneousStop()));
}
public Command getAutonomousCommand() {