Skip to content

Commit

Permalink
Added a Limelight Availability Check. Added Docs. Removed results wra…
Browse files Browse the repository at this point in the history
…pper.
  • Loading branch information
tom131313 authored and thenetworkgrinch committed Jan 24, 2025
1 parent b3e5a86 commit d64617b
Show file tree
Hide file tree
Showing 8 changed files with 221 additions and 53 deletions.
2 changes: 1 addition & 1 deletion example/build.gradle
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
plugins {
id "java"
id "edu.wpi.first.GradleRIO" version "2025.1.1"
id "edu.wpi.first.GradleRIO" version "2025.2.1"
}

java {
Expand Down
86 changes: 80 additions & 6 deletions yall/java/limelight/Limelight.java
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,9 @@

import edu.wpi.first.networktables.NetworkTable;
import edu.wpi.first.networktables.NetworkTableInstance;
import edu.wpi.first.wpilibj.Alert;
import edu.wpi.first.wpilibj.Alert.AlertType;
import edu.wpi.first.wpilibj.DriverStation;
import java.io.IOException;
import java.net.HttpURLConnection;
import java.net.URL;
Expand Down Expand Up @@ -38,15 +41,82 @@ public class Limelight
/**
* Constructs and configures the {@link Limelight} NT Values.
*
* @param name Name of the limelight.
* @param name Name of the limelight
*/
public Limelight(String name)
{
isAvailable(name);
limelightName = name;
limelightData = new LimelightData(this);
settings = new LimelightSettings(this);
}

/**
* 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
* loop.
* <p>
* 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"
*
* @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.
*/
@SuppressWarnings("resource")
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"))
{
return true;
}
System.out.println("waiting " + i + " of 15 seconds for limelight to attach");
try
{
Thread.sleep(1000);
} catch (InterruptedException e)
{
e.printStackTrace();
}
}

StringBuilder message = new StringBuilder();
message.append("Your limelight name \"");
message.append(limelightName);
message.append("\" doesn't exist on the network (no getpipe key).\nThese may be available <");
var foundNoLL = true;
var NTtables = NetworkTableInstance.getDefault().getTable("/").getSubTables().toArray();
for (Object element : NTtables)
{
var tableName = (String) element;
if (tableName.startsWith("limelight"))
{
foundNoLL = false;
message.append(tableName);
message.append(" ");
}
}

if (foundNoLL)
{
message.append("--none--");
}

message.append(">");

DriverStation.reportError(message.toString(), false);
new Alert(message.toString(), AlertType.kError).set(true);

return false;
}

/**
* Create a {@link LimelightPoseEstimator} for the {@link Limelight}.
*
Expand All @@ -58,11 +128,17 @@ public LimelightPoseEstimator getPoseEstimator(boolean megatag2)
return new LimelightPoseEstimator(this, megatag2);
}


/**
* Get the {@link LimelightSettings} with current selections.
* 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
* ".withXXXX" settings to attach to.
* <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.
*/
public LimelightSettings getSettings()
public LimelightSettings settingsBuilder()
{
return settings;
}
Expand Down Expand Up @@ -111,7 +187,6 @@ public void snapshot(String snapshotname)
});
}


/**
* Gets the latest JSON {@link LimelightResults} output and returns a LimelightResults object.
*
Expand All @@ -122,7 +197,6 @@ public Optional<LimelightResults> getLatestResults()
return limelightData.getResults();
}


/**
* Flush the NetworkTable data to server.
*/
Expand Down
2 changes: 2 additions & 0 deletions yall/java/limelight/estimator/LimelightPoseEstimator.java
Original file line number Diff line number Diff line change
Expand Up @@ -55,6 +55,8 @@ public Pose3d getBotPose()

/**
* Get the {@link PoseEstimate} corresponding with your alliance color.
* <p>
* Alliance comes from DriverStation. If simulation, then the sim GUI must not be in "disconnected" mode.
*
* @return {@link Optional} of {@link PoseEstimate} of your given alliance.
*/
Expand Down
45 changes: 19 additions & 26 deletions yall/java/limelight/estimator/PoseEstimate.java
Original file line number Diff line number Diff line change
Expand Up @@ -132,7 +132,7 @@ public Optional<PoseEstimate> getPoseEstimate()
double tagArea = extractArrayEntry(poseArray, 10);

// Convert server timestamp from microseconds to seconds and adjust for latency
double adjustedTimestamp = (timestamp / 1000000.0) - (latency / 1000.0);
double adjustedTimestamp = (timestamp / 1_000_000.0) - (latency / 1_000.0);

RawFiducial[] rawFiducials = new RawFiducial[tagCount];
int valsPerFiducial = 7;
Expand Down Expand Up @@ -231,44 +231,37 @@ public double getAvgTagAmbiguity()
* Prints detailed information about a PoseEstimate to standard output. Includes timestamp, latency, tag count, tag
* span, average tag distance, average tag area, and detailed information about each detected fiducial.
*/
public void printPoseEstimate()
public String toString()
{
StringBuilder str = new StringBuilder();
if (!hasData)
{
System.out.println("No PoseEstimate available.");
return;
str.append(String.format("No PoseEstimate available.%n"));
return str.toString();
}

System.out.printf("Pose Estimate Information:%n");
System.out.printf("Timestamp (Seconds): %.3f%n", timestampSeconds);
System.out.printf("Latency: %.3f ms%n", latency);
System.out.printf("Tag Count: %d%n", tagCount);
System.out.printf("Tag Span: %.2f meters%n", tagSpan);
System.out.printf("Average Tag Distance: %.2f meters%n", avgTagDist);
System.out.printf("Average Tag Area: %.2f%% of image%n", avgTagArea);
System.out.printf("Is MegaTag2: %b%n", isMegaTag2);
System.out.println();
str.append(String.format("%nPose Estimate Information:%n"));
str.append(String.format("Timestamp (Seconds): %.3f%n", timestampSeconds));
str.append(String.format("Latency: %.3f ms%n", latency));
str.append(String.format("Tag Count: %d%n", tagCount));
str.append(String.format("Tag Span: %.2f meters%n", tagSpan));
str.append(String.format("Average Tag Distance: %.2f meters%n", avgTagDist));
str.append(String.format("Average Tag Area: %.2f%% of image%n", avgTagArea));
str.append(String.format("Is MegaTag2: %b%n%n", isMegaTag2));

if (rawFiducials == null || rawFiducials.length == 0)
{
System.out.println("No RawFiducials data available.");
return;
str.append(String.format("No RawFiducials data available.%n"));
return str.toString();
}

System.out.println("Raw Fiducials Details:");
str.append(String.format("Raw Fiducials Details:%n"));
for (int i = 0; i < rawFiducials.length; i++)
{
RawFiducial fiducial = rawFiducials[i];
System.out.printf(" Fiducial #%d:%n", i + 1);
System.out.printf(" ID: %d%n", fiducial.id);
System.out.printf(" TXNC: %.2f%n", fiducial.txnc);
System.out.printf(" TYNC: %.2f%n", fiducial.tync);
System.out.printf(" TA: %.2f%n", fiducial.ta);
System.out.printf(" Distance to Camera: %.2f meters%n", fiducial.distToCamera);
System.out.printf(" Distance to Robot: %.2f meters%n", fiducial.distToRobot);
System.out.printf(" Ambiguity: %.2f%n", fiducial.ambiguity);
System.out.println();
str.append(String.format("Fiducial #%d:%n", i + 1));
str.append(fiducial);
}
return str.toString();
}


Expand Down
16 changes: 16 additions & 0 deletions yall/java/limelight/results/RawFiducial.java
Original file line number Diff line number Diff line change
Expand Up @@ -49,4 +49,20 @@ public RawFiducial(int id, double txnc, double tync, double ta, double distToCam
this.distToRobot = distToRobot;
this.ambiguity = ambiguity;
}


/**
* Convert the AprilTag class into a string
*/
public String toString()
{
StringBuilder str = new StringBuilder(220);
str.append(String.format("Tag ID %d%n", id));
str.append(String.format(" Coordinate in image (%.2f, %.2f)%n", txnc, tync));
str.append(String.format(" Tag Area %.2f%n", ta));
str.append(String.format(" Distance to Camera %.2f%n", distToCamera));
str.append(String.format(" Distance to Robot %.2f%n", distToRobot));
str.append(String.format(" Ambiguity %.2f%n", ambiguity));
return str.toString();
}
}
49 changes: 35 additions & 14 deletions yall/java/limelight/structures/LimelightData.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,8 +4,6 @@
import static limelight.structures.LimelightUtils.extractArrayEntry;
import static limelight.structures.LimelightUtils.toPose3D;

import com.fasterxml.jackson.annotation.JsonProperty;
import com.fasterxml.jackson.core.JsonProcessingException;
import com.fasterxml.jackson.databind.DeserializationFeature;
import com.fasterxml.jackson.databind.ObjectMapper;
import edu.wpi.first.math.geometry.Pose3d;
Expand All @@ -14,7 +12,6 @@
import edu.wpi.first.networktables.NetworkTableEntry;
import edu.wpi.first.networktables.StringArrayEntry;
import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.RobotBase;
import java.util.Optional;
import limelight.Limelight;
import limelight.results.RawDetection;
Expand Down Expand Up @@ -168,26 +165,29 @@ public String getDetectorClass()


/**
* Get {@link LimelightResults} from NetworkTables
* Get {@link LimelightResults} from NetworkTables.
* <p>
* Exists only if LL GUI option "Output & Crosshair - Send JSON over NT?" is Yes
*
* @return {@link LimelightResults} if it exists.
*/
public Optional<LimelightResults> getResults()
{
try
{
LimelightResults data = resultsObjectMapper.readValue(results.getString(""), LimelightResults.class);
return Optional.of(data);

} catch (JsonProcessingException e)
{
if (RobotBase.isSimulation())
var JSONresult = results.getString("");
if (JSONresult.length() <= 0)
{
// TODO: Put sim warning here.
}
else {
DriverStation.reportError("lljson error: " + e.getMessage(), true);
return Optional.empty();
}
LimelightResults data = resultsObjectMapper.readValue(JSONresult,
LimelightResults.class); // don't use wrapper class
// LimelightResults data = resultsObjectMapper.readValue(JSONresult, ResultsWrapper.class).resultsWrapper; // use wrapper class
return Optional.of(data);
} catch (Exception e) // catch all the errors - multiple kinds are possible
{
System.out.println("lljson error: " + e.getMessage());
DriverStation.reportError("lljson error: " + e.getMessage(), true);
}
return Optional.empty();
}
Expand Down Expand Up @@ -276,4 +276,25 @@ public RawDetection[] getRawDetections()
return rawDetections;
}

// Example of a JSON deserializer wrapper class that can be customized.
// Customization not needed for the current impelmentation of this YALL.
// /**
// * ResultsWrapper Class for JSON reading.
// */
// private static class ResultsWrapper
// {

// /**
// * "ResultsWrapper" Object for JSON reading.
// */
// @JsonProperty("resultsWrapper")
// public LimelightResults resultsWrapper;

// @JsonCreator(mode = JsonCreator.Mode.DELEGATING)

// public ResultsWrapper(LimelightResults resultsWrapper)
// {
// this.resultsWrapper = resultsWrapper;
// }
// }
}
37 changes: 36 additions & 1 deletion yall/java/limelight/structures/LimelightResults.java
Original file line number Diff line number Diff line change
Expand Up @@ -10,12 +10,12 @@
import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.math.geometry.Pose3d;
import edu.wpi.first.wpilibj.DriverStation;
import limelight.Limelight;
import limelight.structures.target.AprilTagFiducial;
import limelight.structures.target.Barcode;
import limelight.structures.target.RetroreflectiveTape;
import limelight.structures.target.pipeline.NeuralClassifier;
import limelight.structures.target.pipeline.NeuralDetector;
import limelight.Limelight;

/**
* {@link Limelight} Results object, parsed from a {@link Limelight}'s JSON limelight.results output.
Expand Down Expand Up @@ -126,5 +126,40 @@ public Pose2d getBotPose2d(DriverStation.Alliance alliance)
}
}

/**
* Commonly used but very incomplete set from JSON key from the LL
*/
public String toString()
{
StringBuilder str = new StringBuilder();
str.append("Partial JSON LimelightResults\n");
str.append("error " + error + "\n");
str.append("latency_jsonParse " + latency_jsonParse + "\n");

str.append("pID " + pipelineID + "\n");
str.append("tl " + latency_pipeline + "\n");
str.append("cl " + latency_capture + "\n");
str.append("ts " + timestamp_LIMELIGHT_publish + "\n");
str.append("ts_rio " + timestamp_RIOFPGA_capture + "\n");
str.append("v " + valid + "\n");
str.append("botpose 3d " + getBotPose3d() + "\n");
str.append("botpose_wpired 3d " + getBotPose3d(DriverStation.Alliance.Red) + "\n");
str.append("botpose_wpiblue 3d " + getBotPose3d(DriverStation.Alliance.Blue) + "\n");
str.append("botpose 2d " + getBotPose2d() + "\n");
str.append("botpose_wpired 2d " + getBotPose2d(DriverStation.Alliance.Red) + "\n");
str.append("botpose_wpiblue 2d " + getBotPose2d(DriverStation.Alliance.Blue) + "\n");
str.append("botpose_tagcount " + botpose_tagcount + "\n");
str.append("botpose_span " + botpose_span + "\n");
str.append("botpose_avgdist " + botpose_avgdist + "\n");
str.append("botpose_avgarea " + botpose_avgarea + "\n");
str.append("t6c_rs " + camerapose_robotspace + "\n");
str.append("Retro " + targets_Retro + "\n");
str.append("Fiducial " + targets_Fiducials + "\n");
str.append("Classifier " + targets_Classifier + "\n");
str.append("Detector " + targets_Detector + "\n");
str.append("Barcode " + targets_Barcode + "\n");

return str.toString();
}

}
Loading

0 comments on commit d64617b

Please sign in to comment.