This commit is contained in:
Samuel
2025-11-24 18:33:55 -05:00
2 changed files with 20 additions and 8 deletions

View File

@@ -10,10 +10,11 @@ import java.util.function.DoubleSupplier;
import com.ctre.phoenix6.swerve.SwerveModule.DriveRequestType;
import com.ctre.phoenix6.swerve.SwerveRequest;
import edu.wpi.first.math.filter.SlewRateLimiter;
import edu.wpi.first.math.MathUtil;
import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.DriverStation.Alliance;
import edu.wpi.first.wpilibj.SynchronousInterrupt.WaitResult;
import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.TunerConstants.TunerConstants;
import frc.robot.subsystems.CommandSwerveDrivetrain;
@@ -51,7 +52,7 @@ public class AprilTag3 extends Command {
// Called every time the scheduler runs while the command is scheduled.
@Override
public void execute() {
double[] BotPose = new double[7];
double[] BotPose = new double[6];
Optional<DriverStation.Alliance> alliance = DriverStation.getAlliance();
if(alliance.get() == DriverStation.Alliance.Red){
BotPose = limelight3.getBotPoseRed();
@@ -60,18 +61,24 @@ public class AprilTag3 extends Command {
BotPose = limelight3.getBotPoseBlue();
}
double botx = BotPose[0];
double botz = BotPose[2];
double boty = BotPose[1];
double tx = limelight3.getTx();
double tagId = BotPose[7];
double tagId = limelight3.getTId();
if(limelight3.getV() == true){
if(tagId ==8){
if(tagId ==10){
drivetrain.setControl(drive.
withRotationalRate(tx/20).
withVelocityX((botx-5.81)*2).
withVelocityY((boty-4)*4));
}
else if(tagId ==7){
drivetrain.setControl(drive.
withRotationalRate(tx/20).
withVelocityX((2-limelight3.derive(botx))).
withVelocityY(2-limelight3.derive(botz)));
}
}
else{
else{
drivetrain.setControl(drive.
withRotationalRate(0).
withVelocityX(0).

View File

@@ -42,13 +42,13 @@ public double derive(double currentValue) {
return targetPose;
}
public double[] getBotPoseBlue(){
NetworkTable limelightTable = NetworkTableInstance.getDefault().getTable("limelight");
NetworkTable limelightTable = NetworkTableInstance.getDefault().getTable("limelight-balon");
NetworkTableEntry BotPoseEntry = limelightTable.getEntry("botpose_wpiblue");
double[] BotPose = BotPoseEntry.getDoubleArray(new double[7]);
return BotPose;
}
public double[] getBotPoseRed(){
NetworkTable limelightTable = NetworkTableInstance.getDefault().getTable("limelight");
NetworkTable limelightTable = NetworkTableInstance.getDefault().getTable("limelight-balon");
NetworkTableEntry BotPoseEntry = limelightTable.getEntry("botpose_wpired");
double[] BotPose = BotPoseEntry.getDoubleArray(new double[7]);
return BotPose;
@@ -63,6 +63,11 @@ public double derive(double currentValue) {
NetworkTableEntry ta = table.getEntry("ta");
return ta.getDouble(0.0);
}
public double getTId(){
NetworkTable table = NetworkTableInstance.getDefault().getTable("limelight-balon");
NetworkTableEntry tid = table.getEntry("tid");
return tid.getDouble(0.0);
}
public double getRx(){
NetworkTable table = NetworkTableInstance.getDefault().getTable("limelight-balon");
NetworkTableEntry rx = table.getEntry("rx");