This commit is contained in:
Antoine PerreaultE
2026-03-24 20:20:02 -04:00
parent 36a6bf2ab0
commit 083288d3fc
2 changed files with 46 additions and 3 deletions

View File

@@ -77,7 +77,7 @@ public class RobotContainer {
NamedCommands.registerCommand("GrimperMur", new GrimperMur(limeLight3,drivetrain)); NamedCommands.registerCommand("GrimperMur", new GrimperMur(limeLight3,drivetrain));
NamedCommands.registerCommand("GrimperReservoir", new GrimperReservoir(limeLight3G,drivetrain)); NamedCommands.registerCommand("GrimperReservoir", new GrimperReservoir(limeLight3G,drivetrain));
NamedCommands.registerCommand("Lancer", new LancerAuto(lanceur, limeLight3G)); NamedCommands.registerCommand("Lancer", new LancerAuto(lanceur, limeLight3G));
NamedCommands.registerCommand("RetourMilieuDroite", new RetourMilieuDroite()); NamedCommands.registerCommand("RetourMilieuDroite", new RetourMilieuDroite(drivetrain,limeLight3G));
NamedCommands.registerCommand("RetourMilieuGauche", new RetourMilieuGauche()); NamedCommands.registerCommand("RetourMilieuGauche", new RetourMilieuGauche());
NamedCommands.registerCommand("Limelighter", new Limelighter(limeLight3G,drivetrain)); NamedCommands.registerCommand("Limelighter", new Limelighter(limeLight3G,drivetrain));
NamedCommands.registerCommand("DescendreBalayeuse", new DescendreBalyeuse(balayeuse)); NamedCommands.registerCommand("DescendreBalayeuse", new DescendreBalyeuse(balayeuse));

View File

@@ -4,12 +4,42 @@
package frc.robot.commands.ModeAuto; package frc.robot.commands.ModeAuto;
import static edu.wpi.first.units.Units.*;
import java.util.Optional;
import com.ctre.phoenix6.hardware.Pigeon2;
import com.ctre.phoenix6.swerve.SwerveModule.DriveRequestType;
import com.ctre.phoenix6.swerve.SwerveRequest;
import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.DriverStation.Alliance;
import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.generated.TunerConstants;
import frc.robot.subsystems.CommandSwerveDrivetrain;
import frc.robot.subsystems.Limelight3G;
/* 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 */ /* 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 RetourMilieuDroite extends Command { public class RetourMilieuDroite extends Command {
CommandSwerveDrivetrain drivetrain;
Limelight3G limelight3g;
double botx;
double boty;
double x;
double y;
double angle;
private double MaxSpeed = TunerConstants.kSpeedAt12Volts.in(MetersPerSecond);
private double MaxAngularRate = RotationsPerSecond.of(0.75).in(RadiansPerSecond);
Pigeon2 pigeon2;
Optional<Alliance> alliance = DriverStation.getAlliance();
private final SwerveRequest.FieldCentric drive = new SwerveRequest.FieldCentric()
.withDeadband(MaxSpeed * 0.1).withRotationalDeadband(MaxAngularRate * 0.1)
.withDriveRequestType(DriveRequestType.OpenLoopVoltage);
/** Creates a new RetourMilieu. */ /** Creates a new RetourMilieu. */
public RetourMilieuDroite() { public RetourMilieuDroite(CommandSwerveDrivetrain drivetrain, Limelight3G limelight3g) {
this.drivetrain = drivetrain;
this.limelight3g = limelight3g;
addRequirements(drivetrain, limelight3g);
// Use addRequirements() here to declare subsystem dependencies. // Use addRequirements() here to declare subsystem dependencies.
} }
@@ -19,7 +49,20 @@ public class RetourMilieuDroite 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(alliance.get() == Alliance.Blue){
angle = 0;
}
else{
angle = 180;
}
if(pigeon2.getYaw().getValueAsDouble() >0 && pigeon2.getYaw().getValueAsDouble() <180){
drivetrain.setControl(drive.withRotationalRate(0.5));
}
else if(pigeon2.getYaw().getValueAsDouble() >180){
drivetrain.setControl(drive.withRotationalRate(-0.5));
}
}
// Called once the command ends or is interrupted. // Called once the command ends or is interrupted.
@Override @Override