Reefscape-2025/src/main/java/frc/robot/RobotContainer.java

190 lines
9.3 KiB
Java
Raw Normal View History

2025-01-27 18:21:18 -05:00
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.
package frc.robot;
2025-01-30 19:18:56 -05:00
import static edu.wpi.first.units.Units.*;
2025-03-04 12:23:57 -05:00
import java.util.Map;
2025-01-30 19:18:56 -05:00
import com.ctre.phoenix6.swerve.SwerveModule.DriveRequestType;
2025-02-17 18:33:49 -05:00
import com.ctre.phoenix6.hardware.Pigeon2;
2025-01-30 19:18:56 -05:00
import com.ctre.phoenix6.swerve.SwerveRequest;
import edu.wpi.first.cameraserver.CameraServer;
2025-02-10 18:33:37 -05:00
import edu.wpi.first.math.MathUtil;
2025-02-17 18:33:49 -05:00
import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.networktables.GenericEntry;
2025-03-04 12:23:57 -05:00
import edu.wpi.first.wpilibj.shuffleboard.BuiltInLayouts;
import edu.wpi.first.wpilibj.shuffleboard.BuiltInWidgets;
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
2025-03-04 12:23:57 -05:00
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardLayout;
2025-01-27 18:21:18 -05:00
import edu.wpi.first.wpilibj2.command.Command;
2025-03-04 17:37:15 -05:00
import edu.wpi.first.wpilibj2.command.ParallelCommandGroup;
2025-02-25 16:38:35 -05:00
import edu.wpi.first.wpilibj2.command.RunCommand;
2025-02-17 18:33:49 -05:00
import edu.wpi.first.wpilibj2.command.SequentialCommandGroup;
2025-01-30 19:18:56 -05:00
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
import frc.robot.TunerConstants.TunerConstants;
2025-02-10 19:11:48 -05:00
import frc.robot.commands.RainBow;
2025-02-25 16:38:35 -05:00
import frc.robot.commands.reset;
2025-02-27 18:42:03 -05:00
import frc.robot.commands.Elevateur.Depart;
2025-02-27 18:33:08 -05:00
import frc.robot.commands.Elevateur.ElevateurManuel;
import frc.robot.commands.Elevateur.L2;
import frc.robot.commands.Elevateur.L3;
import frc.robot.commands.Elevateur.L4;
2025-02-27 19:33:57 -05:00
import frc.robot.commands.Elevateur.StationPince;
2025-02-27 19:31:53 -05:00
import frc.robot.commands.Limelight.AprilTag3;
import frc.robot.commands.Limelight.AprilTag3G;
import frc.robot.commands.Limelight.Forme3;
2025-02-27 18:02:26 -05:00
import frc.robot.commands.Pince.AlgueExpire;
import frc.robot.commands.Pince.Algue_inspire;
import frc.robot.commands.Pince.CorailAspir;
import frc.robot.commands.Pince.CoralAlgueInspire;
import frc.robot.commands.Pince.CoralExpire;
2025-02-27 18:33:08 -05:00
import frc.robot.commands.Pince.PinceManuel;
2025-03-01 13:53:13 -05:00
import frc.robot.commands.requin.BalayeuseAlgue;
import frc.robot.commands.requin.BalayeuseCoral;
2025-02-27 19:03:36 -05:00
import frc.robot.commands.requin.BalayeuseHaut;
2025-03-01 14:53:24 -05:00
import frc.robot.commands.requin.ExpireCorail;
2025-03-01 13:53:13 -05:00
import frc.robot.commands.requin.L1Requin;
2025-02-10 19:11:48 -05:00
import frc.robot.subsystems.Bougie;
2025-01-30 19:18:56 -05:00
import frc.robot.subsystems.CommandSwerveDrivetrain;
2025-02-25 16:38:35 -05:00
import frc.robot.subsystems.Elevateur;
2025-02-15 12:38:56 -05:00
import frc.robot.subsystems.Limelight3;
import frc.robot.subsystems.Limelight3G;
2025-02-25 16:38:35 -05:00
import frc.robot.subsystems.Pince;
2025-02-27 19:03:36 -05:00
import frc.robot.subsystems.Requin;
2025-03-01 14:53:24 -05:00
import frc.robot.commands.requin.exspire;
2025-03-03 09:22:48 -05:00
import frc.robot.commands.Pince.DepartPince;
import frc.robot.commands.Elevateur.balonL2;
import frc.robot.commands.Elevateur.balonL3;
2025-01-30 19:18:56 -05:00
2025-01-27 18:21:18 -05:00
public class RobotContainer {
2025-03-04 12:23:57 -05:00
ShuffleboardLayout layoutauto = Shuffleboard.getTab("teb").getLayout("auto", BuiltInLayouts.kList)
.withSize(2, 2).withProperties(Map.of("Label position", "LEFT"));
2025-03-04 17:37:01 -05:00
GenericEntry L1 = layoutauto.add("choix L1",false).withWidget(BuiltInWidgets.kToggleSwitch).getEntry();
GenericEntry sortirAngle = layoutauto.add("Cote?",false).withWidget(BuiltInWidgets.kToggleSwitch).getEntry();
GenericEntry Reculer = layoutauto.add("Reculer",false).withWidget(BuiltInWidgets.kToggleSwitch).getEntry();
GenericEntry L4 = layoutauto.add("L4",false).withWidget(BuiltInWidgets.kToggleSwitch).getEntry();
2025-02-25 18:12:27 -05:00
private double MaxSpeed = TunerConstants.kSpeedAt12Volts.in(MetersPerSecond); // kSpeedAt12Volts desired top speed
private double MaxAngularRate = RotationsPerSecond.of(0.75).in(RadiansPerSecond); // 3/4 of a rotation per second max angular velocity
2025-01-30 19:18:56 -05:00
2025-02-25 18:12:27 -05:00
/* Setting up bindings for necessary control of the swerve drive platform */
2025-03-03 09:22:48 -05:00
private final SwerveRequest.RobotCentric drive = new SwerveRequest.RobotCentric()
2025-02-25 18:12:27 -05:00
.withDeadband(MaxSpeed * 0.1).withRotationalDeadband(MaxAngularRate * 0.1) // Add a 10% deadband
2025-02-25 18:15:52 -05:00
.withDriveRequestType(DriveRequestType.OpenLoopVoltage
); // Use open-loop control for drive motors
2025-01-30 19:18:56 -05:00
2025-02-25 18:12:27 -05:00
private final Telemetry logger = new Telemetry(MaxSpeed);
private final CommandXboxController manette1 = new CommandXboxController(0);
private final CommandXboxController manette2 = new CommandXboxController(1);
2025-02-25 18:15:52 -05:00
private final Pigeon2 gyro = new Pigeon2(13); // ID du Pigeon 2
2025-02-25 18:12:27 -05:00
public final CommandSwerveDrivetrain drivetrain = TunerConstants.createDrivetrain();
2025-02-25 18:15:52 -05:00
public double getAngle() {
return gyro.getYaw().getValueAsDouble(); // Retourne l'angle actuel du robot
}
2025-02-25 18:12:27 -05:00
Elevateur elevateur = new Elevateur();
Pince pince = new Pince();
ElevateurManuel elevateurManuel = new ElevateurManuel(elevateur, manette2::getLeftY);
2025-02-26 17:26:31 -05:00
PinceManuel pinceManuel = new PinceManuel(pince,manette2::getRightY);
2025-02-25 18:12:27 -05:00
Bougie bougie = new Bougie();
Limelight3G limelight3g = new Limelight3G();
Limelight3 limelight3 = new Limelight3();
Pose2d pose = new Pose2d();
2025-02-27 19:03:36 -05:00
Requin requin = new Requin();
2025-03-01 13:53:13 -05:00
CorailAspir corailAspir = new CorailAspir(pince, bougie);
2025-02-25 18:12:27 -05:00
public RobotContainer() {
CameraServer.startAutomaticCapture();
configureBindings();
}
2025-02-25 18:12:27 -05:00
private void configureBindings() {
2025-02-27 19:03:36 -05:00
drivetrain.registerTelemetry(logger::telemeterize);
drivetrain.setDefaultCommand(
2025-03-03 09:22:48 -05:00
// Drivetrain will execute this command periodically
2025-02-25 18:12:27 -05:00
drivetrain.applyRequest(() ->
2025-03-03 09:22:48 -05:00
drive.withVelocityY(MathUtil.applyDeadband(-manette1.getLeftX()*-manette1.getLeftX()*-manette1.getLeftX()*MaxSpeed, 0.05)) // Drive forward with negative Y (forward)
.withVelocityX(MathUtil.applyDeadband(-manette1.getLeftY()*-manette1.getLeftY()*-manette1.getLeftY()*MaxSpeed, 0.05)) // Drive left with negative X (left)
.withRotationalRate(MathUtil.applyDeadband(-manette1.getRightX()*-manette1.getRightX()*-manette1.getRightX()*MaxAngularRate, 0.05)) // Drive counterclockwise with negative X (left)
2025-02-25 18:12:27 -05:00
)
);
2025-02-27 19:03:36 -05:00
/* Manette 1 */
2025-02-26 19:48:48 -05:00
//pince
2025-02-22 10:30:20 -05:00
manette1.rightTrigger().whileTrue(new CoralAlgueInspire(pince, bougie));
manette1.rightBumper().toggleOnTrue(new StationPince(pince, elevateur,bougie));
2025-03-03 09:22:48 -05:00
manette1.povLeft().whileTrue(new AlgueExpire(pince, bougie));
2025-02-27 20:23:26 -05:00
manette1.leftBumper().whileTrue(new AprilTag3G(limelight3g,drivetrain,manette1::getLeftX,manette1::getLeftY));
2025-03-01 14:53:24 -05:00
manette1.povRight().whileTrue(new CoralExpire(pince, bougie));
2025-03-03 09:22:48 -05:00
manette1.leftTrigger().whileTrue(new DepartPince(pince));
manette1.povDown().whileTrue(new Algue_inspire(pince,bougie));
manette1.leftStick().whileTrue(new CorailAspir(pince, bougie));
2025-03-03 09:22:48 -05:00
//elevateur
manette1.a().toggleOnTrue(new Depart(elevateur, pince));
manette1.b().toggleOnTrue(new L2(elevateur,pince));
manette1.x().toggleOnTrue(new L3(elevateur, pince));
manette1.y().toggleOnTrue(new L4(elevateur, pince));
manette1.povUp().toggleOnTrue(new balonL2(elevateur));
manette1.start().toggleOnTrue(new balonL3(elevateur));
2025-02-26 19:48:48 -05:00
2025-02-27 19:03:36 -05:00
/* Manette 2 */
2025-03-01 14:53:24 -05:00
//requin
manette2.rightBumper().whileTrue(new BalayeuseAlgue(requin,bougie));
manette2.leftBumper().whileTrue(new L1Requin(requin, bougie));
manette2.rightTrigger().whileTrue(new BalayeuseHaut(requin));
2025-03-01 13:53:13 -05:00
manette2.leftTrigger().whileTrue(new BalayeuseCoral(requin, bougie));
2025-03-01 14:53:24 -05:00
manette2.y().whileTrue(new exspire(requin, bougie));
manette2.x().whileTrue(new ExpireCorail(requin, bougie));
2025-03-03 09:22:48 -05:00
//limelight
manette2.a().whileTrue(new Forme3(limelight3,drivetrain,manette1::getLeftX,manette1::getLeftY));
manette2.b().whileTrue(new AprilTag3(limelight3, drivetrain, manette1::getLeftX, manette1::getLeftY));
2025-03-03 09:22:48 -05:00
2025-02-27 19:03:36 -05:00
//Pince manuel
pince.setDefaultCommand(new RunCommand(()->{
2025-03-01 15:27:32 -05:00
pince.pivote(MathUtil.applyDeadband((manette2.getRightY()*manette2.getRightY()*manette2.getRightY())/3, 0.05));
2025-02-27 19:03:36 -05:00
}, pince));
//Elevateur manuel
elevateur.setDefaultCommand(new RunCommand(()->{
elevateur.vitesse(MathUtil.applyDeadband(manette2.getLeftY()*manette2.getLeftY()*manette2.getLeftY(), 0.05));
2025-02-27 19:03:36 -05:00
}, elevateur));
//Reset encodeur
manette2.start().whileTrue(new reset(elevateur, pince, requin));
2025-01-29 19:01:51 -05:00
}
2025-02-26 18:02:25 -05:00
2025-02-18 18:47:13 -05:00
public Command getAutonomousCommand() {
2025-03-04 09:34:50 -05:00
return new SequentialCommandGroup(
2025-03-04 11:41:46 -05:00
drivetrain.applyRequest(()->
2025-03-04 13:07:57 -05:00
drive.withVelocityX(-0.1*MaxSpeed)
2025-03-04 11:41:46 -05:00
.withVelocityY(0)
2025-03-04 17:37:15 -05:00
.withRotationalRate(0)).unless(()->!Reculer.getBoolean(true)).withTimeout(3.5),
drivetrain.applyRequest(()->
drive.withVelocityX(0.1*MaxSpeed)
.withVelocityY(0)
.withRotationalRate(0)).unless(()->!L4.getBoolean(true)).withTimeout(3.5),
2025-03-04 12:52:13 -05:00
drivetrain.applyRequest(()->
2025-03-04 17:37:15 -05:00
drive.withVelocityX(-0.1*MaxSpeed)
2025-03-04 12:52:13 -05:00
.withVelocityY(0)
2025-03-04 17:37:15 -05:00
.withRotationalRate(0)).unless(()->!sortirAngle.getBoolean(true)).withTimeout(3),
2025-03-04 11:59:17 -05:00
drivetrain.applyRequest(()->
drive.withVelocityX(0)
.withVelocityY(0)
.withRotationalRate(0)).withTimeout(0.1),
2025-03-04 12:52:13 -05:00
new L4(elevateur, pince).unless(()->!L4.getBoolean(true)).withTimeout(4),
drivetrain.applyRequest(()->
2025-03-04 17:37:15 -05:00
drive.withVelocityX(0.1*MaxSpeed)
2025-03-04 12:52:13 -05:00
.withVelocityY(0)
2025-03-04 17:37:15 -05:00
.withRotationalRate(0)).unless(()->!L4.getBoolean(true)).withTimeout(0.25),
2025-03-04 12:52:13 -05:00
drivetrain.applyRequest(()->
drive.withVelocityX(0*MaxSpeed)
.withVelocityY(0)
.withRotationalRate(0)).unless(()->!L4.getBoolean(true)).withTimeout(2),
new CoralExpire(pince, bougie).unless(()->!L4.getBoolean(true)).withTimeout(2),
2025-03-04 12:23:57 -05:00
new L1Requin(requin, bougie).unless(()-> !L1.getBoolean(true)).withTimeout(2),
new ExpireCorail(requin, bougie).unless(()->!L1.getBoolean(true)).withTimeout(2),
2025-03-04 09:34:50 -05:00
new RainBow(bougie));
2025-02-25 18:12:27 -05:00
}
}