Pular para o conteúdo principal

API NetworkTables

O Limelight OS possui um Cliente NetworkTables 4. Ele se conecta automaticamente ao Servidor NetworkTables 4 em execução nos Robôs FRC com base no Número da Equipe / ID configurado na interface de Configurações.

Todos os dados são publicados em uma tabela que corresponde ao nome do dispositivo (ex: "limelight"). Se um hostname / apelido for atribuído à sua câmera, o nome da tabela corresponderá ao nome completo do limelight (ex: "limelight-top").

LimelightLib WPIJava e LimelightLib WPICPP interagem com dispositivos Limelight via NetworkTables.

Dados Básicos de Rastreamento

Use o seguinte código:

NetworkTableInstance.getDefault().getTable("limelight").getEntry("<variablename>").getDouble(0);

para obter estes dados:

chavetipodescrição
tvint1 se existir um alvo válido. 0 se não existirem alvos válidos
txdoubleDeslocamento Horizontal da Mira até o Alvo (LL1: -27 graus a 27 graus / LL2: -29.8 a 29.8 graus)
tydoubleDeslocamento Vertical da Mira até o Alvo (LL1: -20.5 graus a 20.5 graus / LL2: -24.85 a 24.85 graus)
txncdoubleDeslocamento Horizontal do Pixel Principal até o Alvo (graus)
tyncdoubleDeslocamento Vertical do Pixel Principal até o Alvo (graus)
tadoubleÁrea do Alvo (0% da imagem a 100% da imagem)
tldoubleContribuição de latência do pipeline (ms). Adicione a "cl" para obter a latência total.
cldoubleLatência do pipeline de captura (ms). Tempo entre o fim da exposição da linha central do sensor até o início do pipeline de rastreamento.
t2ddoubleArray contendo vários valores para estatísticas de timestamp sincronizado: [targetValid, targetCount, targetLatency, captureLatency, tx, ty, txnc, tync, ta, tid, targetClassIndexDetector , targetClassIndexClassifier, targetLongSidePixels, targetShortSidePixels, targetHorizontalExtentPixels, targetVerticalExtentPixels, targetSkewDegrees]
getpipeintÍndice real do pipeline ativo da câmera (0 .. 9)
getpipetypestringTipo de Pipeline ex: "pipe_color"
jsonstringDump JSON completo dos resultados de rastreamento. Deve ser habilitado por pipeline na aba 'output'
tclassstringNome da classe do resultado primário do detector neural ou resultado do classificador neural
tcdoubleArrayObtém a cor HSV média sob a região da mira (região de 3x3 pixels) como um NumberArray
hbdoubleValor de heartbeat. Aumenta uma vez por frame, reseta em 2 bilhões
hwdoubleArrayMétricas de HW [fps, temp cpu, uso de ram, temp]
crosshairsdoubleArrayMiras 2D [cx0, cy0, cx1, cy1]
tcclassstringNome da classe computada do pipeline classificador
tdclassstringNome da detecção primária do pipeline detector

AprilTag e Dados 3D

Use o seguinte código:

NetworkTableInstance.getDefault().getTable("limelight").getEntry("<variablename>").getDoubleArray(new double[6]);

para obter estes dados:

chavetipodescrição
botposedoubleArrayTransformação do robô no espaço do campo. Translação (X,Y,Z) em metros, Rotação(Roll,Pitch,Yaw) em graus, latência total (cl+tl), contagem de tags, extensão de tags, distância média das tags até a câmera, área média das tags (porcentagem da imagem)
botpose_wpibluedoubleArrayTransformação do robô no espaço do campo (origem WPILIB da estação de driver azul). Translação (X,Y,Z) em metros, Rotação(Roll,Pitch,Yaw) em graus, latência total (cl+tl), contagem de tags, extensão de tags, distância média das tags até a câmera, área média das tags (porcentagem da imagem)
botpose_wpireddoubleArrayTransformação do robô no espaço do campo (origem WPILIB da estação de driver vermelha). Translação (X,Y,Z) em metros, Rotação(Roll,Pitch,Yaw) em graus, latência total (cl+tl), contagem de tags, extensão de tags, distância média das tags até a câmera, área média das tags (porcentagem da imagem)
botpose_orbdoubleArrayTransformação do robô no espaço do campo (Megatag2). Translação (X,Y,Z) em metros, Rotação(Roll,Pitch,Yaw) em graus, latência total (cl+tl), contagem de tags, extensão de tags, distância média das tags até a câmera, área média das tags (porcentagem da imagem)
botpose_orb_wpibluedoubleArrayTransformação do robô no espaço do campo (Megatag2) (origem WPILIB da estação de driver azul). Translação (X,Y,Z) em metros, Rotação(Roll,Pitch,Yaw) em graus, latência total (cl+tl), contagem de tags, extensão de tags, distância média das tags até a câmera, área média das tags (porcentagem da imagem)
botpose_orb_wpireddoubleArrayTransformação do robô no espaço do campo (Megatag2) (origem WPILIB da estação de driver vermelha). Translação (X,Y,Z) em metros, Rotação(Roll,Pitch,Yaw) em graus, latência total (cl+tl), contagem de tags, extensão de tags, distância média das tags até a câmera, área média das tags (porcentagem da imagem)
camerapose_targetspacedoubleArrayTransformação 3D da câmera no sistema de coordenadas do AprilTag primário visível (array (6)) [tx, ty, tz, pitch, yaw, roll] (metros, graus)
targetpose_cameraspacedoubleArrayTransformação 3D do AprilTag primário visível no sistema de coordenadas da Câmera (array (6)) [tx, ty, tz, pitch, yaw, roll] (metros, graus)
targetpose_robotspacedoubleArrayTransformação 3D do AprilTag primário visível no sistema de coordenadas do Robô (array (6)) [tx, ty, tz, pitch, yaw, roll] (metros, graus)
botpose_targetspacedoubleArrayTransformação 3D do robô no sistema de coordenadas do AprilTag primário visível (array (6)) [tx, ty, tz, pitch, yaw, roll] (metros, graus)
camerapose_robotspacedoubleArrayTransformação 3D da câmera no sistema de coordenadas do robô (array (6))
tidintID do AprilTag primário visível
stddevsdoubleArrayDesvios Padrão MegaTag [MT1x, MT1y, MT1z, MT1roll, MT1pitch, MT1Yaw, MT2x, MT2y, MT2z, MT2roll, MT2pitch, MT2yaw]
camerapose_robotspace_setdoubleArrayDEFINE a pose da câmera no sistema de coordenadas do robô.
priorityidintDEFINE o ID necessário para rastreamento tx/ty. Ignora outros alvos. Não afeta a localização
robot_orientation_setdoubleArrayDEFINE a Orientação do Robô e velocidades angulares em graus e graus por segundo[yaw,yawrate,pitch,pitchrate,roll,rollrate]
fiducial_id_filters_setdoubleArraySobrescreve IDs de fiduciais válidos para localização (array)
fiducial_offset_setdoubleArrayDEFINE o Deslocamento do Ponto de Interesse 3D [x,y,z]

Controles da Câmera

Use o seguinte código:

NetworkTableInstance.getDefault().getTable("limelight").getEntry("<variablename>").setNumber(<value>);

para definir estes dados:

ledModeDefine o estado do LED do limelight
[0]usar o Modo de LED definido no pipeline atual
[1]forçar desligado
[2]forçar piscar
[3]forçar ligado
pipelineDefine o pipeline atual do limelight
0 .. 9Selecionar pipeline 0..9
streamDefine o modo de streaming do limelight
0Padrão - Streams lado a lado se uma webcam estiver conectada ao Limelight
1PiP Principal - O stream da câmera secundária é colocado no canto inferior direito do stream da câmera principal
2PiP Secundário - O stream da câmera principal é colocado no canto inferior direito do stream da câmera secundária
crop(Array) Define o retângulo de corte. O pipeline deve utilizar o retângulo de corte padrão na interface web. O array deve ter exatamente 4 entradas.
[0]X0 - Valor X Mín ou Máx do retângulo de corte (-1 a 1)
[1]X1 - Valor X Mín ou Máx do retângulo de corte (-1 a 1)
[2]Y0 - Valor Y Mín ou Máx do retângulo de corte (-1 a 1)
[3]Y1 - Valor Y Mín ou Máx do retângulo de corte (-1 a 1)
throttle_set(int) Recomendamos definir isso para 100-200 enquanto desabilitado. Define o número de frames a pular entre frames processados para reduzir o aumento de temperatura. As saídas não são zeradas durante frames pulados.
double[] cropValues = new double[4];
cropValues[0] = -1.0;
cropValues[1] = 1.0;
cropValues[2] = -1.0;
cropValues[3] = 1.0;
NetworkTableInstance.getDefault().getTable("limelight").getEntry("crop").setDoubleArray(cropValues);

Controles IMU

chavetipodescrição
imumode_setintDefine o imumode. 0 - usar imu externo, 1 - usar imu externo, alimentar imu interno, 2 - usar interno, 3 - usar interno com convergência assistida por MT1, 4 - usar IMU interno com convergência assistida por IMU externo
imuassistalpha_setdoubleAlpha / força do filtro complementar. Valores mais altos farão o imu interno convergir para a fonte de assistência mais rapidamente. O padrão é definido para um valor baixo 0.001 porque agora confiamos mais no IMU interno do que antes. Os modos de assistência são construídos para "puxar" muito suavemente o imu interno em direção à fonte de assistência escolhida.

Python

Scripts Python permitem dados de entrada e saída arbitrários.

llpythonNumberArray enviado por scripts python. Isso é acessível dentro do código do robô.
llrobotNumberArray enviado pelo robô. Isso é acessível dentro dos SnapScripts python.

Dados Brutos

Cantos:

Habilite "send contours" na aba "Output" para transmitir coordenadas de cantos:

tcornxyArray de números com coordenadas de cantos [x0,y0,x1,y1......]

Alvos Brutos:

O Limelight publica três contornos brutos no NetworkTables que não são influenciados pelo seu modo de agrupamento. Ou seja, eles são filtrados com os parâmetros do seu pipeline, mas nunca agrupados. X e Y são retornados em espaço de tela normalizado (-1 a 1) em vez de graus.

rawtargets[txnc,tync,ta,txnc2,tync2,ta2....]

Fiduciais Brutos:

Obtém todos os fiduciais válidos (não filtrados)

rawfiducials [id, txnc, tync, ta, distToCamera, distToRobot, ambiguity, id2.....]

Detecções Brutas:

Obtém todos os resultados de detecção neural válidos (não filtrados)

rawdetections [id, txnc, tync, ta, corner0x, corner0y, corner1x, corner1y, corner2x, corner2y, corner3x, corner3y, id2.....]

Códigos de Barras Brutos:

Obtém todos os resultados de código de barras válidos (não filtrados)

rawbarcodes array de strings com dados de código de barras