Skip to content
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.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -72,7 +72,7 @@ limelight.getSettings()
.save();

// Get MegaTag2 pose
Optional<PoseEstimate> visionEstimate = limelight.createPoseEstimator(true).getPoseEstimate();
Optional<PoseEstimate> visionEstimate = limelight.createPoseEstimator(EstimationMode.MEGATAG2).getPoseEstimate();
// If the pose is present
visionEstimate.ifPresent((PoseEstimate poseEstimate) -> {
// Add it to the pose estimator.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,7 @@
import limelight.networktables.LimelightSettings.LEDMode;
import limelight.networktables.Orientation3d;
import limelight.networktables.PoseEstimate;
import limelight.networktables.LimelightPoseEstimator.EstimationMode;
import limelight.networktables.target.pipeline.NeuralClassifier;

public class DrivebaseSubsystem extends SubsystemBase
Expand Down Expand Up @@ -86,7 +87,7 @@ public DrivebaseSubsystem()
.withLimelightLEDMode(LEDMode.PipelineControl)
.withCameraOffset(cameraOffset)
.save();
poseEstimator = limelight.createPoseEstimator(true);
poseEstimator = limelight.createPoseEstimator(EstimationMode.MEGATAG2);

}

Expand Down
119 changes: 56 additions & 63 deletions yall/java/limelight/Limelight.java
Original file line number Diff line number Diff line change
@@ -1,6 +1,5 @@
package limelight;


import static edu.wpi.first.units.Units.Milliseconds;
import static edu.wpi.first.units.Units.Seconds;
import static limelight.networktables.LimelightUtils.getLimelightURLString;
Expand All @@ -20,36 +19,35 @@
import limelight.networktables.LimelightPoseEstimator;
import limelight.networktables.LimelightResults;
import limelight.networktables.LimelightSettings;
import limelight.networktables.LimelightPoseEstimator.EstimationMode;

/**
* Limelight Camera class.
*/
public class Limelight
{
public class Limelight {

/**
* {@link Limelight} name.
*/
public final String limelightName;
public final String limelightName;
/**
* {@link Limelight} data from NetworkTables.
*/
private LimelightData limelightData;
private LimelightData limelightData;
/**
* {@link Limelight} settings that we apply.
*/
private LimelightSettings settings;
private LimelightSettings settings;

static final long ONE_SECOND_IN_MILI = (long) Seconds.of(1).in(Milliseconds);

/**
* Constructs and configures the {@link Limelight} NT Values.
*
* @param name Name of the limelight
*/
public Limelight(String name)
{
if (!isAvailable(name) && !RobotBase.isSimulation())
{
public Limelight(String name) {
if (!isAvailable(name) && !RobotBase.isSimulation()) {
throw new RuntimeException("Limelight not available");
}

Expand All @@ -61,71 +59,75 @@ public Limelight(String name)
/**
* Verify limelight name exists as a table in NT.
* <p>
* This check is expected to be run once during robot construction and is not intended to be checked in the iterative
* This check is expected to be run once during robot construction and is not
* intended to be checked in the iterative
* loop.
* <p>
* Use check "yourLimelightObject.getData().targetData.getTargetStatus())"" for the validity of an iteration for 2d
* Use check "yourLimelightObject.getData().targetData.getTargetStatus())"" for
* the validity of an iteration for 2d
* targeting.
* <p>
* For valid 3d pose check "yourLimelightPoseEstimatorObject.getPoseEstimate().get().hasData"
* For valid 3d pose check
* "yourLimelightPoseEstimatorObject.getPoseEstimate().get().hasData"
*
* @param limelightName Limelight Name to check for table existence.
* @return true if an NT table exists with requested LL name.
* <p>false and issues a WPILib Error Alert if requested LL doesn't appear as an NT table.
* <p>
* false and issues a WPILib Error Alert if requested LL doesn't appear
* as an NT table.
*/
@SuppressWarnings("resource")
public static boolean isAvailable(String limelightName)
{
public static boolean isAvailable(String limelightName) {
// LL sends key "getpipe" if it's on so check that
// put in a delay if needed to help assure NT has latched onto the LL if it is transmitting
for (int i = 1; i <= 15; i++)
{
if (NetworkTableInstance.getDefault().getTable(limelightName).containsKey("getpipe"))
{
// put in a delay if needed to help assure NT has latched onto the LL if it is
// transmitting
for (int i = 1; i <= 15; i++) {
if (NetworkTableInstance.getDefault().getTable(limelightName).containsKey("getpipe")) {
return true;
}
//System.out.println("waiting " + i + " of 15 seconds for limelight to attach");
try
{
Thread.sleep((long) Seconds.of(1).in(Milliseconds));
} catch (InterruptedException e)
{
// System.out.println("waiting " + i + " of 15 seconds for limelight to
// attach");
try {
Thread.sleep(ONE_SECOND_IN_MILI);
} catch (InterruptedException e) {
e.printStackTrace();
}
}
String errMsg = "Your limelight name \"" + limelightName +
"\" is invalid. doesn't exist on the network (no getpipe key).\n" +
"These may be available:" +
NetworkTableInstance.getDefault().getTable("/").getSubTables().stream()
.filter(ntName -> ((String) (ntName)).startsWith("limelight"))
.collect(Collectors.joining("\n"));
"\" is invalid. doesn't exist on the network (no getpipe key).\n" +
"These may be available:" +
NetworkTableInstance.getDefault().getTable("/").getSubTables().stream()
.filter(ntName -> ((String) (ntName)).startsWith("limelight"))
.collect(Collectors.joining("\n"));
new Alert(errMsg, AlertType.kError).set(true);
return false;
}

/**
* Create a {@link LimelightPoseEstimator} for the {@link Limelight}.
*
* @param megatag2 Use MegaTag2.
* @param estimationMode Estimation mode to use (MEGATAG1 / MEGATAG2).
* @return {@link LimelightPoseEstimator}
*/
public LimelightPoseEstimator createPoseEstimator(boolean megatag2)
{
return new LimelightPoseEstimator(this, megatag2);
public LimelightPoseEstimator createPoseEstimator(EstimationMode estimationMode) {
return new LimelightPoseEstimator(this, estimationMode);
}

/**
* Get the {@link LimelightSettings} preparatory to changing settings.
* <p>While this method does get current settings from the LL there are
* no getters provided for the settings so they are useless, dead data. This merely provides a stub for the various
* <p>
* While this method does get current settings from the LL there are
* no getters provided for the settings so they are useless, dead data. This
* merely provides a stub for the various
* ".withXXXX" settings to attach to.
* <p>This method may be used as often as needed and may contain none or more
* <p>
* This method may be used as often as needed and may contain none or more
* chained ".withXXXX" settings.
*
* @return object used as the target of the various ".withXXXX" settings methods.
* @return object used as the target of the various ".withXXXX" settings
* methods.
*/
public LimelightSettings getSettings()
{
public LimelightSettings getSettings() {
return settings;
}

Expand All @@ -134,8 +136,7 @@ public LimelightSettings getSettings()
*
* @return {@link LimelightData} object.
*/
public LimelightData getData()
{
public LimelightData getData() {
return limelightData;
}

Expand All @@ -144,50 +145,43 @@ public LimelightData getData()
*
* @param snapshotname Snapshot name to save.
*/
public void snapshot(String snapshotname)
{
public void snapshot(String snapshotname) {
CompletableFuture.supplyAsync(() -> {
URL url = getLimelightURLString(limelightName, "capturesnapshot");
try
{
try {
HttpURLConnection connection = (HttpURLConnection) url.openConnection();
connection.setRequestMethod("GET");
if (snapshotname != null && snapshotname != "")
{
if (snapshotname != null && snapshotname != "") {
connection.setRequestProperty("snapname", snapshotname);
}

int responseCode = connection.getResponseCode();
if (responseCode == 200)
{
if (responseCode == 200) {
return true;
} else
{
} else {
System.err.println("Bad LL Request");
}
} catch (IOException e)
{
} catch (IOException e) {
System.err.println(e.getMessage());
}
return false;
});
}

/**
* Gets the latest JSON {@link LimelightResults} output and returns a LimelightResults object.
* Gets the latest JSON {@link LimelightResults} output and returns a
* LimelightResults object.
*
* @return LimelightResults object containing all current target data
*/
public Optional<LimelightResults> getLatestResults()
{
public Optional<LimelightResults> getLatestResults() {
return limelightData.getResults();
}

/**
* Flush the NetworkTable data to server.
*/
public void flush()
{
public void flush() {
NetworkTableInstance.getDefault().flush();
}

Expand All @@ -196,8 +190,7 @@ public void flush()
*
* @return {@link NetworkTable} for this limelight.
*/
public NetworkTable getNTTable()
{
public NetworkTable getNTTable() {
return NetworkTableInstance.getDefault().getTable(limelightName);
}
}
Loading