j
This commit is contained in:
		@@ -14,37 +14,39 @@ import frc.robot.LimelightHelpers;
 | 
			
		||||
 | 
			
		||||
 | 
			
		||||
public class Limelight extends SubsystemBase {
 | 
			
		||||
  /** Creates a new Limelight. */
 | 
			
		||||
  public Limelight() {
 | 
			
		||||
 | 
			
		||||
  NetworkTable table = NetworkTableInstance.getDefault().getTable("limelight");
 | 
			
		||||
  NetworkTableInstance.getDefault().getTable("limelight").getEntry("Tv").getDouble(0);
 | 
			
		||||
  NetworkTableInstance.getDefault().getTable("limelight").getEntry("getpipe").getDouble(1);
 | 
			
		||||
  NetworkTableInstance.getDefault().getTable("limelight").getEntry("").getDoubleArray(new double[6]);
 | 
			
		||||
 | 
			
		||||
 | 
			
		||||
  NetworkTableEntry tx = table.getEntry("tx");
 | 
			
		||||
  NetworkTableEntry ty = table.getEntry("ty");
 | 
			
		||||
  NetworkTableEntry ta = table.getEntry("ta");
 | 
			
		||||
  NetworkTableEntry botpose = table.getEntry("pose");
 | 
			
		||||
  NetworkTableEntry getpipe = table.getEntry(getName());
 | 
			
		||||
  NetworkTableEntry pipeline = table.getEntry("pipeline");
 | 
			
		||||
  NetworkTableEntry tv = table.getEntry("tv");
 | 
			
		||||
  NetworkTableEntry camMode = table.getEntry("camMode");
 | 
			
		||||
 | 
			
		||||
  double x = tx.getDouble(0.0);
 | 
			
		||||
  double y = ty.getDouble(0.0);
 | 
			
		||||
  double area = ta.getDouble(0.0);
 | 
			
		||||
  double pose = botpose.getDouble(area);
 | 
			
		||||
  
 | 
			
		||||
    
 | 
			
		||||
  
 | 
			
		||||
 
 | 
			
		||||
     /** Creates a new Limelight. */
 | 
			
		||||
  public Limelight() {
 | 
			
		||||
  }
 | 
			
		||||
  
 | 
			
		||||
  public double getx(){
 | 
			
		||||
    return tx.getDouble(0);
 | 
			
		||||
  }
 | 
			
		||||
  public double gety(){
 | 
			
		||||
    return ty.getDouble(0);
 | 
			
		||||
  }
 | 
			
		||||
  public double geta() {
 | 
			
		||||
    return ta.getDouble(0);
 | 
			
		||||
  }
 | 
			
		||||
  public boolean getv(){
 | 
			
		||||
    return tv.getBoolean(false);
 | 
			
		||||
  }
 | 
			
		||||
  public double getpipeline(){
 | 
			
		||||
    return pipeline.getDouble(0);
 | 
			
		||||
  }
 | 
			
		||||
  public double getcamMode(){
 | 
			
		||||
    return camMode.getDouble(0);
 | 
			
		||||
  }
 | 
			
		||||
 | 
			
		||||
  SmartDashboard.putNumber("LimelightX", x);
 | 
			
		||||
  SmartDashboard.putNumber("LimelightY", y);
 | 
			
		||||
  SmartDashboard.putNumber("LimelightArea", area);
 | 
			
		||||
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
  
 | 
			
		||||
  @Override
 | 
			
		||||
  public void periodic() {
 | 
			
		||||
    // This method will be called once per scheduler run
 | 
			
		||||
 
 | 
			
		||||
		Reference in New Issue
	
	Block a user