diff --git a/src/main/java/frc/robot/command/Lancer.java b/src/main/java/frc/robot/command/Lancer.java index e7fa56d..57289d3 100644 --- a/src/main/java/frc/robot/command/Lancer.java +++ b/src/main/java/frc/robot/command/Lancer.java @@ -29,7 +29,7 @@ public class Lancer extends Command { // Called every time the scheduler runs while the command is scheduled. @Override public void execute() { - if(limelight.getv()){ + if(limelight.getv()==1){ lanceur.lancerspeaker(); } } diff --git a/src/main/java/frc/robot/command/Lancerampli.java b/src/main/java/frc/robot/command/Lancerampli.java index 3e1fe59..8127295 100644 --- a/src/main/java/frc/robot/command/Lancerampli.java +++ b/src/main/java/frc/robot/command/Lancerampli.java @@ -29,7 +29,7 @@ public class Lancerampli extends Command { // Called every time the scheduler runs while the command is scheduled. @Override public void execute() { - if(limelight.getv()){ + if(limelight.getv()==1){ lanceur.lanceramp(); } diff --git a/src/main/java/frc/robot/command/Limelight_tracker.java b/src/main/java/frc/robot/command/Limelight_tracker.java index 9b42d82..edc95fd 100644 --- a/src/main/java/frc/robot/command/Limelight_tracker.java +++ b/src/main/java/frc/robot/command/Limelight_tracker.java @@ -27,8 +27,8 @@ public class Limelight_tracker extends Command { @Override public void execute() { - if (tracker.getv()){ - drive.drive(0,0, tracker.getx()); + if (tracker.getv()==1){ + drive.drive(0,0, tracker.getx()/30); } else{ diff --git a/src/main/java/frc/robot/subsystem/Limelight.java b/src/main/java/frc/robot/subsystem/Limelight.java index 383685a..62d0be3 100644 --- a/src/main/java/frc/robot/subsystem/Limelight.java +++ b/src/main/java/frc/robot/subsystem/Limelight.java @@ -34,8 +34,8 @@ public class Limelight extends SubsystemBase { public double gety(){ return ty.getDouble(0); } - public boolean getv(){ - return tv.getBoolean(false); + public double getv(){ + return tv.getDouble(0); } public void setpipeline(){ pipeline.setNumber(0);