Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add Limelight vertical length getter method #6

Merged
merged 5 commits into from Jan 20, 2020
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
32 changes: 32 additions & 0 deletions src/main/java/frc/robot/Limelight.java
Expand Up @@ -11,39 +11,71 @@ public class Limelight {
private double tx;
private double ty;
private double ta;
private double tvert;

NetworkTable limelightTable;

/**
* Constructor
*/
public Limelight() {
// Assuming use of the default network table.
limelightTable = NetworkTableInstance.getDefault().getTable("limelight");
}

/**
* Updates limelight values.
*/
public void update() {
this.tv = limelightTable.getEntry("tv").getDouble(0);
this.tx = limelightTable.getEntry("tx").getDouble(0);
this.ty = limelightTable.getEntry("ty").getDouble(0);
this.ta = limelightTable.getEntry("ta").getDouble(0);
this.tvert = limelightTable.getEntry("tvert").getDouble(0);

SmartDashboard.putNumber("LimelightX", this.getTargetX());
SmartDashboard.putNumber("LimelightY", this.getTargetY());
SmartDashboard.putNumber("LimelightArea", this.getTargetArea());
SmartDashboard.putBoolean("LimelightTargeted", this.isTargetVisible());
SmartDashboard.putNumber("LimelightHeight", this.getTargetVertical());
}

/**
* @return if target is visible.
*/
public boolean isTargetVisible() {
return this.tv > 0.0;
}

/**
* @return current target x-coordinate.
*/
public double getTargetX() {
return this.tx;
}

/**
* @return current target y-coordinate.
*/
public double getTargetY() {
return this.ty;
}

/**
* @return current target area of screen (0 to 100 percent).
*/
public double getTargetArea() {
return this.ta;
}

/**
* @return current target vertical length.
*/
public double getTargetVertical() {
return this.tvert;
}

public void setLightEnabled(boolean enabled) {
limelightTable.getEntry("ledMode").forceSetNumber(enabled ? 3: 1);
}
}
9 changes: 9 additions & 0 deletions src/main/java/frc/robot/Robot.java
Expand Up @@ -38,6 +38,9 @@ public class Robot extends TimedRobot {
public void robotInit() {
System.out.print("Initializing vision system (limelight)...");
limelight = new Limelight();
limelight.setLightEnabled(false);
System.out.println("done");

System.out.print("Initializing shooter...");
shooter = new Shooter(new CANSparkMax(2, MotorType.kBrushless));
System.out.println("done");
Expand Down Expand Up @@ -75,6 +78,12 @@ public void teleopPeriodic() {

shooter.manualControl(speed);

if (driver.getXButtonPressed()) {
limelight.setLightEnabled(true);
} else if (driver.getYButtonPressed()) {
limelight.setLightEnabled(false);
}

SmartDashboard.putNumber("ShooterPower", speed);
SmartDashboard.putNumber("ShooterRPM", shooter.getLauncherRPM());
}
Expand Down