s'enligne vers le apriltag
This commit is contained in:
@@ -27,13 +27,13 @@ public class Limelight3 extends SubsystemBase {
|
||||
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;
|
||||
@@ -48,6 +48,11 @@ public class Limelight3 extends SubsystemBase {
|
||||
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");
|
||||
|
||||
Reference in New Issue
Block a user