This commit is contained in:
EdwardFaucher
2025-03-06 15:47:09 -05:00
15 changed files with 147 additions and 332 deletions

View File

@@ -5,27 +5,21 @@
package frc.robot;
import static edu.wpi.first.units.Units.*;
import java.util.Map;
import com.ctre.phoenix6.swerve.SwerveModule.DriveRequestType;
import com.ctre.phoenix6.hardware.Pigeon2;
import com.ctre.phoenix6.swerve.SwerveRequest;
import com.pathplanner.lib.auto.AutoBuilder;
import com.pathplanner.lib.auto.NamedCommands;
import com.pathplanner.lib.commands.PathPlannerAuto;
import com.pathplanner.lib.util.FlippingUtil;
import edu.wpi.first.cameraserver.CameraServer;
import edu.wpi.first.math.MathUtil;
import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.networktables.GenericEntry;
import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.DriverStation.Alliance;
import edu.wpi.first.wpilibj.shuffleboard.BuiltInLayouts;
import edu.wpi.first.wpilibj.shuffleboard.BuiltInWidgets;
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab;
import edu.wpi.first.wpilibj.smartdashboard.SendableChooser;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardLayout;
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.ParallelCommandGroup;
import edu.wpi.first.wpilibj2.command.RunCommand;
import edu.wpi.first.wpilibj2.command.SequentialCommandGroup;
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
@@ -47,9 +41,6 @@ import frc.robot.commands.Pince.CorailAspir;
import frc.robot.commands.Pince.CoralAlgueInspire;
import frc.robot.commands.Pince.CoralExpire;
import frc.robot.commands.Pince.PinceManuel;
import frc.robot.commands.grimpeur.GrimperHaut;
import frc.robot.commands.grimpeur.GrimpeurBas;
import frc.robot.commands.grimpeur.GrimpeurManuelhaut;
import frc.robot.commands.requin.BalayeuseAlgue;
import frc.robot.commands.requin.BalayeuseCoral;
import frc.robot.commands.requin.BalayeuseHaut;
@@ -58,7 +49,6 @@ import frc.robot.commands.requin.L1Requin;
import frc.robot.subsystems.Bougie;
import frc.robot.subsystems.CommandSwerveDrivetrain;
import frc.robot.subsystems.Elevateur;
import frc.robot.subsystems.Grimpeur;
import frc.robot.subsystems.Limelight3;
import frc.robot.subsystems.Limelight3G;
import frc.robot.subsystems.Pince;
@@ -69,6 +59,12 @@ import frc.robot.commands.Elevateur.balonL2;
import frc.robot.commands.Elevateur.balonL3;
public class RobotContainer {
ShuffleboardLayout layoutauto = Shuffleboard.getTab("teb").getLayout("auto", BuiltInLayouts.kList)
.withSize(2, 2).withProperties(Map.of("Label position", "LEFT"));
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();
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
@@ -83,7 +79,6 @@ public class RobotContainer {
private final CommandXboxController manette2 = new CommandXboxController(1);
private final Pigeon2 gyro = new Pigeon2(13); // ID du Pigeon 2
public final CommandSwerveDrivetrain drivetrain = TunerConstants.createDrivetrain();
private final SendableChooser<Command> autoChooser;
public double getAngle() {
return gyro.getYaw().getValueAsDouble(); // Retourne l'angle actuel du robot
}
@@ -96,22 +91,11 @@ public class RobotContainer {
Limelight3G limelight3g = new Limelight3G();
Limelight3 limelight3 = new Limelight3();
Pose2d pose = new Pose2d();
Grimpeur Grimpeur = new Grimpeur();
Requin requin = new Requin();
CorailAspir corailAspir = new CorailAspir(pince, bougie);
public RobotContainer() {
CameraServer.startAutomaticCapture();
configureBindings();
NamedCommands.registerCommand("AprilTag", new AprilTag3G(limelight3g, drivetrain, null, null));
NamedCommands.registerCommand("Station",new StationPince(pince, elevateur,bougie));
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));
NamedCommands.registerCommand("baleeuse",new L1Requin(requin, bougie));
NamedCommands.registerCommand("baleeuse sort", new ExpireCorail(requin, bougie));
autoChooser = AutoBuilder.buildAutoChooser("New Auto");
SmartDashboard.putData("Auto Mode", autoChooser);
}
private void configureBindings() {
@@ -156,11 +140,6 @@ public class RobotContainer {
//limelight
manette2.a().whileTrue(new Forme3(limelight3,drivetrain,manette1::getLeftX,manette1::getLeftY));
manette2.b().whileTrue(new AprilTag3(limelight3, drivetrain, manette1::getLeftX, manette1::getLeftY));
//grimpeur
manette2.povDown().whileTrue(new GrimpeurManuelhaut(Grimpeur, bougie));
manette2.povLeft().whileTrue(new GrimperHaut(Grimpeur, bougie));
manette2.povRight().whileTrue(new GrimpeurBas(Grimpeur));
//Pince manuel
pince.setDefaultCommand(new RunCommand(()->{
@@ -177,14 +156,35 @@ public class RobotContainer {
}
public Command getAutonomousCommand() {
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));
return new SequentialCommandGroup(
drivetrain.applyRequest(()->
drive.withVelocityX(-0.1*MaxSpeed)
.withVelocityY(0)
.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),
drivetrain.applyRequest(()->
drive.withVelocityX(-0.1*MaxSpeed)
.withVelocityY(0)
.withRotationalRate(0)).unless(()->!sortirAngle.getBoolean(true)).withTimeout(3),
drivetrain.applyRequest(()->
drive.withVelocityX(0)
.withVelocityY(0)
.withRotationalRate(0)).withTimeout(0.1),
new L4(elevateur, pince).unless(()->!L4.getBoolean(true)).withTimeout(4),
drivetrain.applyRequest(()->
drive.withVelocityX(0.1*MaxSpeed)
.withVelocityY(0)
.withRotationalRate(0)).unless(()->!L4.getBoolean(true)).withTimeout(0.25),
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),
new L1Requin(requin, bougie).unless(()-> !L1.getBoolean(true)).withTimeout(2),
new ExpireCorail(requin, bougie).unless(()->!L1.getBoolean(true)).withTimeout(2),
new RainBow(bougie));
}
}