enlever truc inutil + toggle pour auto

This commit is contained in:
Antoine PerreaultE 2025-03-04 12:23:57 -05:00
parent 41e7d89919
commit 5009a1c928
6 changed files with 10 additions and 286 deletions

View File

@ -5,33 +5,24 @@
package frc.robot; package frc.robot;
import static edu.wpi.first.units.Units.*; import static edu.wpi.first.units.Units.*;
import java.util.Map;
import com.ctre.phoenix6.swerve.SwerveModule.DriveRequestType; import com.ctre.phoenix6.swerve.SwerveModule.DriveRequestType;
import com.ctre.phoenix6.hardware.Pigeon2; import com.ctre.phoenix6.hardware.Pigeon2;
import com.ctre.phoenix6.swerve.SwerveRequest; 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.cameraserver.CameraServer;
import edu.wpi.first.math.MathUtil; import edu.wpi.first.math.MathUtil;
import edu.wpi.first.math.geometry.Pose2d; import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.networktables.GenericEntry; import edu.wpi.first.networktables.GenericEntry;
import edu.wpi.first.wpilibj.DriverStation; import edu.wpi.first.wpilibj.shuffleboard.BuiltInLayouts;
import edu.wpi.first.wpilibj.DriverStation.Alliance; import edu.wpi.first.wpilibj.shuffleboard.BuiltInWidgets;
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard; import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab; import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardLayout;
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.Command;
import edu.wpi.first.wpilibj2.command.Commands;
import edu.wpi.first.wpilibj2.command.InstantCommand;
import edu.wpi.first.wpilibj2.command.RunCommand; import edu.wpi.first.wpilibj2.command.RunCommand;
import edu.wpi.first.wpilibj2.command.SequentialCommandGroup; import edu.wpi.first.wpilibj2.command.SequentialCommandGroup;
import edu.wpi.first.wpilibj2.command.WaitUntilCommand;
import edu.wpi.first.wpilibj2.command.button.CommandXboxController; import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
import frc.robot.TunerConstants.TunerConstants; import frc.robot.TunerConstants.TunerConstants;
import frc.robot.commands.AvancerAuto;
import frc.robot.commands.RainBow; import frc.robot.commands.RainBow;
import frc.robot.commands.reset; import frc.robot.commands.reset;
import frc.robot.commands.Elevateur.Depart; import frc.robot.commands.Elevateur.Depart;
@ -49,9 +40,6 @@ import frc.robot.commands.Pince.CorailAspir;
import frc.robot.commands.Pince.CoralAlgueInspire; import frc.robot.commands.Pince.CoralAlgueInspire;
import frc.robot.commands.Pince.CoralExpire; import frc.robot.commands.Pince.CoralExpire;
import frc.robot.commands.Pince.PinceManuel; 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.BalayeuseAlgue;
import frc.robot.commands.requin.BalayeuseCoral; import frc.robot.commands.requin.BalayeuseCoral;
import frc.robot.commands.requin.BalayeuseHaut; import frc.robot.commands.requin.BalayeuseHaut;
@ -60,7 +48,6 @@ import frc.robot.commands.requin.L1Requin;
import frc.robot.subsystems.Bougie; import frc.robot.subsystems.Bougie;
import frc.robot.subsystems.CommandSwerveDrivetrain; import frc.robot.subsystems.CommandSwerveDrivetrain;
import frc.robot.subsystems.Elevateur; import frc.robot.subsystems.Elevateur;
import frc.robot.subsystems.Grimpeur;
import frc.robot.subsystems.Limelight3; import frc.robot.subsystems.Limelight3;
import frc.robot.subsystems.Limelight3G; import frc.robot.subsystems.Limelight3G;
import frc.robot.subsystems.Pince; import frc.robot.subsystems.Pince;
@ -71,6 +58,9 @@ import frc.robot.commands.Elevateur.balonL2;
import frc.robot.commands.Elevateur.balonL3; import frc.robot.commands.Elevateur.balonL3;
public class RobotContainer { 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",true).withWidget(BuiltInWidgets.kToggleSwitch).getEntry();
private double MaxSpeed = TunerConstants.kSpeedAt12Volts.in(MetersPerSecond); // kSpeedAt12Volts desired top speed 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 private double MaxAngularRate = RotationsPerSecond.of(0.75).in(RadiansPerSecond); // 3/4 of a rotation per second max angular velocity
@ -98,22 +88,11 @@ public class RobotContainer {
Limelight3G limelight3g = new Limelight3G(); Limelight3G limelight3g = new Limelight3G();
Limelight3 limelight3 = new Limelight3(); Limelight3 limelight3 = new Limelight3();
Pose2d pose = new Pose2d(); Pose2d pose = new Pose2d();
Grimpeur Grimpeur = new Grimpeur();
Requin requin = new Requin(); Requin requin = new Requin();
CorailAspir corailAspir = new CorailAspir(pince, bougie); CorailAspir corailAspir = new CorailAspir(pince, bougie);
public RobotContainer() { public RobotContainer() {
CameraServer.startAutomaticCapture(); CameraServer.startAutomaticCapture();
configureBindings(); 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() { private void configureBindings() {
@ -158,11 +137,6 @@ public class RobotContainer {
//limelight //limelight
manette2.a().whileTrue(new Forme3(limelight3,drivetrain,manette1::getLeftX,manette1::getLeftY)); manette2.a().whileTrue(new Forme3(limelight3,drivetrain,manette1::getLeftX,manette1::getLeftY));
manette2.b().whileTrue(new AprilTag3(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 manuel
pince.setDefaultCommand(new RunCommand(()->{ pince.setDefaultCommand(new RunCommand(()->{
@ -188,17 +162,8 @@ public class RobotContainer {
drive.withVelocityX(0) drive.withVelocityX(0)
.withVelocityY(0) .withVelocityY(0)
.withRotationalRate(0)).withTimeout(0.1), .withRotationalRate(0)).withTimeout(0.1),
new L1Requin(requin, bougie).withTimeout(2), new L1Requin(requin, bougie).unless(()-> !L1.getBoolean(true)).withTimeout(2),
new ExpireCorail(requin, bougie).withTimeout(2), new ExpireCorail(requin, bougie).unless(()->!L1.getBoolean(true)).withTimeout(2),
new RainBow(bougie)); new RainBow(bougie));
// 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));
} }
} }

View File

@ -1,56 +0,0 @@
// 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.commands.grimpeur;
import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.subsystems.Bougie;
import frc.robot.subsystems.Grimpeur;
/* You should consider using the more terse Command factories API instead https://docs.wpilib.org/en/stable/docs/software/commandbased/organizing-command-based.html#defining-commands */
public class GrimperHaut extends Command {
private Grimpeur grimpeur;
private Bougie bougie;
/** Creates a new Grimper. */
public GrimperHaut(Grimpeur grimpeur, Bougie bougie) {
this.grimpeur = grimpeur;
this.bougie = bougie;
addRequirements(grimpeur,bougie);
// Use addRequirements() here to declare subsystem dependencies.
}
// Called when the command is initially scheduled.
@Override
public void initialize() {}
// Called every time the scheduler runs while the command is scheduled.
@Override
public void execute() {
if(grimpeur.stop()==true){
grimpeur.grimpe(0);
grimpeur.reset();
bougie.RainBow();
}
else{
grimpeur.grimpe(0.5);
bougie.RainBowStop();
}
}
// Called once the command ends or is interrupted.
@Override
public void end(boolean interrupted) {
grimpeur.grimpe(0);
if(grimpeur.stop()){
bougie.RainBow();
}
}
// Returns true when the command should end.
@Override
public boolean isFinished() {
return grimpeur.stop()==true;
}
}

View File

@ -1,47 +0,0 @@
// 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.commands.grimpeur;
import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.subsystems.Grimpeur;
/* You should consider using the more terse Command factories API instead https://docs.wpilib.org/en/stable/docs/software/commandbased/organizing-command-based.html#defining-commands */
public class GrimpeurBas extends Command {
private Grimpeur grimpeur;
/** Creates a new GrimpeurBas. */
public GrimpeurBas(Grimpeur grimpeur) {
this.grimpeur = grimpeur;
addRequirements(grimpeur);
// Use addRequirements() here to declare subsystem dependencies.
}
// Called when the command is initially scheduled.
@Override
public void initialize() {}
// Called every time the scheduler runs while the command is scheduled.
@Override
public void execute() {
if(grimpeur.encodeur()>=-43.3 && grimpeur.encodeur()<=-42.5){
grimpeur.grimpe(0);
}
else if(grimpeur.encodeur()>=-43.3){
grimpeur.grimpe(-0.5);
}
else{grimpeur.grimpe(0.5);
}
}
// Called once the command ends or is interrupted.
@Override
public void end(boolean interrupted) {
grimpeur.grimpe(0);
}
// Returns true when the command should end.
@Override
public boolean isFinished() {
return false;
}
}

View File

@ -1,59 +0,0 @@
// 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.commands.grimpeur;
import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.subsystems.Bougie;
import frc.robot.subsystems.Grimpeur;
/* You should consider using the more terse Command factories API instead https://docs.wpilib.org/en/stable/docs/software/commandbased/organizing-command-based.html#defining-commands */
public class GrimpeurManuelhaut extends Command {
private Grimpeur grimpeur;
private Bougie bougie;
/** Creates a new GrimpeurManuel. */
public GrimpeurManuelhaut(Grimpeur grimpeur,Bougie bougie) {
this.grimpeur = grimpeur;
this.bougie = bougie;
addRequirements(grimpeur, bougie);
// Use addRequirements() here to declare subsystem dependencies.
}
// Called when the command is initially scheduled.
@Override
public void initialize() {}
// Called every time the scheduler runs while the command is scheduled.
@Override
public void execute() {
if(grimpeur.stop()){
bougie.RainBow();
grimpeur.grimpe(-0.5);
}
else{
bougie.RainBowStop();
grimpeur.grimpe(-0.5);
}
}
// Called once the command ends or is interrupted.
@Override
public void end(boolean interrupted) {
grimpeur.grimpe(0);
if(grimpeur.stop()){
bougie.RainBow();
}
else{bougie.RainBowStop();}
}
// Returns true when the command should end.
@Override
public boolean isFinished() {
return false;
}
}

View File

@ -1,39 +0,0 @@
// 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.commands.grimpeur;
import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.subsystems.Grimpeur;
/* You should consider using the more terse Command factories API instead https://docs.wpilib.org/en/stable/docs/software/commandbased/organizing-command-based.html#defining-commands */
public class ResetGrimpeur extends Command {
private Grimpeur grimpeur;
/** Creates a new ResetGrimpeur. */
public ResetGrimpeur(Grimpeur grimpeur) {
this.grimpeur = grimpeur;
addRequirements(grimpeur);
// Use addRequirements() here to declare subsystem dependencies.
}
// Called when the command is initially scheduled.
@Override
public void initialize() {}
// Called every time the scheduler runs while the command is scheduled.
@Override
public void execute() {
grimpeur.reset();
}
// Called once the command ends or is interrupted.
@Override
public void end(boolean interrupted) {}
// Returns true when the command should end.
@Override
public boolean isFinished() {
return false;
}
}

View File

@ -1,40 +0,0 @@
// 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.subsystems;
import com.revrobotics.spark.SparkMax;
import com.revrobotics.spark.SparkLowLevel.MotorType;
import edu.wpi.first.wpilibj.DigitalInput;
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
public class Grimpeur extends SubsystemBase {
/** Creates a new Grimpeur. */
ShuffleboardTab teb = Shuffleboard.getTab("teb");
public Grimpeur() {
teb.addBoolean("limit grimpeur", this::stop);
teb.addDouble("encodeur grimpeur", this::encodeur);
}
final SparkMax grimpeur = new SparkMax(21,MotorType.kBrushless);
final DigitalInput limit1 = new DigitalInput(2);
public void grimpe(double vitesse){
grimpeur.set(vitesse);
}
public boolean stop(){
return limit1.get();
}
public double encodeur(){
return grimpeur.getEncoder().getPosition();
}
public void reset(){
grimpeur.getEncoder().setPosition(135.11);
}
@Override
public void periodic() {
// This method will be called once per scheduler run
}
}