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

168 lines
7.6 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.*;
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 com.pathplanner.lib.auto.AutoBuilder;
import com.pathplanner.lib.auto.NamedCommands;
2025-02-17 19:15:53 -05:00
import com.pathplanner.lib.commands.PathPlannerAuto;
import com.pathplanner.lib.util.FlippingUtil;
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;
2025-02-17 19:15:53 -05:00
import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.DriverStation.Alliance;
2025-01-30 19:18:56 -05:00
import edu.wpi.first.wpilibj.smartdashboard.SendableChooser;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
2025-01-27 18:21:18 -05:00
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.Commands;
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-15 12:38:56 -05:00
import frc.robot.commands.AprilTag3;
import frc.robot.commands.AprilTag3G;
import frc.robot.commands.Forme3;
2025-02-10 19:11:48 -05:00
import frc.robot.commands.RainBow;
2025-02-06 17:50:24 -05:00
import frc.robot.commands.StationPince;
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 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-02-27 19:03:36 -05:00
import frc.robot.commands.requin.BalayeuseBas;
import frc.robot.commands.requin.BalayeuseHaut;
import frc.robot.commands.requin.exspire;
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-26 19:48:48 -05:00
import frc.robot.subsystems.Grimpeur;
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-01-30 19:18:56 -05:00
2025-01-27 18:21:18 -05:00
public class RobotContainer {
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 */
private final SwerveRequest.FieldCentric drive = new SwerveRequest.FieldCentric()
.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
private final SendableChooser<Command> autoChooser;
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-26 19:48:48 -05:00
Grimpeur Grimpeur = new Grimpeur();
2025-02-27 19:03:36 -05:00
Requin requin = new Requin();
2025-02-25 18:15:52 -05:00
2025-02-25 18:12:27 -05:00
public RobotContainer() {
2025-02-25 18:15:52 -05:00
autoChooser = AutoBuilder.buildAutoChooser("New Auto");
SmartDashboard.putData("Auto Mode", autoChooser);
configureBindings();
NamedCommands.registerCommand("AprilTag", new AprilTag3G(limelight3g, drivetrain, null, null));
2025-02-26 18:02:25 -05:00
NamedCommands.registerCommand("Station",new StationPince(pince, elevateur));
NamedCommands.registerCommand("L4", new L4(elevateur, pince));
NamedCommands.registerCommand("L3", new L3(elevateur, pince));
NamedCommands.registerCommand("CoralExpire",new CoralExpire(pince,bougie));
NamedCommands.registerCommand("CoraletAlgue", new CoralAlgueInspire(pince,bougie));
2025-02-25 18:15:52 -05:00
}
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(
// Drivetrain will execute this command periodically
drivetrain.applyRequest(() ->
drive.withVelocityX(MathUtil.applyDeadband(Math.pow(-manette1.getLeftX(), 2)*MaxSpeed, 0.1)) // Drive forward with negative Y (forward)
.withVelocityY(MathUtil.applyDeadband(Math.pow(-manette1.getLeftY(), 2)*MaxSpeed, 0.10000)) // Drive left with negative X (left)
.withRotationalRate(MathUtil.applyDeadband(Math.pow(-manette1.getRightX(), 2)*manette1.getRightX()*MaxAngularRate, 0.1)) // Drive counterclockwise with negative X (left)
2025-02-25 18:12:27 -05:00
)
);
2025-02-27 19:03:36 -05:00
2025-02-26 18:02:25 -05:00
2025-02-27 19:03:36 -05:00
/* Manette 1 */
2025-02-26 19:48:48 -05:00
// reset the field-centric heading on start press
2025-02-25 18:12:27 -05:00
manette1.start().onTrue(drivetrain.runOnce(() -> drivetrain.seedFieldCentric()));
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().whileTrue(new StationPince(pince, elevateur));
2025-02-26 18:11:11 -05:00
manette1.leftTrigger().whileTrue(new CoralExpire(pince, bougie));
2025-02-26 19:48:48 -05:00
2025-02-27 19:03:36 -05:00
//elevateur
manette1.a().whileTrue(new Depart(elevateur, pince));
manette1.b().whileTrue(new L2(elevateur,pince));
manette1.x().whileTrue(new L3(elevateur, pince));
manette1.y().whileTrue(new L4(elevateur, pince));
2025-02-26 19:48:48 -05:00
2025-02-27 19:03:36 -05:00
/* Manette 2 */
2025-02-26 19:48:48 -05:00
//pince
2025-02-24 18:15:32 -05:00
manette2.a().whileTrue(new CorailAspir(pince));
2025-02-26 18:11:11 -05:00
manette2.b().whileTrue(new Algue_inspire(pince));
2025-02-27 19:03:36 -05:00
manette2.y().whileTrue(new BalayeuseHaut(requin));
manette2.x().whileTrue(new BalayeuseBas(requin));
manette2.rightTrigger().whileTrue(new exspire(requin));
2025-02-26 19:48:48 -05:00
manette2.leftTrigger().whileTrue(new AlgueExpire(pince, bougie));
2025-02-27 19:03:36 -05:00
//Pince manuel
pince.setDefaultCommand(new RunCommand(()->{
pince.pivote(MathUtil.applyDeadband(manette2.getRightY(), 0.1));
}, pince));
//Elevateur manuel
elevateur.setDefaultCommand(new RunCommand(()->{
if(elevateur.limit2()){
elevateur.vitesse(0);
}
else{
elevateur.vitesse(MathUtil.applyDeadband(manette2.getLeftX(), 0.1));
}
}, elevateur));
2025-02-26 19:48:48 -05:00
//limelight
2025-02-26 18:11:11 -05:00
manette2.leftBumper().whileTrue(new AprilTag3(limelight3,drivetrain,manette1::getLeftX,manette1::getLeftY));
manette2.rightBumper().whileTrue(new Forme3(limelight3,drivetrain,manette1::getLeftX,manette1::getLeftY));
2025-02-27 19:03:36 -05:00
//Reset encodeur
manette2.start().whileTrue(new reset(elevateur, pince));
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-02-25 18:12:27 -05:00
return new SequentialCommandGroup(Commands.runOnce(()->{
boolean flip = DriverStation.getAlliance().orElse(Alliance.Blue) == Alliance.Red;
if(flip){
drivetrain.resetPose(FlippingUtil.flipFieldPose(((PathPlannerAuto)autoChooser.getSelected()).getStartingPose()));
}
else{
drivetrain.resetPose(((PathPlannerAuto)autoChooser.getSelected()).getStartingPose());
}
}),autoChooser.getSelected(), new RainBow(bougie));
}
}