12 Commits

Author SHA1 Message Date
172d3c92ab led 2025-04-07 12:06:05 -04:00
80e1f22ea3 plus structurer 2025-03-19 12:08:35 -04:00
792d780d89 mode auto unutile 2025-03-19 12:03:48 -04:00
398ea4ac82 elevateur va mieux 2025-03-12 17:23:59 -04:00
59a44ada9a mode auto L4 2025-03-07 10:04:39 -05:00
0878a276dd mode auto L4 2025-03-07 10:00:15 -05:00
bb9870732c Merge branch 'main' of https://git.demerso.net/PLS5618/Reefscape-2025 2025-03-07 09:06:40 -05:00
c4704210b9 derniere modif de compe 2025-03-07 09:06:10 -05:00
63313b3b7a Merge branch 'main' of https://git.demerso.net/PLS5618/Reefscape-2025 2025-03-06 15:47:09 -05:00
7de77db146 mode auto 2025-03-06 15:47:04 -05:00
c0e7985ab7 mode auto 2025-03-04 17:37:15 -05:00
004890fd7b mode auto 2025-03-04 17:37:01 -05:00
10 changed files with 87 additions and 79 deletions

View File

@ -19,6 +19,7 @@ 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.ShuffleboardLayout; import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardLayout;
import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.ParallelCommandGroup;
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.button.CommandXboxController; import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
@ -60,15 +61,16 @@ import frc.robot.commands.Elevateur.balonL3;
public class RobotContainer { public class RobotContainer {
ShuffleboardLayout layoutauto = Shuffleboard.getTab("teb").getLayout("auto", BuiltInLayouts.kList) ShuffleboardLayout layoutauto = Shuffleboard.getTab("teb").getLayout("auto", BuiltInLayouts.kList)
.withSize(2, 2).withProperties(Map.of("Label position", "LEFT")); .withSize(2, 2).withProperties(Map.of("Label position", "LEFT"));
GenericEntry L1 = layoutauto.add("choix L1",true).withWidget(BuiltInWidgets.kToggleSwitch).getEntry(); GenericEntry L1 = layoutauto.add("choix L1",false).withWidget(BuiltInWidgets.kToggleSwitch).getEntry();
GenericEntry sortirAngle = layoutauto.add("Cote?",true).withWidget(BuiltInWidgets.kToggleSwitch).getEntry(); GenericEntry sortirAngle = layoutauto.add("Cote?",false).withWidget(BuiltInWidgets.kToggleSwitch).getEntry();
GenericEntry Reculer = layoutauto.add("Reculer",true).withWidget(BuiltInWidgets.kToggleSwitch).getEntry(); GenericEntry ReculerB = layoutauto.add("ReculerB",false).withWidget(BuiltInWidgets.kToggleSwitch).getEntry();
GenericEntry L4 = layoutauto.add("L4",true).withWidget(BuiltInWidgets.kToggleSwitch).getEntry(); GenericEntry ReculerR = layoutauto.add("ReculerR",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 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
/* Setting up bindings for necessary control of the swerve drive platform */ /* Setting up bindings for necessary control of the swerve drive platform */
private final SwerveRequest.RobotCentric drive = new SwerveRequest.RobotCentric() private final SwerveRequest.FieldCentric drive = new SwerveRequest.FieldCentric()
.withDeadband(MaxSpeed * 0.1).withRotationalDeadband(MaxAngularRate * 0.1) // Add a 10% deadband .withDeadband(MaxSpeed * 0.1).withRotationalDeadband(MaxAngularRate * 0.1) // Add a 10% deadband
.withDriveRequestType(DriveRequestType.OpenLoopVoltage .withDriveRequestType(DriveRequestType.OpenLoopVoltage
); // Use open-loop control for drive motors ); // Use open-loop control for drive motors
@ -78,7 +80,6 @@ public class RobotContainer {
private final CommandXboxController manette2 = new CommandXboxController(1); private final CommandXboxController manette2 = new CommandXboxController(1);
private final Pigeon2 gyro = new Pigeon2(13); // ID du Pigeon 2 private final Pigeon2 gyro = new Pigeon2(13); // ID du Pigeon 2
public final CommandSwerveDrivetrain drivetrain = TunerConstants.createDrivetrain(); public final CommandSwerveDrivetrain drivetrain = TunerConstants.createDrivetrain();
//private final SendableChooser<Command> autoChooser;
public double getAngle() { public double getAngle() {
return gyro.getYaw().getValueAsDouble(); // Retourne l'angle actuel du robot return gyro.getYaw().getValueAsDouble(); // Retourne l'angle actuel du robot
} }
@ -157,32 +158,31 @@ public class RobotContainer {
public Command getAutonomousCommand() { public Command getAutonomousCommand() {
return new SequentialCommandGroup( return new SequentialCommandGroup(
drivetrain.applyRequest(()->
drive.withVelocityX(0.1*MaxSpeed)
.withVelocityY(0)
.withRotationalRate(0)).unless(()->!ReculerR.getBoolean(true)).withTimeout(3.5),
drivetrain.applyRequest(()-> drivetrain.applyRequest(()->
drive.withVelocityX(-0.1*MaxSpeed) drive.withVelocityX(-0.1*MaxSpeed)
.withVelocityY(0) .withVelocityY(0)
.withRotationalRate(0)).unless(()->!Reculer.getBoolean(true)).withTimeout(2), .withRotationalRate(0)).unless(()->!ReculerB.getBoolean(true)).withTimeout(3.5),
drivetrain.applyRequest(()-> drivetrain.applyRequest(()->
drive.withVelocityX(0.5*MaxSpeed) drive.withVelocityX(-0.1*MaxSpeed)
.withVelocityY(0) .withVelocityY(0)
.withRotationalRate(0)).unless(()->!L4.getBoolean(true)).withTimeout(2), .withRotationalRate(0)).unless(()->!L4.getBoolean(true)).withTimeout(2.35),
drivetrain.applyRequest(()-> drivetrain.applyRequest(()->
drive.withVelocityX(-0.5*MaxSpeed) drive.withVelocityX(0.1*MaxSpeed)
.withVelocityY(0) .withVelocityY(0)
.withRotationalRate(0)).unless(()->!sortirAngle.getBoolean(true)).withTimeout(2), .withRotationalRate(0)).unless(()->!sortirAngle.getBoolean(true)|| !ReculerR.getBoolean(true)).withTimeout(3),
drivetrain.applyRequest(()->
drive.withVelocityX(-0.1*MaxSpeed)
.withVelocityY(0)
.withRotationalRate(0)).unless(()->!sortirAngle.getBoolean(true)|| !ReculerB.getBoolean(true)).withTimeout(3),
drivetrain.applyRequest(()-> drivetrain.applyRequest(()->
drive.withVelocityX(0) drive.withVelocityX(0)
.withVelocityY(0) .withVelocityY(0)
.withRotationalRate(0)).withTimeout(0.1), .withRotationalRate(0)).withTimeout(0.1),
new L4(elevateur, pince).unless(()->!L4.getBoolean(true)).withTimeout(4), new L4(elevateur, pince).unless(()->!L4.getBoolean(true)).withTimeout(4),
drivetrain.applyRequest(()->
drive.withVelocityX(0.2*MaxSpeed)
.withVelocityY(0)
.withRotationalRate(0)).unless(()->!L4.getBoolean(true)).withTimeout(0.5),
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 L1Requin(requin, bougie).unless(()-> !L1.getBoolean(true)).withTimeout(2),
new ExpireCorail(requin, bougie).unless(()->!L1.getBoolean(true)).withTimeout(2), new ExpireCorail(requin, bougie).unless(()->!L1.getBoolean(true)).withTimeout(2),
new RainBow(bougie)); new RainBow(bougie));

View File

@ -78,7 +78,7 @@ public class TunerConstants {
// Theoretical free speed (m/s) at 12 V applied output; // Theoretical free speed (m/s) at 12 V applied output;
// This needs to be tuned to your individual robot // This needs to be tuned to your individual robot
public static final LinearVelocity kSpeedAt12Volts = MetersPerSecond.of(5.21); public static final LinearVelocity kSpeedAt12Volts = MetersPerSecond.of(6);
// Every 1 rotation of the azimuth results in kCoupleRatio drive motor turns; // Every 1 rotation of the azimuth results in kCoupleRatio drive motor turns;
// This may need to be tuned to your individual robot // This may need to be tuned to your individual robot

View File

@ -26,10 +26,10 @@ public class L2 extends Command {
// Called every time the scheduler runs while the command is scheduled. // Called every time the scheduler runs while the command is scheduled.
@Override @Override
public void execute() { public void execute() {
if(pince.encodeurpivot()>=14 && pince.encodeurpivot()<=15){ if(pince.encodeurpivot()>=15 && pince.encodeurpivot()<=16.5){
pince.pivote(0); pince.pivote(0);
} }
else if(pince.encodeurpivot()>=14){ else if(pince.encodeurpivot()>=15){
pince.pivote(-0.2); pince.pivote(-0.2);
} }
else{ else{

View File

@ -38,10 +38,10 @@ public class StationPince extends Command {
if(pince.emperagecoral() >= 18){ if(pince.emperagecoral() >= 18){
pince.x = true; pince.x = true;
} }
if(elevateur.position()<=-0.1 && elevateur.position()>= -0.2){ if(elevateur.position()<=-0.4 && elevateur.position()>= -0.5){
elevateur.vitesse(0); elevateur.vitesse(0);
} }
else if(elevateur.position()>=-0.1){ else if(elevateur.position()>=-0.4){
elevateur.vitesse(-0.7); elevateur.vitesse(-0.7);
} }
else{ else{

View File

@ -27,8 +27,8 @@ public class BalayeuseAlgue extends Command {
// Called every time the scheduler runs while the command is scheduled. // Called every time the scheduler runs while the command is scheduled.
@Override @Override
public void execute() { public void execute() {
double cibleMin = 700; double cibleMin = 550;
double cibleMax = 900; double cibleMax = 650;
if(requin.amp()>=78.2){ if(requin.amp()>=78.2){
requin.xRequin = true; requin.xRequin = true;

View File

@ -28,12 +28,12 @@ public class ExpireCorail extends Command {
@Override @Override
public void execute() { public void execute() {
if(requin.amp()> 60){ if(requin.amp()> 60){
requin.balaye(-0.4); requin.balaye(-0.1);
} }
else else
{ {
bougie.Rouge(); bougie.Rouge();
requin.balaye(-0.4); requin.balaye(-0.1);
} }
} }

View File

@ -27,10 +27,10 @@ public class L1Requin extends Command {
// Called every time the scheduler runs while the command is scheduled. // Called every time the scheduler runs while the command is scheduled.
@Override @Override
public void execute() { public void execute() {
if(requin.encodeur()<=530 && requin.encodeur()>=430){ if(requin.encodeur()<=485 && requin.encodeur()>=385){
requin.rotationer(0); requin.rotationer(0);
} }
else if(requin.encodeur()>=530){ else if(requin.encodeur()>=485){
requin.rotationer(-0.5); requin.rotationer(-0.5);
} }
else{ else{

View File

@ -31,11 +31,11 @@ public class exspire extends Command {
public void execute() { public void execute() {
if(requin.amp()> 15) if(requin.amp()> 15)
{ {
requin.balaye(0.4); requin.balaye(0.2);
} }
else{ else{
bougie.Rouge(); bougie.Rouge();
requin.balaye(0.4); requin.balaye(0.2);
} }
} }

View File

@ -6,14 +6,22 @@ package frc.robot.subsystems;
import com.ctre.phoenix.led.CANdle; import com.ctre.phoenix.led.CANdle;
import com.ctre.phoenix.led.CANdleConfiguration; import com.ctre.phoenix.led.CANdleConfiguration;
import com.ctre.phoenix.led.FireAnimation;
import com.ctre.phoenix.led.LarsonAnimation;
import com.ctre.phoenix.led.RainbowAnimation; import com.ctre.phoenix.led.RainbowAnimation;
import com.ctre.phoenix.led.TwinkleAnimation;
import com.ctre.phoenix.led.TwinkleOffAnimation;
import com.ctre.phoenix.led.TwinkleOffAnimation.TwinkleOffPercent;
import com.ctre.phoenix.led.LarsonAnimation.BounceMode;
import com.ctre.phoenix.led.TwinkleAnimation.TwinklePercent;
import edu.wpi.first.wpilibj2.command.SubsystemBase; import edu.wpi.first.wpilibj2.command.SubsystemBase;
public class Bougie extends SubsystemBase { public class Bougie extends SubsystemBase {
CANdle candle = new CANdle(23); CANdle candle = new CANdle(23);
CANdleConfiguration config = new CANdleConfiguration(); CANdleConfiguration config = new CANdleConfiguration();
RainbowAnimation rainbowAnim = new RainbowAnimation(1, 0.5, 68); LarsonAnimation rainbowAnim = new LarsonAnimation(256,0,0,0,0.1,68,BounceMode.Front,10,8);
//TwinkleOffAnimation rainbowAnim = new TwinkleOffAnimation(256, 0, 0,0,0.5,68,TwinkleOffPercent.Percent88,8);
/** Creates a new Bougie. */ /** Creates a new Bougie. */
public Bougie() { public Bougie() {
config.brightnessScalar = 0.5; config.brightnessScalar = 0.5;

View File

@ -45,42 +45,42 @@ public class CommandSwerveDrivetrain extends TunerSwerveDrivetrain implements Su
private final SwerveRequest.SysIdSwerveSteerGains m_steerCharacterization = new SwerveRequest.SysIdSwerveSteerGains(); private final SwerveRequest.SysIdSwerveSteerGains m_steerCharacterization = new SwerveRequest.SysIdSwerveSteerGains();
private final SwerveRequest.SysIdSwerveRotation m_rotationCharacterization = new SwerveRequest.SysIdSwerveRotation(); private final SwerveRequest.SysIdSwerveRotation m_rotationCharacterization = new SwerveRequest.SysIdSwerveRotation();
private void configureAutoBuilder() { // private void configureAutoBuilder() {
try { // try {
var config = RobotConfig.fromGUISettings(); // var config = RobotConfig.fromGUISettings();
AutoBuilder.configure( // AutoBuilder.configure(
() -> getState().Pose, // Supplier of current robot pose // () -> getState().Pose, // Supplier of current robot pose
this::resetPose, // Consumer for seeding pose against auto // this::resetPose, // Consumer for seeding pose against auto
() -> getState().Speeds, // Supplier of current robot speeds // () -> getState().Speeds, // Supplier of current robot speeds
// Consumer of ChassisSpeeds and feedforwards to drive the robot // // Consumer of ChassisSpeeds and feedforwards to drive the robot
(speeds, feedforwards) -> setControl( // (speeds, feedforwards) -> setControl(
m_pathApplyRobotSpeeds.withSpeeds(speeds) // m_pathApplyRobotSpeeds.withSpeeds(speeds)
.withWheelForceFeedforwardsY(feedforwards.robotRelativeForcesXNewtons()) // .withWheelForceFeedforwardsY(feedforwards.robotRelativeForcesXNewtons())
.withWheelForceFeedforwardsX(feedforwards.robotRelativeForcesYNewtons()) // .withWheelForceFeedforwardsX(feedforwards.robotRelativeForcesYNewtons())
), // ),
new PPHolonomicDriveController( // new PPHolonomicDriveController(
// PID constants for translation // // PID constants for translation
new PIDConstants(63.167, 0, 0.54521), // new PIDConstants(63.167, 0, 0.54521),
// // // PID constants for rotation
// // new PIDConstants(7.9735, 0, 0.038499)
// // PID constants for rotation // // PID constants for rotation
// new PIDConstants(7.9735, 0, 0.038499) // new PIDConstants(43.502,0,2.7353)
// PID constants for rotation // ),
new PIDConstants(43.502,0,2.7353) // config,
), // // Assume the path needs to be flipped for Red vs Blue, this is normally the case
config, // () -> DriverStation.getAlliance().orElse(Alliance.Blue) == Alliance.Red,
// Assume the path needs to be flipped for Red vs Blue, this is normally the case // this // Subsystem for requirements
() -> DriverStation.getAlliance().orElse(Alliance.Blue) == Alliance.Red,
this // Subsystem for requirements
); // );
} catch (Exception ex) { // } catch (Exception ex) {
DriverStation.reportError("Failed to load PathPlanner config and configure AutoBuilder", ex.getStackTrace()); // DriverStation.reportError("Failed to load PathPlanner config and configure AutoBuilder", ex.getStackTrace());
} // }
PPHolonomicDriveController.overrideRotationFeedback(()->{ // PPHolonomicDriveController.overrideRotationFeedback(()->{
return 0; // return 0;
}); // });
} // }
/** /**
* Constructs a CTRE SwerveDrivetrain using the specified constants. * Constructs a CTRE SwerveDrivetrain using the specified constants.
@ -100,7 +100,7 @@ public class CommandSwerveDrivetrain extends TunerSwerveDrivetrain implements Su
if (Utils.isSimulation()) { if (Utils.isSimulation()) {
startSimThread(); startSimThread();
} }
configureAutoBuilder(); //configureAutoBuilder();
} }
/** /**
@ -125,7 +125,7 @@ public class CommandSwerveDrivetrain extends TunerSwerveDrivetrain implements Su
if (Utils.isSimulation()) { if (Utils.isSimulation()) {
startSimThread(); startSimThread();
} }
configureAutoBuilder(); // configureAutoBuilder();
} }
/** /**
@ -158,7 +158,7 @@ public class CommandSwerveDrivetrain extends TunerSwerveDrivetrain implements Su
if (Utils.isSimulation()) { if (Utils.isSimulation()) {
startSimThread(); startSimThread();
} }
configureAutoBuilder(); //configureAutoBuilder();
} }