跳到主要内容

使用 Limelight Lib 进行 FRC 编程 (WPILib Java & C++)

JavaDocs: https://limelightlib-wpijava-reference.limelightvision.io

使用方法

这是一个单文件库。你只需要从最新版本(https://github.com/LimelightVision/limelightlib-wpijava/releases)复制 LimelightHelpers.java 文件到你的 Java 项目的 "robot" 文件夹中即可。你不需要为你的 Limelight 创建任何对象 - 这个库简单且实用,以最大限度地提高易用性和可靠性。

成功要诣

  • 从简单开始!许多成功的FRC队伍都在有效地使用基本方法。例如,2056队在2024年使用标准的90FPS颜色管道而不是神经网络来追踪比赛道具。
  • 思考你真正需要什么:你是需要完整的场地定位,还是简单的目标居中就够了(例如,driveSpeed = result.getTx() * 0.03)?

关键概念

1. 基本用法

每个方法都接受一个Limelight名称参数。留空或null则使用"limelight":

// 基本目标数据
double tx = LimelightHelpers.getTX(""); // 从准星到目标的水平偏移角度
double ty = LimelightHelpers.getTY(""); // 从准星到目标的垂直偏移角度
double ta = LimelightHelpers.getTA(""); // 目标区域(图像的0%到100%)
boolean hasTarget = LimelightHelpers.getTV(""); // 是否有有效目标?

double txnc = LimelightHelpers.getTXNC(""); // 从主像素/点到目标的水平偏移角度
double tync = LimelightHelpers.getTYNC(""); // 从主像素/点到目标的垂直偏移角度

2. 管道管理

管道就像可以即时切换的程序,用于改变Limelight处理图像的方式。你可以在网页界面中设置10个不同的管道:

// 切换到管道0
LimelightHelpers.setPipelineIndex("", 0);

3. LED控制

对于带有明亮照明LED的Limelight,你可以在不同情况下控制LED:

// 让当前管道控制LED
LimelightHelpers.setLEDMode_PipelineControl("");

// 强制LED开启/关闭/闪烁
LimelightHelpers.setLEDMode_ForceOn("");
LimelightHelpers.setLEDMode_ForceOff("");
LimelightHelpers.setLEDMode_ForceBlink("");

4. 使用MegaTag进行场地定位

(查看MegaTag文档和Swerve姿态估计教程了解更多细节。)

// 在你的周期函数中:
LimelightHelpers.PoseEstimate limelightMeasurement = LimelightHelpers.getBotPoseEstimate_wpiBlue("limelight");
if (limelightMeasurement.tagCount >= 2) { // 只有看到多个标签时才信任测量值
m_poseEstimator.setVisionMeasurementStdDevs(VecBuilder.fill(0.7, 0.7, 9999999));
m_poseEstimator.addVisionMeasurement(
limelightMeasurement.pose,
limelightMeasurement.timestampSeconds
);
}

5. 使用MegaTag2进行场地定位

(查看MegaTag2文档和Swerve姿态估计教程了解更多细节。)

MegaTag2通过融合机器人方向数据和视觉来提高定位精度。通过提供陀螺仪数据,你可以帮助MegaTag2约束定位问题,即使只有一个标签可见也能提供出色的结果:

// 首先,告诉Limelight你的机器人当前的方向
double robotYaw = m_gyro.getYaw();
LimelightHelpers.SetRobotOrientation("", robotYaw, 0.0, 0.0, 0.0, 0.0, 0.0);

// 获取姿态估计
LimelightHelpers.PoseEstimate limelightMeasurement = LimelightHelpers.getBotPoseEstimate_wpiBlue("");

// 将其添加到你的姿态估计器
m_poseEstimator.setVisionMeasurementStdDevs(VecBuilder.fill(.5, .5, 9999999));
m_poseEstimator.addVisionMeasurement(
limelightMeasurement.pose,
limelightMeasurement.timestampSeconds
);

6. 特殊AprilTag功能

// 设置自定义裁剪窗口以提高性能(每个值为-1到1)
LimelightHelpers.setCropWindow("", -0.5, 0.5, -0.5, 0.5);

// 更改相对于机器人中心的相机姿态(x前进,y左侧,z向上,角度)
LimelightHelpers.setCameraPose_RobotSpace("",
0.5, // 前进偏移(米)
0.0, // 侧向偏移(米)
0.5, // 高度偏移(米)
0.0, // 横滚角(度)
30.0, // 俯仰角(度)
0.0 // 偏航角(度)
);

// 设置AprilTag偏移跟踪点(米)
LimelightHelpers.setFiducial3DOffset("",
0.0, // 前进偏移
0.0, // 侧向偏移
0.5 // 高度偏移
);

// 配置AprilTag检测
LimelightHelpers.SetFiducialIDFiltersOverride("", new int[]{1, 2, 3, 4}); // 只跟踪这些标签ID
LimelightHelpers.SetFiducialDownscalingOverride("", 2.0f); // 以半分辨率处理以提高帧率和减少范围

7. Python集成

与自定义Python SnapScripts通信:

// 发送数据到Python
double[] dataToSend = {1.0, 2.0, 3.0};
LimelightHelpers.setPythonScriptData("", dataToSend);

// 从Python获取数据
double[] dataFromPython = LimelightHelpers.getPythonScriptData("");

8. 从NetworkTables获取详细结果(原始目标)

为获得最佳性能,你可以直接从NetworkTables访问原始目标数据,绕过JSON解析:

// 获取原始AprilTag/基准点数据
RawFiducial[] fiducials = LimelightHelpers.getRawFiducials("");
for (RawFiducial fiducial : fiducials) {
int id = fiducial.id; // 标签ID
double txnc = fiducial.txnc; // X偏移(无准星)
double tync = fiducial.tync; // Y偏移(无准星)
double ta = fiducial.ta; // 目标区域
double distToCamera = fiducial.distToCamera; // 到相机的距离
double distToRobot = fiducial.distToRobot; // 到机器人的距离
double ambiguity = fiducial.ambiguity; // 标签姿态模糊度
}

// 获取原始神经网络检测器结果
RawDetection[] detections = LimelightHelpers.getRawDetections("");
for (RawDetection detection : detections) {
int classID = detection.classId;
double txnc = detection.txnc;
double tync = detection.tync;
double ta = detection.ta;
// 需要时访问角点坐标
double corner0X = detection.corner0_X;
double corner0Y = detection.corner0_Y;
// ... 角点1-3类似
}

9. 从JSON获取详细结果(Results对象)

Results对象提供对所有Limelight数据类型的全面访问。在RoboRIO上解析可能需要最多2毫秒,因此我们不建议在FRC中使用这种方法:

LimelightResults results = LimelightHelpers.getLatestResults("");
if (results.valid) {
// 颜色/反光目标
if (results.targets_Retro.length > 0) {
LimelightTarget_Retro target = results.targets_Retro[0];
double skew = target.ts; // 目标倾斜/旋转
double shortSide = target.short_side; // 最短边(像素)
double longSide = target.long_side; // 最长边(像素)
Pose3d targetPose = target.getCameraPose_TargetSpace();
}

// AprilTags/基准点
if (results.targets_Fiducials.length > 0) {
LimelightTarget_Fiducial tag = results.targets_Fiducials[0];
double id = tag.fiducialID; // 标签ID
String family = tag.fiducialFamily; // 标签族(如"16h5")

// 3D姿态数据
Pose3d robotPoseField = tag.getRobotPose_FieldSpace(); // 机器人在场地空间中的姿态
Pose3d cameraPoseTag = tag.getCameraPose_TargetSpace(); // 相机相对于标签的姿态
Pose3d robotPoseTag = tag.getRobotPose_TargetSpace(); // 机器人相对于标签的姿态
Pose3d tagPoseCamera = tag.getTargetPose_CameraSpace(); // 标签相对于相机的姿态
Pose3d tagPoseRobot = tag.getTargetPose_RobotSpace(); // 标签相对于机器人的姿态

// 2D目标数据
double tx = tag.tx; // 与准星的水平偏移
double ty = tag.ty; // 与准星的垂直偏移
double ta = tag.ta; // 目标区域(图像的0-100%)
}

// 神经网络检测
if (results.targets_Detector.length > 0) {
LimelightTarget_Detector detection = results.targets_Detector[0];
String className = detection.className;
double confidence = detection.confidence;
double area = detection.ta;
}

// 分类器结果
if (results.targets_Classifier.length > 0) {
LimelightTarget_Classifier result = results.targets_Classifier[0];
String class_name = result.className;
double confidence = result.confidence;
int classID = (int)result.classID;
}

// 条形码/二维码结果
if (results.targets_Barcode.length > 0) {
LimelightTarget_Barcode barcode = results.targets_Barcode[0];
String data = barcode.data;
String family = barcode.family;
}
}

10. 快照管理

拍摄快照用于离线管道调整:

// 拍摄快照以便稍后在网页界面查看
LimelightHelpers.takeSnapshot("", "auto_shot_1");

11. 其他功能

// 更改流模式
LimelightHelpers.setStreamMode_Standard(""); // 并排流
LimelightHelpers.setStreamMode_PiPMain(""); // 次要流在角落
LimelightHelpers.setStreamMode_PiPSecondary(""); // 主要流在角落

LimelightHelpers 静态方法

目标数据

public static boolean getTV(String limelightName)
public static double getTX(String limelightName)
public static double getTY(String limelightName)
public static double getTXNC(String limelightName)
public static double getTYNC(String limelightName)
public static double getTA(String limelightName)
public static double[] getT2DArray(String limelightName)
public static int getTargetCount(String limelightName)
public static RawFiducial[] getRawFiducials(String limelightName)
public static RawDetection[] getRawDetections(String limelightName)

神经网络结果

public static int getClassifierClassIndex(String limelightName)  
public static int getDetectorClassIndex(String limelightName)
public static String getClassifierClass(String limelightName)
public static String getDetectorClass(String limelightName)

姿态估计

public static PoseEstimate getBotPoseEstimate_wpiBlue(String limelightName)
public static PoseEstimate getBotPoseEstimate_wpiRed(String limelightName)
public static PoseEstimate getBotPoseEstimate_wpiBlue_MegaTag2(String limelightName)
public static PoseEstimate getBotPoseEstimate_wpiRed_MegaTag2(String limelightName)

public static Pose3d getBotPose3d(String limelightName)
public static Pose3d getBotPose3d_wpiRed(String limelightName)
public static Pose3d getBotPose3d_wpiBlue(String limelightName)
public static Pose3d getBotPose3d_TargetSpace(String limelightName)
public static Pose3d getCameraPose3d_TargetSpace(String limelightName)
public static Pose3d getTargetPose3d_CameraSpace(String limelightName)
public static Pose3d getTargetPose3d_RobotSpace(String limelightName)
public static Pose3d getCameraPose3d_RobotSpace(String limelightName)

public static Pose2d getBotPose2d(String limelightName)
public static Pose2d getBotPose2d_wpiBlue(String limelightName)
public static Pose2d getBotPose2d_wpiRed(String limelightName)

public static double[] getBotPose(String limelightName)
public static double[] getBotPose_wpiRed(String limelightName)
public static double[] getBotPose_wpiBlue(String limelightName)
public static double[] getBotPose_TargetSpace(String limelightName)
public static double[] getCameraPose_TargetSpace(String limelightName)
public static double[] getTargetPose_CameraSpace(String limelightName)
public static double[] getTargetPose_RobotSpace(String limelightName)

相机/管道配置

public static void setPipelineIndex(String limelightName, int pipelineIndex)
public static void setPriorityTagID(String limelightName, int ID)
public static double getCurrentPipelineIndex(String limelightName)
public static String getCurrentPipelineType(String limelightName)

public static void setLEDMode_PipelineControl(String limelightName)
public static void setLEDMode_ForceOff(String limelightName)
public static void setLEDMode_ForceBlink(String limelightName)
public static void setLEDMode_ForceOn(String limelightName)

public static void setStreamMode_Standard(String limelightName)
public static void setStreamMode_PiPMain(String limelightName)
public static void setStreamMode_PiPSecondary(String limelightName)

public static void setCropWindow(String limelightName, double cropXMin, double cropXMax, double cropYMin, double cropYMax)
public static void setCameraPose_RobotSpace(String limelightName, double forward, double side, double up, double roll, double pitch, double yaw)

高级AprilTag/基准标记设置

public static void setFiducial3DOffset(String limelightName, double offsetX, double offsetY, double offsetZ)
public static void SetRobotOrientation(String limelightName, double yaw, double yawRate, double pitch, double pitchRate, double roll, double rollRate)
public static void SetFiducialIDFiltersOverride(String limelightName, int[] validIDs)
public static void SetFiducialDownscalingOverride(String limelightName, float downscale)

结果和数据访问

public static double getLatency_Pipeline(String limelightName)
public static double getLatency_Capture(String limelightName)
public static double[] getTargetColor(String limelightName)
public static double getFiducialID(String limelightName)
public static String getNeuralClassID(String limelightName)
public static String[] getRawBarcodeData(String limelightName)
public static String getJSONDump(String limelightName)
public static LimelightResults getLatestResults(String limelightName)

Python脚本接口

public static void setPythonScriptData(String limelightName, double[] outgoingPythonData)
public static double[] getPythonScriptData(String limelightName)

实用方法

public static CompletableFuture<Boolean> takeSnapshot(String tableName, String snapshotName)
public static NetworkTable getLimelightNTTable(String tableName)
public static NetworkTableEntry getLimelightNTTableEntry(String tableName, String entryName)
public static double getLimelightNTDouble(String tableName, String entryName)
public static void setLimelightNTDouble(String tableName, String entryName, double val)
public static void setLimelightNTDoubleArray(String tableName, String entryName, double[] val)
public static double[] getLimelightNTDoubleArray(String tableName, String entryName)
public static String getLimelightNTString(String tableName, String entryName)
public static URL getLimelightURLString(String tableName, String request)

核心类

PoseEstimate

表示3D姿态估计

公共属性:

  • Pose2d pose - 估计的姿态
  • double timestampSeconds - 估计的时间戳
  • double latency - 处理延迟
  • int tagCount - 使用的标签数量
  • double tagSpan - 检测到的标签之间的跨度
  • double avgTagDist - 到标签的平均距离
  • double avgTagArea - 标签的平均面积
  • RawFiducial[] rawFiducials - 原始基准检测
  • boolean isMegaTag2 - 是否为MegaTag2结果

(NetworkTables衍生) RawFiducial

表示原始AprilTag/基准检测数据

公共属性:

  • int id - AprilTag ID号
  • double txnc - 相对相机中心的水平偏移(度)
  • double tync - 相对相机中心的垂直偏移(度)
  • double ta - 目标面积(图像的0-100%)
  • double distToCamera - 相机到目标的距离(米)
  • double distToRobot - 机器人到目标的距离(米)
  • double ambiguity - AprilTag姿态模糊度分数

(NetworkTables衍生) RawDetection

表示原始神经网络检测数据

公共属性:

  • int classId - 神经网络类别ID
  • double txnc - 相对相机中心的水平偏移(度)
  • double tync - 相对相机中心的垂直偏移(度)
  • double ta - 目标面积(图像的0-100%)
  • double corner0_X - 第一个角点X坐标
  • double corner0_Y - 第一个角点Y坐标
  • double corner1_X - 第二个角点X坐标
  • double corner1_Y - 第二个角点Y坐标
  • double corner2_X - 第三个角点X坐标
  • double corner2_Y - 第三个角点Y坐标
  • double corner3_X - 第四个角点X坐标
  • double corner3_Y - 第四个角点Y坐标

(JSON衍生) LimelightResults

包含Limelight的JSON输出的所有结果

公共属性:

  • String error - 错误信息(如果有)
  • double pipelineID - 当前管道索引
  • double latency_pipeline - 管道处理延迟(毫秒)
  • double latency_capture - 图像捕获延迟(毫秒)
  • double latency_jsonParse - JSON解析延迟(毫秒)
  • double timestamp_LIMELIGHT_publish - 数据发布时的时间戳
  • double timestamp_RIOFPGA_capture - RoboRIO FPGA捕获数据时的时间戳
  • boolean valid - 目标是否有效
  • double[] botpose - 场地空间中的机器人姿态
  • double[] botpose_wpired - WPILib红方联盟空间中的机器人姿态
  • double[] botpose_wpiblue - WPILib蓝方联盟空间中的机器人姿态
  • double botpose_tagcount - 用于姿态估计的标签数量
  • double botpose_span - 检测到的标签之间的跨度
  • double botpose_avgdist - 到检测标签的平均距离
  • double botpose_avgarea - 检测标签的平均面积
  • double[] camerapose_robotspace - 相对于机器人的相机姿态
  • LimelightTarget_Retro[] targets_Retro - 反光目标数组
  • LimelightTarget_Fiducial[] targets_Fiducials - AprilTag目标数组
  • LimelightTarget_Classifier[] targets_Classifier - 分类器结果数组
  • LimelightTarget_Detector[] targets_Detector - 检测器结果数组
  • LimelightTarget_Barcode[] targets_Barcode - 条形码结果数组

公共方法:

  • Pose3d getBotPose3d()
  • Pose3d getBotPose3d_wpiRed()
  • Pose3d getBotPose3d_wpiBlue()
  • Pose2d getBotPose2d()
  • Pose2d getBotPose2d_wpiRed()
  • Pose2d getBotPose2d_wpiBlue()

(JSON衍生) LimelightTarget_Retro

表示颜色/反光目标结果

公共属性:

  • double ta - 目标面积(图像的0-100%)
  • double tx - 从准星到目标的水平偏移(-29.8到29.8度)
  • double ty - 从准星到目标的垂直偏移(-24.85到24.85度)
  • double tx_pixels - 水平偏移(像素)
  • double ty_pixels - 垂直偏移(像素)
  • double tx_nocrosshair - 相对相机中心的水平偏移
  • double ty_nocrosshair - 相对相机中心的垂直偏移
  • double ts - 目标倾斜或旋转(-90到0度)

公共方法:

  • Pose3d getCameraPose_TargetSpace()
  • Pose3d getRobotPose_FieldSpace()
  • Pose3d getRobotPose_TargetSpace()
  • Pose3d getTargetPose_CameraSpace()
  • Pose3d getTargetPose_RobotSpace()
  • Pose2d getCameraPose_TargetSpace2D()
  • Pose2d getRobotPose_FieldSpace2D()
  • Pose2d getRobotPose_TargetSpace2D()
  • Pose2d getTargetPose_CameraSpace2D()
  • Pose2d getTargetPose_RobotSpace2D()

(JSON衍生) LimelightTarget_Fiducial

表示AprilTag/基准目标结果

公共属性:

  • double fiducialID - AprilTag ID号
  • String fiducialFamily - AprilTag系列类型
  • LimelightTarget_Retro的所有属性

公共方法:

  • LimelightTarget_Retro的所有方法

(JSON衍生) LimelightTarget_Barcode

表示条形码目标结果

公共属性:

  • String family - 条形码系列类型(如"QR"、"DataMatrix")
  • String data - 解码的条形码数据内容
  • double tx_pixels - 水平偏移(像素)
  • double ty_pixels - 垂直偏移(像素)
  • double tx - 相对准星的水平偏移
  • double ty - 相对准星的垂直偏移
  • double tx_nocrosshair - 相对相机中心的水平偏移
  • double ty_nocrosshair - 相对相机中心的垂直偏移
  • double ta - 目标面积
  • double[][] corners - 角点坐标

公共方法:

  • String getFamily()

(JSON衍生) LimelightTarget_Classifier

表示神经分类器管道结果

公共属性:

  • String className - 检测到的类别名称
  • double classID - 检测到的类别ID号
  • double confidence - 检测置信度(0-100%)
  • double zone - 检测区域
  • double tx - 相对准星的水平偏移
  • double ty - 相对准星的垂直偏移
  • double txp - 水平偏移(像素)
  • double typ - 垂直偏移(像素)

(JSON衍生) LimelightTarget_Detector

表示神经检测器管道结果

公共属性:

  • String className - 检测到的类别名称
  • double classID - 检测到的类别ID号
  • double confidence - 检测置信度(0-100%)
  • double ta - 目标面积
  • double tx - 相对准星的水平偏移
  • double ty - 相对准星的垂直偏移
  • double txp - 水平偏移(像素)
  • double typ - 垂直偏移(像素)
  • double tx_nocrosshair - 相对相机中心的水平偏移
  • double ty_nocrosshair - 相对相机中心的垂直偏移