Skip to content

Conversation

@timtogan
Copy link
Member

added LimelightHelpers as a vendorLib as mentioned in #113 (review)

Copilot AI review requested due to automatic review settings December 28, 2025 10:12
@timtogan timtogan requested a review from a team as a code owner December 28, 2025 10:12
Copy link

Copilot AI left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Pull request overview

This PR adds LimelightHelpers v1.12 as a vendor library to support integration with Limelight vision cameras. The library provides comprehensive functionality for AprilTag tracking, neural networks, and standard color/retroreflective tracking in FRC applications.

  • Adds complete LimelightHelpers class with support for multiple target types (Retro, Fiducial, Barcode, Classifier, Detector)
  • Implements pose estimation methods for robot localization using vision data
  • Provides NetworkTables integration for reading/writing Limelight data

💡 Add Copilot custom instructions for smarter, more guided reviews. Learn how to get started.

Comment on lines +1520 to +1610
public static void SetIMUMode(String limelightName, int mode) {
setLimelightNTDouble(limelightName, "imumode_set", mode);
}

/**
* Configures the complementary filter alpha value for IMU Assist Modes (Modes 3 and 4)
*
* @param limelightName Name/identifier of the Limelight
* @param alpha Defaults to .001. Higher values will cause the internal IMU to converge onto the assist source more rapidly.
*/
public static void SetIMUAssistAlpha(String limelightName, double alpha) {
setLimelightNTDouble(limelightName, "imuassistalpha_set", alpha);
}


/**
* Configures the throttle value. Set to 100-200 while disabled to reduce thermal output/temperature.
*
* @param limelightName Name/identifier of the Limelight
* @param throttle Defaults to 0. Your Limelgiht will process one frame after skipping throttle frames.
*/
public static void SetThrottle(String limelightName, int throttle) {
setLimelightNTDouble(limelightName, "throttle_set", throttle);
}

/**
* Sets the 3D point-of-interest offset for the current fiducial pipeline.
* https://docs.limelightvision.io/docs/docs-limelight/pipeline-apriltag/apriltag-3d#point-of-interest-tracking
*
* @param limelightName Name/identifier of the Limelight
* @param x X offset in meters
* @param y Y offset in meters
* @param z Z offset in meters
*/
public static void SetFidcuial3DOffset(String limelightName, double x, double y,
double z) {

double[] entries = new double[3];
entries[0] = x;
entries[1] = y;
entries[2] = z;
setLimelightNTDoubleArray(limelightName, "fiducial_offset_set", entries);
}

/**
* Overrides the valid AprilTag IDs that will be used for localization.
* Tags not in this list will be ignored for robot pose estimation.
*
* @param limelightName Name/identifier of the Limelight
* @param validIDs Array of valid AprilTag IDs to track
*/
public static void SetFiducialIDFiltersOverride(String limelightName, int[] validIDs) {
double[] validIDsDouble = new double[validIDs.length];
for (int i = 0; i < validIDs.length; i++) {
validIDsDouble[i] = validIDs[i];
}
setLimelightNTDoubleArray(limelightName, "fiducial_id_filters_set", validIDsDouble);
}

/**
* Sets the downscaling factor for AprilTag detection.
* Increasing downscale can improve performance at the cost of potentially reduced detection range.
*
* @param limelightName Name/identifier of the Limelight
* @param downscale Downscale factor. Valid values: 1.0 (no downscale), 1.5, 2.0, 3.0, 4.0. Set to 0 for pipeline control.
*/
public static void SetFiducialDownscalingOverride(String limelightName, float downscale)
{
int d = 0; // pipeline
if (downscale == 1.0)
{
d = 1;
}
if (downscale == 1.5)
{
d = 2;
}
if (downscale == 2)
{
d = 3;
}
if (downscale == 3)
{
d = 4;
}
if (downscale == 4)
{
d = 5;
}
setLimelightNTDouble(limelightName, "fiducial_downscale_set", d);
}
Copy link

Copilot AI Dec 28, 2025

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Inconsistent naming convention: method name should start with lowercase letter. The methods "SetIMUMode", "SetIMUAssistAlpha", "SetThrottle", "SetFidcuial3DOffset", and "SetFiducialIDFiltersOverride", "SetFiducialDownscalingOverride" should follow Java naming conventions and start with lowercase letters.

Copilot uses AI. Check for mistakes.
}

private static boolean SYNCH_TAKESNAPSHOT(String tableName, String snapshotName) {
URL url = getLimelightURLString(tableName, "capturesnapshot");
Copy link

Copilot AI Dec 28, 2025

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Potential null pointer exception. If getLimelightURLString returns null (which can happen based on line 961), calling url.openConnection() will throw a NullPointerException. Add a null check before attempting to open the connection.

Suggested change
URL url = getLimelightURLString(tableName, "capturesnapshot");
URL url = getLimelightURLString(tableName, "capturesnapshot");
if (url == null) {
System.err.println("Unable to create Limelight URL for snapshot request");
return false;
}

Copilot uses AI. Check for mistakes.
}

/**
* T2D is an array that contains several targeting metrcis
Copy link

Copilot AI Dec 28, 2025

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Spelling error: "metrcis" should be "metrics"

Suggested change
* T2D is an array that contains several targeting metrcis
* T2D is an array that contains several targeting metrics

Copilot uses AI. Check for mistakes.
* Configures the throttle value. Set to 100-200 while disabled to reduce thermal output/temperature.
*
* @param limelightName Name/identifier of the Limelight
* @param throttle Defaults to 0. Your Limelgiht will process one frame after skipping throttle frames.
Copy link

Copilot AI Dec 28, 2025

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Spelling error: "Limelgiht" should be "Limelight"

Suggested change
* @param throttle Defaults to 0. Your Limelgiht will process one frame after skipping throttle frames.
* @param throttle Defaults to 0. Your Limelight will process one frame after skipping <throttle> frames.

Copilot uses AI. Check for mistakes.
* @param y Y offset in meters
* @param z Z offset in meters
*/
public static void SetFidcuial3DOffset(String limelightName, double x, double y,
Copy link

Copilot AI Dec 28, 2025

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Spelling error in method name: "SetFidcuial3DOffset" should be "SetFiducial3DOffset" (missing 'i' in Fiducial)

Copilot uses AI. Check for mistakes.
Comment on lines +1487 to +1496
SetRobotOrientation_INTERNAL(limelightName, yaw, yawRate, pitch, pitchRate, roll, rollRate, true);
}

public static void SetRobotOrientation_NoFlush(String limelightName, double yaw, double yawRate,
double pitch, double pitchRate,
double roll, double rollRate) {
SetRobotOrientation_INTERNAL(limelightName, yaw, yawRate, pitch, pitchRate, roll, rollRate, false);
}

private static void SetRobotOrientation_INTERNAL(String limelightName, double yaw, double yawRate,
Copy link

Copilot AI Dec 28, 2025

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Inconsistent naming convention: method name should start with lowercase letter. The method "SetRobotOrientation_INTERNAL" should be "setRobotOrientation_INTERNAL" to follow Java naming conventions.

Suggested change
SetRobotOrientation_INTERNAL(limelightName, yaw, yawRate, pitch, pitchRate, roll, rollRate, true);
}
public static void SetRobotOrientation_NoFlush(String limelightName, double yaw, double yawRate,
double pitch, double pitchRate,
double roll, double rollRate) {
SetRobotOrientation_INTERNAL(limelightName, yaw, yawRate, pitch, pitchRate, roll, rollRate, false);
}
private static void SetRobotOrientation_INTERNAL(String limelightName, double yaw, double yawRate,
setRobotOrientation_INTERNAL(limelightName, yaw, yawRate, pitch, pitchRate, roll, rollRate, true);
}
public static void SetRobotOrientation_NoFlush(String limelightName, double yaw, double yawRate,
double pitch, double pitchRate,
double roll, double rollRate) {
setRobotOrientation_INTERNAL(limelightName, yaw, yawRate, pitch, pitchRate, roll, rollRate, false);
}
private static void setRobotOrientation_INTERNAL(String limelightName, double yaw, double yawRate,

Copilot uses AI. Check for mistakes.
/**
* Represents a Limelight Raw Fiducial result from Limelight's NetworkTables output.
*/
public static class RawFiducial {
Copy link

Copilot AI Dec 28, 2025

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Class RawFiducial overrides equals but not hashCode.

Copilot uses AI. Check for mistakes.
/**
* Represents a 3D Pose Estimate.
*/
public static class PoseEstimate {
Copy link

Copilot AI Dec 28, 2025

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Class PoseEstimate overrides equals but not hashCode.

Copilot uses AI. Check for mistakes.
static boolean profileJSON = false;

static final String sanitizeName(String name) {
if ("".equals(name) || name == null) {
Copy link

Copilot AI Dec 28, 2025

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Inefficient comparison to empty string, check for zero length instead.

Suggested change
if ("".equals(name) || name == null) {
if (name == null || name.isEmpty()) {

Copilot uses AI. Check for mistakes.
try {
HttpURLConnection connection = (HttpURLConnection) url.openConnection();
connection.setRequestMethod("GET");
if (snapshotName != null && !"".equals(snapshotName)) {
Copy link

Copilot AI Dec 28, 2025

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Inefficient comparison to empty string, check for zero length instead.

Suggested change
if (snapshotName != null && !"".equals(snapshotName)) {
if (snapshotName != null && !snapshotName.isEmpty()) {

Copilot uses AI. Check for mistakes.
@timtogan
Copy link
Member Author

@CoolSpy3 could you review pls

Copy link
Member

@CoolSpy3 CoolSpy3 left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

W00T 👍 Ty :D

@timtogan timtogan merged commit cf28366 into 2025 Dec 30, 2025
3 checks passed
@timtogan timtogan deleted the limelight branch December 30, 2025 03:12
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Labels

None yet

Projects

None yet

Development

Successfully merging this pull request may close these issues.

3 participants