メインコンテンツまでスキップ

FRC プログラミング Limelight Lib を使用 (WPILib Java & C++)

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

使用方法

これは単一ファイルのライブラリです。最新のリリース(https://github.com/LimelightVision/limelightlib-wpijava/releases)からLimelightHelpers.javaファイルをコピーして、Javaプロジェクトの"robot"フォルダに配置するだけです。Limelightのオブジェクトを作成する必要はありません - このライブラリは使いやすさと信頼性を最大限に高めるためにシンプルで機能的に設計されています。

成功のためのヒント

  • シンプルに始めましょう!多くの成功しているFRCチームは基本的なアプローチを効果的に使用しています。例えば、2024年のチーム2056は、ゲームピースのトラッキングにニューラルネットワークの代わりに標準的な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が画像を処理する方法を即座に切り替えられるプログラムのようなものです。Webインターフェースで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はローカライゼーションの問題を制約し、1つのタグしか見えない場合でも優れた結果を提供します:

// まず、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から詳細な結果を取得(RawTargets)

最高のパフォーマンスを得るために、JSONパースを回避してNetworkTablesから直接生のターゲットデータにアクセスできます:

// 生のAprilTag/Fiducialデータを取得
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での解析に最大2msかかる可能性があるため、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/Fiducials
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;
}

// バーコード/QRコード結果
if (results.targets_Barcode.length > 0) {
LimelightTarget_Barcode barcode = results.targets_Barcode[0];
String data = barcode.data;
String family = barcode.family;
}
}

10. スナップショット管理

オフラインでのパイプライン調整用にスナップショットを撮影:

// 後でWebインターフェースで表示するためにスナップショットを撮影
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 - 第1コーナーのX座標
  • double corner0_Y - 第1コーナーのY座標
  • double corner1_X - 第2コーナーのX座標
  • double corner1_Y - 第2コーナーのY座標
  • double corner2_X - 第3コーナーのX座標
  • double corner2_Y - 第3コーナーのY座標
  • double corner3_X - 第4コーナーのX座標
  • double corner3_Y - 第4コーナーのY座標

(JSON由来) LimelightResults

LimelightのJSON出力からのすべての結果を含みます

パブリックプロパティ:

  • String error - エラーメッセージ(存在する場合)
  • double pipelineID - 現在のパイプラインインデックス
  • double latency_pipeline - パイプライン処理の遅延時間(ms)
  • double latency_capture - 画像キャプチャの遅延時間(ms)
  • double latency_jsonParse - JSON解析の遅延時間(ms)
  • 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 - カメラ中心からの垂直オフセット