This commit is contained in:
@@ -55,23 +55,24 @@ public class AprilTag3 extends Command {
|
||||
double Botyaw = BotPose[5];
|
||||
double tx = limelight3.getTx();
|
||||
if(limelight3.getV() == true){
|
||||
System.out.println(Botyaw);
|
||||
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 <=180){
|
||||
drivetrain.setControl(drive.
|
||||
withRotationalRate(0).
|
||||
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)));
|
||||
withVelocityY(MathUtil.clamp(z/4, -1, 1)));
|
||||
}
|
||||
else if(Botyaw >-180 && Botyaw <=-90){
|
||||
drivetrain.setControl(drive.
|
||||
|
||||
@@ -21,14 +21,14 @@ public class Limelight3 extends SubsystemBase {
|
||||
}
|
||||
}
|
||||
public double[] getTargetPose(){
|
||||
NetworkTable limelightTable = NetworkTableInstance.getDefault().getTable("limelight");
|
||||
NetworkTable limelightTable = NetworkTableInstance.getDefault().getTable("limelight-balon");
|
||||
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");
|
||||
NetworkTable limelightTable = NetworkTableInstance.getDefault().getTable("limelight-balon");
|
||||
NetworkTableEntry BotPoseEntry = limelightTable.getEntry("botpose");
|
||||
double[] BotPose = BotPoseEntry.getDoubleArray(new double[6]);
|
||||
return BotPose;
|
||||
}
|
||||
|
||||
Reference in New Issue
Block a user