From 1f91867209afd9f94af234797434490fd3ffec3e Mon Sep 17 00:00:00 2001 From: Aarav Shah Date: Mon, 5 Apr 2021 16:56:27 -0600 Subject: [PATCH] Trying to fix shooter --- .../robot/commands/shooter/TrackTarget.java | 1 + .../frc4388/robot/subsystems/LimeLight.java | 19 ++++++++++++++++++- 2 files changed, 19 insertions(+), 1 deletion(-) diff --git a/src/main/java/frc4388/robot/commands/shooter/TrackTarget.java b/src/main/java/frc4388/robot/commands/shooter/TrackTarget.java index 0fca6a5..dbcfe5a 100644 --- a/src/main/java/frc4388/robot/commands/shooter/TrackTarget.java +++ b/src/main/java/frc4388/robot/commands/shooter/TrackTarget.java @@ -65,6 +65,7 @@ public class TrackTarget extends CommandBase { //NetworkTableInstance.getDefault().getTable("limelight").getEntry("ledMode").setNumber(3); NetworkTableInstance.getDefault().getTable("limelight").getEntry("camMode").setNumber(0); NetworkTableInstance.getDefault().getTable("limelight").getEntry("ledMode").setNumber(3); + m_limeLight.changePipeline(0); } // Called every time the scheduler runs while the command is scheduled. diff --git a/src/main/java/frc4388/robot/subsystems/LimeLight.java b/src/main/java/frc4388/robot/subsystems/LimeLight.java index 9ea2c96..09bd99d 100644 --- a/src/main/java/frc4388/robot/subsystems/LimeLight.java +++ b/src/main/java/frc4388/robot/subsystems/LimeLight.java @@ -19,7 +19,7 @@ public class LimeLight extends SubsystemBase { } public void limeOff(){ - NetworkTableInstance.getDefault().getTable("limelight").getEntry("camMode").setNumber(1); + NetworkTableInstance.getDefault().getTable("limelight").getEntry("camMode").setNumber(0); NetworkTableInstance.getDefault().getTable("limelight").getEntry("ledMode").setNumber(1); } @@ -27,7 +27,24 @@ public class LimeLight extends SubsystemBase { NetworkTableInstance.getDefault().getTable("limelight").getEntry("camMode").setNumber(0); NetworkTableInstance.getDefault().getTable("limelight").getEntry("ledMode").setNumber(3); } + + public void changePipeline(int pipelineId) + { + NetworkTableInstance.getDefault().getTable("limelight").getEntry("pipeline").setNumber(pipelineId); + } + public double getV() + { + return NetworkTableInstance.getDefault().getTable("limelight").getEntry("tv").getDouble(0); + } + public double getX() + { + return NetworkTableInstance.getDefault().getTable("limelight").getEntry("tx").getDouble(0); + } + public double getY() + { + return NetworkTableInstance.getDefault().getTable("limelight").getEntry("ty").getDouble(0); + } @Override public void periodic() { // This method will be called once per scheduler run