debug de jeudi

This commit is contained in:
samuel desharnais
2026-03-28 09:16:33 -04:00
parent 57fa3597e2
commit 79568a58b9
8 changed files with 33 additions and 95 deletions

View File

@@ -7,16 +7,18 @@ package frc.robot.commands.ModeAuto;
import com.ctre.phoenix6.swerve.SwerveModule.DriveRequestType;
import com.ctre.phoenix6.swerve.SwerveRequest;
import edu.wpi.first.wpilibj.Timer;
import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.DriverStation.Alliance;
import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.generated.TunerConstants;
import frc.robot.subsystems.CommandSwerveDrivetrain;
import frc.robot.subsystems.Limelight3G;
import static edu.wpi.first.units.Units.*;
import java.util.Optional;
/* 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 LimelighterAuto extends Command {
Timer timer;
Limelight3G limelight3g;
CommandSwerveDrivetrain drivetrain;
private double MaxSpeed = TunerConstants.kSpeedAt12Volts.in(MetersPerSecond);
@@ -25,6 +27,7 @@ public class LimelighterAuto extends Command {
double boty;
double angle;
double calcul;
Optional<Alliance> alliance = DriverStation.getAlliance();
private final SwerveRequest.FieldCentric drive = new SwerveRequest.FieldCentric()
.withDeadband(MaxSpeed * 0.1).withRotationalDeadband(MaxAngularRate * 0.1)
.withDriveRequestType(DriveRequestType.OpenLoopVoltage);
@@ -34,39 +37,37 @@ public class LimelighterAuto extends Command {
this.limelight3g = limelight3g;
this.drivetrain = drivetrain;
addRequirements(drivetrain, limelight3g);
timer = new Timer();
// Use addRequirements() here to declare subsystem dependencies.
}
// Called when the command is initially scheduled.
@Override
public void initialize() {
timer.reset();
}
public void initialize() {}
// Called every time the scheduler runs while the command is scheduled.
@Override
public void execute() {
double[] BotPose = new double[6];
System.out.println("e");
if (limelight3g.getV()) {
BotPose = limelight3g.getBotPoseBlue();
if(alliance.get() == Alliance.Blue){
BotPose = limelight3g.getBotPoseBlue();
}
else{
BotPose = limelight3g.getBotPoseRed();
}
botx = BotPose[1];
boty = BotPose[0];
angle = drivetrain.getPigeon2().getYaw().getValueAsDouble();
if(angle >180){
angle =- 360;
angle -= 360;
}
calcul = limelight3g.Calcule(botx, 4, boty, 4.6, angle) / 5;
drivetrain.setControl(
drive.withVelocityX(0).withVelocityY(0).withRotationalRate(calcul));
System.out.println(calcul);
if (calcul < 0.2 && calcul > -0.2) {
// timer.start();
// } else {
// timer.reset();
// }
// } else {
// timer.stop();
drivetrain.setControl(drive.withRotationalRate(0));
}
}
@@ -80,7 +81,6 @@ public class LimelighterAuto extends Command {
@Override
public void end(boolean interrupted) {
drivetrain.setControl(drive.withRotationalRate(0));
timer.stop();
}
// Returns true when the command should end.
@@ -89,3 +89,4 @@ public class LimelighterAuto extends Command {
return calcul < 0.1 && calcul > -0.1;
}
}