limelight

This commit is contained in:
2026-03-30 05:04:22 +02:00
parent 5c626f33e3
commit f7e88619e9
3 changed files with 64 additions and 32 deletions

View File

@@ -50,21 +50,32 @@ public class Limelighter extends Command {
double[] BotPose = new double[6];
System.out.println("e");
if (limelight3g.getV()) {
if(!alliance.isPresent()){return;}
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;
calcul = limelight3g.Calcule(botx, 4, boty, 4.6, angle);
if(calcul < -5 && calcul > -180){
drivetrain.setControl(
drive.withRotationalRate(0.5*180/Math.PI));
}
calcul = limelight3g.Calcule(botx, 4, boty, 4.6, angle) / 10;
else if(calcul > 5 && calcul < 180){
drivetrain.setControl(
drive.withRotationalRate(-0.5*180/Math.PI));
}
else if(calcul >= 180){
drivetrain.setControl(
drive.withRotationalRate(-0.5*180/Math.PI));
}
else if(calcul <= -180){
drivetrain.setControl(
drive.withRotationalRate(0.5*180/Math.PI));
}
else{
drivetrain.setControl(
drive.withRotationalRate(0));
}
drivetrain.setControl(
drive.withVelocityX(0).withVelocityY(0).withRotationalRate(calcul));
System.out.println(angle);