Limelight Lib ile FRC Programlama (WPILib Java & C++)
- https://github.com/LimelightVision/limelightlib-wpijava
- https://github.com/LimelightVision/limelightlib-wpicpp
JavaDocs: https://limelightlib-wpijava-reference.limelightvision.io
Kullanım
Bu tek dosyalı bir kütüphanedir. Tek yapmanız gereken, en son sürümdeki (https://github.com/LimelightVision/limelightlib-wpijava/releases) LimelightHelpers.java dosyasını Java projenizin "robot" klasörüne kopyalamaktır. Limelight'larınız için herhangi bir nesne oluşturmanıza gerek yoktur - kütüphane, kullanım kolaylığını ve güvenilirliği en üst düzeye çıkarmak için basit ve işlevseldir.
Başarı İpuçları
- Basit başlayın! Birçok başarılı FRC takımı temel yaklaşımları etkili bir şekilde kullanır. Örneğin, 2024'te 2056 numaralı takım, oyun parçası takibi için sinir ağları yerine standart 90FPS renk işlem hattı kullandı.
- Gerçekten neye ihtiyacınız olduğunu düşünün: Tam saha lokalizasyonuna mı ihtiyacınız var, yoksa basit hedef merkezleme (örneğin,
driveSpeed = result.getTx() * 0.03
) yeterli olur mu?
Temel Kavramlar
1. Temel Kullanım
Her metot bir Limelight isim parametresi kabul eder. "limelight" kullanmak için boş veya null bırakın:
// Temel hedefleme verileri
double tx = LimelightHelpers.getTX(""); // Hedefin nişangahtan yatay sapması (derece)
double ty = LimelightHelpers.getTY(""); // Hedefin nişangahtan dikey sapması (derece)
double ta = LimelightHelpers.getTA(""); // Hedef alanı (görüntünün %0 - %100'ü)
boolean hasTarget = LimelightHelpers.getTV(""); // Geçerli bir hedefiniz var mı?
double txnc = LimelightHelpers.getTXNC(""); // Hedefin ana piksel/noktadan yatay sapması (derece)
double tync = LimelightHelpers.getTYNC(""); // Hedefin ana piksel/noktadan dikey sapması (derece)
2. Pipeline Yönetimi
Pipeline'lar, Limelight'ın görüntüleri nasıl işlediğini değiştiren anında değiştirilebilir programlar gibidir. Web arayüzünde 10 farklı pipeline kurabilirsiniz:
// Pipeline 0'a geç
LimelightHelpers.setPipelineIndex("", 0);
3. LED Kontrolü
Parlak aydınlatma LED'lerine sahip Limelight'lar için, farklı durumlar için LED'leri kontrol edebilirsiniz:
// Mevcut pipeline'ın LED'leri kontrol etmesine izin ver
LimelightHelpers.setLEDMode_PipelineControl("");
// LED'leri zorla açık/kapalı/yanıp söner yap
LimelightHelpers.setLEDMode_ForceOn("");
LimelightHelpers.setLEDMode_ForceOff("");
LimelightHelpers.setLEDMode_ForceBlink("");
4. MegaTag ile Saha Konumlandırma
(Daha fazla detay için MegaTag dokümantasyonuna ve Swerve Konum Tahmini Öğreticisine bakın.)
// Periyodik fonksiyonunuzda:
LimelightHelpers.PoseEstimate limelightMeasurement = LimelightHelpers.getBotPoseEstimate_wpiBlue("limelight");
if (limelightMeasurement.tagCount >= 2) { // Sadece birden fazla etiket görüyorsak ölçüme güven
m_poseEstimator.setVisionMeasurementStdDevs(VecBuilder.fill(0.7, 0.7, 9999999));
m_poseEstimator.addVisionMeasurement(
limelightMeasurement.pose,
limelightMeasurement.timestampSeconds
);
}
5. MegaTag2 ile Saha Konumlandırma
(Daha fazla detay için MegaTag2 dokümantasyonuna ve Swerve Konum Tahmini Öğreticisine bakın.)
MegaTag2, robot yönelim verisini görüntü ile birleştirerek konumlandırma doğruluğunu artırır. Jiroskop verisi sağlayarak, MegaTag2'nin konumlandırma problemini sınırlamasına ve tek bir etiket görünür olsa bile mükemmel sonuçlar sağlamasına yardımcı olursunuz:
// Önce, Limelight'a robotunuzun mevcut yönelimini söyleyin
double robotYaw = m_gyro.getYaw();
LimelightHelpers.SetRobotOrientation("", robotYaw, 0.0, 0.0, 0.0, 0.0, 0.0);
// Konum tahminini al
LimelightHelpers.PoseEstimate limelightMeasurement = LimelightHelpers.getBotPoseEstimate_wpiBlue("");
// Konum tahmincisine ekle
m_poseEstimator.setVisionMeasurementStdDevs(VecBuilder.fill(.5, .5, 9999999));
m_poseEstimator.addVisionMeasurement(
limelightMeasurement.pose,
limelightMeasurement.timestampSeconds
);
6. Özel AprilTag İşlevselliği
// Gelişmiş performans için özel kırpma penceresi ayarla (her değer için -1 ile 1 arası)
LimelightHelpers.setCropWindow("", -0.5, 0.5, -0.5, 0.5);
// Robot merkezine göre kamera konumunu değiştir (x ileri, y sol, z yukarı, derece)
LimelightHelpers.setCameraPose_RobotSpace("",
0.5, // İleri offset (metre)
0.0, // Yan offset (metre)
0.5, // Yükseklik offset (metre)
0.0, // Yuvarlanma (derece)
30.0, // Yunuslama (derece)
0.0 // Sapma (derece)
);
// AprilTag offset takip noktasını ayarla (metre)
LimelightHelpers.setFiducial3DOffset("",
0.0, // İleri offset
0.0, // Yan offset
0.5 // Yükseklik offset
);
// AprilTag algılamayı yapılandır
LimelightHelpers.SetFiducialIDFiltersOverride("", new int[]{1, 2, 3, 4}); // Sadece bu etiket ID'lerini takip et
LimelightHelpers.SetFiducialDownscalingOverride("", 2.0f); // Gelişmiş kare hızı ve azaltılmış menzil için yarı çözünürlükte işle
7. Python Entegrasyonu
Özel Python SnapScripts ile iletişim kur:
// Python'a veri gönder
double[] dataToSend = {1.0, 2.0, 3.0};
LimelightHelpers.setPythonScriptData("", dataToSend);
// Python'dan veri al
double[] dataFromPython = LimelightHelpers.getPythonScriptData("");
8. NetworkTables'dan Detaylı Sonuçlar Alma (RawTargets)
Maksimum performans için, JSON ayrıştırmayı atlayarak ham hedef verilerine doğrudan NetworkTables'dan erişebilirsiniz:
// Ham AprilTag/Fiducial verilerini al
RawFiducial[] fiducials = LimelightHelpers.getRawFiducials("");
for (RawFiducial fiducial : fiducials) {
int id = fiducial.id; // Etiket ID'si
double txnc = fiducial.txnc; // X offset (nişangahsız)
double tync = fiducial.tync; // Y offset (nişangahsız)
double ta = fiducial.ta; // Hedef alanı
double distToCamera = fiducial.distToCamera; // Kameraya uzaklık
double distToRobot = fiducial.distToRobot; // Robota uzaklık
double ambiguity = fiducial.ambiguity; // Etiket poz belirsizliği
}
// Ham sinir ağı dedektör sonuçlarını al
RawDetection[] detections = LimelightHelpers.getRawDetections("");
for (RawDetection detection : detections) {
int classID = detection.classId;
double txnc = detection.txnc;
double tync = detection.tync;
double ta = detection.ta;
// Gerekirse köşe koordinatlarına eriş
double corner0X = detection.corner0_X;
double corner0Y = detection.corner0_Y;
// ... köşe 1-3 benzer şekilde mevcut
}
9. JSON'dan Detaylı Sonuçlar Alma (Results Nesnesi)
Results nesnesi tüm Limelight veri tiplerine kapsamlı erişim sağlar. RoboRIO'da ayrıştırması 2 ms'ye kadar sürebilir, bu yüzden FRC'de bu yaklaşımı önermiyoruz:
LimelightResults results = LimelightHelpers.getLatestResults("");
if (results.valid) {
// Renk/Retroreflektif hedefler
if (results.targets_Retro.length > 0) {
LimelightTarget_Retro target = results.targets_Retro[0];
double skew = target.ts; // Hedef eğimi/dönüşü
double shortSide = target.short_side; // En kısa kenar (piksel)
double longSide = target.long_side; // En uzun kenar (piksel)
Pose3d targetPose = target.getCameraPose_TargetSpace();
}
// AprilTags/Fiducials
if (results.targets_Fiducials.length > 0) {
LimelightTarget_Fiducial tag = results.targets_Fiducials[0];
double id = tag.fiducialID; // Etiket ID'si
String family = tag.fiducialFamily; // Etiket ailesi (örn. "16h5")
// 3B Poz Verileri
Pose3d robotPoseField = tag.getRobotPose_FieldSpace(); // Robotun saha uzayındaki pozu
Pose3d cameraPoseTag = tag.getCameraPose_TargetSpace(); // Kameranın etikete göre pozu
Pose3d robotPoseTag = tag.getRobotPose_TargetSpace(); // Robotun etikete göre pozu
Pose3d tagPoseCamera = tag.getTargetPose_CameraSpace(); // Etiketin kameraya göre pozu
Pose3d tagPoseRobot = tag.getTargetPose_RobotSpace(); // Etiketin robota göre pozu
// 2B hedefleme verileri
double tx = tag.tx; // Nişangahtan yatay sapma
double ty = tag.ty; // Nişangahtan dikey sapma
double ta = tag.ta; // Hedef alanı (görüntünün %0-100'ü)
}
// Sinir ağı algılamaları
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;
}
// Sınıflandırıcı sonuçları
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;
}
// Barkod/QR kod sonuçları
if (results.targets_Barcode.length > 0) {
LimelightTarget_Barcode barcode = results.targets_Barcode[0];
String data = barcode.data;
String family = barcode.family;
}
}
10. Anlık Görüntü Yönetimi
Çevrimdışı pipeline ayarlaması için anlık görüntüler alın:
// Web arayüzünde daha sonra görüntülemek için anlık görüntü al
LimelightHelpers.takeSnapshot("", "auto_shot_1");
11. Çeşitli İşlevler
// Yayın modlarını değiştir
LimelightHelpers.setStreamMode_Standard(""); // Yan yana yayınlar
LimelightHelpers.setStreamMode_PiPMain(""); // İkincil yayın köşede
LimelightHelpers.setStreamMode_PiPSecondary(""); // Ana yayın köşede
LimelightHelpers Statik Metodları
Hedef Verisi
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)
Sinir Ağı Sonuçları
public static int getClassifierClassIndex(String limelightName)
public static int getDetectorClassIndex(String limelightName)
public static String getClassifierClass(String limelightName)
public static String getDetectorClass(String limelightName)
Konum Tahmini
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)
Kamera/İşlem Hattı Yapılandırması
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)
Gelişmiş AprilTag/Fiducial Ayarları
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)
Sonuçlar ve Veri Erişimi
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 Script Arayüzü
public static void setPythonScriptData(String limelightName, double[] outgoingPythonData)
public static double[] getPythonScriptData(String limelightName)
Yardımcı Metodlar
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)
Temel Sınıflar
PoseEstimate
3B Poz Tahmini temsil eder
Genel Özellikler:
Pose2d pose
- Tahmin edilen pozdouble timestampSeconds
- Tahmin zaman damgasıdouble latency
- İşlem gecikmesiint tagCount
- Kullanılan etiket sayısıdouble tagSpan
- Algılanan etiketler arası mesafedouble avgTagDist
- Etiketlere ortalama uzaklıkdouble avgTagArea
- Etiketlerin ortalama alanıRawFiducial[] rawFiducials
- Ham fiducial algılamalarıboolean isMegaTag2
- MegaTag2 sonucu olup olmadığı
(NetworkTables-türetilmiş) RawFiducial
Ham AprilTag/Fiducial algılama verilerini temsil eder
Genel Özellikler:
int id
- AprilTag ID numarasıdouble txnc
- Kamera merkezinden yatay ofset (derece)double tync
- Kamera merkezinden dikey ofset (derece)double ta
- Hedef alanı (görüntünün %0-100'ü)double distToCamera
- Kameradan hedefe olan mesafe (metre)double distToRobot
- Robottan hedefe olan mesafe (metre)double ambiguity
- AprilTag poz belirsizlik skoru
(NetworkTables-türetilmiş) RawDetection
Ham sinir ağı algılama verilerini temsil eder
Genel Özellikler:
int classId
- Sinir ağı sınıf ID'sidouble txnc
- Kamera merkezinden yatay ofset (derece)double tync
- Kamera merkezinden dikey ofset (derece)double ta
- Hedef alanı (görüntünün %0-100'ü)double corner0_X
- Birinci köşe X koordinatıdouble corner0_Y
- Birinci köşe Y koordinatıdouble corner1_X
- İkinci köşe X koordinatıdouble corner1_Y
- İkinci köşe Y koordinatıdouble corner2_X
- Üçüncü köşe X koordinatıdouble corner2_Y
- Üçüncü köşe Y koordinatıdouble corner3_X
- Dördüncü köşe X koordinatıdouble corner3_Y
- Dördüncü köşe Y koordinatı
(JSON-türetilmiş) LimelightResults
Bir Limelight'ın JSON çıktısındaki tüm sonuçları içerir
Genel Özellikler:
String error
- Varsa hata mesajıdouble pipelineID
- Mevcut pipeline indeksidouble latency_pipeline
- Pipeline işlem gecikmesi (ms)double latency_capture
- Görüntü yakalama gecikmesi (ms)double latency_jsonParse
- JSON ayrıştırma gecikmesi (ms)double timestamp_LIMELIGHT_publish
- Verinin yayınlandığı zaman damgasıdouble timestamp_RIOFPGA_capture
- RoboRIO FPGA'nın veriyi yakaladığı zaman damgasıboolean valid
- Hedefin geçerli olup olmadığıdouble[] botpose
- Saha uzayında robot pozudouble[] botpose_wpired
- WPILib Kırmızı ittifak uzayında robot pozudouble[] botpose_wpiblue
- WPILib Mavi ittifak uzayında robot pozudouble botpose_tagcount
- Poz tahmini için kullanılan etiket sayısıdouble botpose_span
- Algılanan etiketler arası mesafedouble botpose_avgdist
- Algılanan etiketlere ortalama uzaklıkdouble botpose_avgarea
- Algılanan etiketlerin ortalama alanıdouble[] camerapose_robotspace
- Robota göre kamera pozuLimelightTarget_Retro[] targets_Retro
- Retroreflektif hedef dizisiLimelightTarget_Fiducial[] targets_Fiducials
- AprilTag hedef dizisiLimelightTarget_Classifier[] targets_Classifier
- Sınıflandırıcı sonuç dizisiLimelightTarget_Detector[] targets_Detector
- Dedektör sonuç dizisiLimelightTarget_Barcode[] targets_Barcode
- Barkod sonuç dizisi
Genel Metodlar:
Pose3d getBotPose3d()
Pose3d getBotPose3d_wpiRed()
Pose3d getBotPose3d_wpiBlue()
Pose2d getBotPose2d()
Pose2d getBotPose2d_wpiRed()
Pose2d getBotPose2d_wpiBlue()
(JSON-türetilmiş) LimelightTarget_Retro
Renk/Retroreflektif Hedef Sonucunu temsil eder
Genel Özellikler:
double ta
- Hedef alanı (görüntünün %0-100'ü)double tx
- Artı işaretinden hedefe yatay ofset (-29.8 ile 29.8 derece)double ty
- Artı işaretinden hedefe dikey ofset (-24.85 ile 24.85 derece)double tx_pixels
- Piksel cinsinden yatay ofsetdouble ty_pixels
- Piksel cinsinden dikey ofsetdouble tx_nocrosshair
- Kamera merkezinden yatay ofsetdouble ty_nocrosshair
- Kamera merkezinden dikey ofsetdouble ts
- Hedef eğimi veya dönüşü (-90 ile 0 derece)
Genel Metodlar:
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-türetilmiş) LimelightTarget_Fiducial
AprilTag/Fiducial Hedef Sonucunu temsil eder
Genel Özellikler:
double fiducialID
- AprilTag ID numarasıString fiducialFamily
- AprilTag aile tipi- LimelightTarget_Retro'dan tüm özellikler
Genel Metodlar:
- LimelightTarget_Retro'dan tüm metodlar
(JSON-türetilmiş) LimelightTarget_Barcode
Barkod Hedef Sonucunu temsil eder
Genel Özellikler:
String family
- Barkod aile tipi (örn. "QR", "DataMatrix")String data
- Çözümlenmiş barkod veri içeriğidouble tx_pixels
- Piksel cinsinden yatay ofsetdouble ty_pixels
- Piksel cinsinden dikey ofsetdouble tx
- Artı işaretinden yatay ofsetdouble ty
- Artı işaretinden dikey ofsetdouble tx_nocrosshair
- Kamera merkezinden yatay ofsetdouble ty_nocrosshair
- Kamera merkezinden dikey ofsetdouble ta
- Hedef alanıdouble[][] corners
- Köşe koordinatları
Genel Metodlar:
String getFamily()
(JSON-türetilmiş) LimelightTarget_Classifier
Sinir Ağı Sınıflandırıcı Pipeline Sonucunu temsil eder
Genel Özellikler:
String className
- Algılanan sınıf adıdouble classID
- Algılanan sınıf ID numarasıdouble confidence
- Algılama güveni (%0-100)double zone
- Algılama bölgesidouble tx
- Artı işaretinden yatay ofsetdouble ty
- Artı işaretinden dikey ofsetdouble txp
- Piksel cinsinden yatay ofsetdouble typ
- Piksel cinsinden dikey ofset
(JSON-türetilmiş) LimelightTarget_Detector
Sinir Ağı Dedektör Pipeline Sonucunu temsil eder
Genel Özellikler:
String className
- Algılanan sınıf adıdouble classID
- Algılanan sınıf ID numarasıdouble confidence
- Algılama güveni (%0-100)double ta
- Hedef alanıdouble tx
- Artı işaretinden yatay ofsetdouble ty
- Artı işaretinden dikey ofsetdouble txp
- Piksel cinsinden yatay ofsetdouble typ
- Piksel cinsinden dikey ofsetdouble tx_nocrosshair
- Kamera merkezinden yatay ofsetdouble ty_nocrosshair
- Kamera merkezinden dikey ofset