Compare commits
4 Commits
da6bd598b0
...
04718b8400
| Author | SHA1 | Date | |
|---|---|---|---|
|
|
04718b8400 | ||
|
|
eef7ee3eed | ||
|
|
820d7de306 | ||
|
|
f590d88c2d |
@@ -10,6 +10,7 @@ import java.util.function.DoubleSupplier;
|
||||
import com.ctre.phoenix6.swerve.SwerveModule.DriveRequestType;
|
||||
import com.ctre.phoenix6.swerve.SwerveRequest;
|
||||
|
||||
import edu.wpi.first.math.MathUtil;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import frc.robot.TunerConstants.TunerConstants;
|
||||
import frc.robot.subsystems.CommandSwerveDrivetrain;
|
||||
@@ -47,17 +48,37 @@ public class AprilTag3 extends Command {
|
||||
// Called every time the scheduler runs while the command is scheduled.
|
||||
@Override
|
||||
public void execute() {
|
||||
double a = limelight3.getTx();
|
||||
double b = (limelight3.getTA()*100) / (Math.cos(90-limelight3.getTx()));
|
||||
double[] targetPose = limelight3.getTargetPose();
|
||||
double[] BotPose = limelight3.getBotPose();
|
||||
double z = targetPose[2];
|
||||
double x = targetPose[0];
|
||||
double Botyaw = BotPose[5];
|
||||
double tx = limelight3.getTx();
|
||||
if(limelight3.getV() == true){
|
||||
if(limelight3.getTA() > 1.2){
|
||||
drivetrain.setControl(drive.
|
||||
withRotationalRate(a/20).
|
||||
withVelocityX(0).
|
||||
withVelocityY( b/50));
|
||||
System.out.println(b/50);
|
||||
if(Botyaw > 0 && Botyaw <=90){
|
||||
drivetrain.setControl(drive.
|
||||
withRotationalRate(tx/20).
|
||||
withVelocityX(MathUtil.clamp(x/4, -1, 1)).
|
||||
withVelocityY(MathUtil.clamp(z/4, -1, 1)));
|
||||
}
|
||||
|
||||
else if(Botyaw >90 && Botyaw <=180){
|
||||
drivetrain.setControl(drive.
|
||||
withRotationalRate(tx/20).
|
||||
withVelocityX(MathUtil.clamp(-x/4, -1, 1)).
|
||||
withVelocityY(MathUtil.clamp(z/4, -1, 1)));
|
||||
}
|
||||
else if(Botyaw >-90 && Botyaw <=0){
|
||||
drivetrain.setControl(drive.
|
||||
withRotationalRate(tx/20).
|
||||
withVelocityX(MathUtil.clamp(-x/4, -1, 1)).
|
||||
withVelocityY(MathUtil.clamp(-z/4, -1, 1)));
|
||||
}
|
||||
else if(Botyaw >-180 && Botyaw <=-90){
|
||||
drivetrain.setControl(drive.
|
||||
withRotationalRate(tx/20).
|
||||
withVelocityX(MathUtil.clamp(x/4, -1, 1)).
|
||||
withVelocityY(MathUtil.clamp(-z/4, -1, 1)));
|
||||
}
|
||||
}
|
||||
else{
|
||||
drivetrain.setControl(drive.
|
||||
|
||||
@@ -20,6 +20,18 @@ public class Limelight3 extends SubsystemBase {
|
||||
PortForwarder.add(port, "limelight.local", port);
|
||||
}
|
||||
}
|
||||
public double[] getTargetPose(){
|
||||
NetworkTable limelightTable = NetworkTableInstance.getDefault().getTable("limelight");
|
||||
NetworkTableEntry targetPoseEntry = limelightTable.getEntry("targetpose_cameraspace");
|
||||
double[] targetPose = targetPoseEntry.getDoubleArray(new double[6]);
|
||||
return targetPose;
|
||||
}
|
||||
public double[] getBotPose(){
|
||||
NetworkTable limelightTable = NetworkTableInstance.getDefault().getTable("limelight");
|
||||
NetworkTableEntry BotPoseEntry = limelightTable.getEntry("botpose_cameraspace");
|
||||
double[] BotPose = BotPoseEntry.getDoubleArray(new double[6]);
|
||||
return BotPose;
|
||||
}
|
||||
public double getTx(){
|
||||
NetworkTable table = NetworkTableInstance.getDefault().getTable("limelight-balon");
|
||||
NetworkTableEntry tx = table.getEntry("tx");
|
||||
|
||||
Reference in New Issue
Block a user