Skip to content

Limelight

Read the official Limelight documentation here.

The limelight API is for interfacing with limelights in the robot code. It is a wrapper around the network tables API.

To create a limelight, you can use the following code:

wom::Limelight *limelight = new wom::Limelight("limelight name");

Parameters

TypeNameDescriptionSee Also
std::stringnameThe name of the limelight

Enums

LimelightTargetingData

NameDescriptionUsage
tvWhether the limelight has any valid targets (0 or 1)wom::LimelightTargetingData::kTv
txHorizontal Offset From Crosshair To Target (LL1: -27 degrees to 27 degrees / LL2: -29.8 to 29.8 degrees)wom::LimelightTargetingData::kTx
tyVertical Offset From Crosshair To Target (LL1: -20.5 degrees to 20.5 degrees / LL2: -24.85 to 24.85 degrees)wom::LimelightTargetingData::kTy
taTarget Area (0% of image to 100% of image)wom::LimelightTargetingData::kTa
tlThe pipeline’s latency contribution (ms). Add to “cl” to get total latency.wom::LimelightTargetingData::kTl
clCapture pipeline latency (ms). Time between the end of the exposure of the middle row of the sensor to the beginning of the tracking pipeline.wom::LimelightTargetingData::kCl
tshortSidelength of shortest side of the fitted bounding box (pixels)wom::LimelightTargetingData::kTshort
tlongSidelength of longest side of the fitted bounding box (pixels)wom::LimelightTargetingData::kTlong
thorHorizontal sidelength of the rough bounding box (0 - 320 pixels)wom::LimelightTargetingData::kThor
tvertVertical sidelength of the rough bounding box (0 - 320 pixels)wom::LimelightTargetingData::kTvert
getpipeTrue active pipeline index of the camera (0 .. 9)wom::LimelightTargetingData::kGetpipe
jsonFull JSON dump of targeting resultswom::LimelightTargetingData::kJson
tclassClass ID of primary neural detector result or neural classifier resultwom::LimelightTargetingData::kTclass
tcGet the average HSV color underneath the crosshair region as a NumberArraywom::LimelightTargetingData::kTc

LimelightAprilTagData

NameDescriptionUsage
botposeRobot transform in field-space. Translation (X,Y,Z) Rotation(Roll,Pitch,Yaw), total latency (cl+tl)wom::LimelightAprilTagData::kBotpose
botpose_wpiblueRobot transform in field-space (blue driverstation WPILIB origin). Translation (X,Y,Z) Rotation(Roll,Pitch,Yaw), total latency (cl+tl)wom::LimelightAprilTagData::kBotpose_wpiblue
botpose_wpiredRobot transform in field-space (red driverstation WPILIB origin). Translation (X,Y,Z) Rotation(Roll,Pitch,Yaw), total latency (cl+tl)wom::LimelightAprilTagData::kBotpose_wpired
camerapose_targetspace3D transform of the camera in the coordinate system of the primary in-view AprilTag (array (6))wom::LimelightAprilTagData::kCamerapose_targetspace
targetpose_cameraspace3D transform of the primary in-view AprilTag in the coordinate system of the Camera (array (6))wom::LimelightAprilTagData::kTargetpose_cameraspace
targetpose_robotspace3D transform of the primary in-view AprilTag in the coordinate system of the Robot (array (6))wom::LimelightAprilTagData::kTargetpose_robotspace
botpose_targetspace3D transform of the robot in the coordinate system of the primary in-view AprilTag (array (6))wom::LimelightAprilTagData::kBotpose_targetspace
camerapose_robotspace3D transform of the camera in the coordinate system of the robot (array (6))wom::LimelightAprilTagData::kCamerapose_robotspace
tid0The ID of the primary AprilTag in the imagewom::LimelightAprilTagData::kTid

LimelightLEDMode

NameDescriptionUsage
PipelineDefaultUse the LED Mode set in the current pipelinewom::LimelightLEDMode::kPipelineDefault
ForceOffForce the LEDs offwom::LimelightLEDMode::kForceOff
ForceBlinkForce the LEDs to blinkwom::LimelightLEDMode::kForceBlink
ForceOnForce the LEDs onwom::LimelightLEDMode::kForceOn

LimelightCamMode

NameDescriptionUsage
VisionProcessorVision processorwom::LimelightCamMode::kVisionProcessor
DriverCameraDriver camera (Increases exposure, disables vision processing)wom::LimelightCamMode::kDriverCamera

LimelightPipeline

NameDescriptionUsage
Pipeline0Pipeline 0wom::LimelightPipeline::kPipeline0
Pipeline1Pipeline 1wom::LimelightPipeline::kPipeline1
Pipeline2Pipeline 2wom::LimelightPipeline::kPipeline2
Pipeline3Pipeline 3wom::LimelightPipeline::kPipeline3
Pipeline4Pipeline 4wom::LimelightPipeline::kPipeline4
Pipeline5Pipeline 5wom::LimelightPipeline::kPipeline5
Pipeline6Pipeline 6wom::LimelightPipeline::kPipeline6
Pipeline7Pipeline 7wom::LimelightPipeline::kPipeline7
Pipeline8Pipeline 8wom::LimelightPipeline::kPipeline8
Pipeline9Pipeline 9wom::LimelightPipeline::kPipeline9

LimelightStreamMode

NameDescriptionUsage
StandardSide-by-side streams if a webcam is attached to Limelightwom::LimelightStreamMode::kStandard
PiPMainThe secondary camera stream is placed in the lower-right corner of the primary camera streamwom::LimelightStreamMode::kPiPMain
PiPSecondaryThe primary camera stream is placed in the lower-right corner of the secondary camera streamwom::LimelightStreamMode::kPiPSecondary

LimelightSnapshot

NameDescriptionUsage
ResetReset snapshot modewom::LimelightSnapshotMode::kReset
SingleTake two snapshots per secondwom::LimelightSnapshotMode::kSingle

Methods

GetName

Gets the name of the limelight.

std::string GetName();

GetOffset

Gets the offset of the limelight.

std::pair<double, double> GetOffset();

Example

std::pair<double, double> offset = limelight->GetOffset();

GetAprilTagData

Gets the AprilTag data from the limelight. The string that you pass in corresponds to the data that you want to fetch from it.

You can see all of the types of data here.

std::vector<double> GetAprilTagData(wom::LimelightAprilTagData dataType);

Example

std::vector<double> data = limelight->GetAprilTagData(wom::LimeLightAprilTagData::kBotpose);

GetTargetingData

Gets the targeting data from the limelight. The string that you pass in corresponds to the data that you want to fetch from it.

You can see all of the types of data here.

double GetTargetingData(wom::LimelightTargetingData, double defaultValue = 0.0)

Example

double data = limelight->GetTargetingData(wom::LimelightTargetingData::kTx);

SetLEDMode

Sets the LED mode of the limelight.

You can see all of the types of LED modes here.

void SetLEDMode(wom::LimelightLEDMode mode);

Example

limelight->SetLEDMode(wom::LimelightLEDMode::kForceOn);

SetCamMode

Sets the camera mode of the limelight.

You can see all of the types of camera modes here.

void SetCamMode(wom::LimelightCamMode mode);

Example

limelight->SetCamMode(wom::LimelightCamMode::kDriverCamera);

SetPipeline

Sets the pipeline of the limelight.

You can see all of the types of pipelines here.

void SetPipeline(wom::LimelightPipeline pipeline);

Example

limelight->SetPipeline(wom::LimelightPipeline::kPipeline0);

SetStreamMode

Sets the stream mode of the limelight.

You can see all of the types of stream modes here.

void SetStreamMode(wom::LimelightStreamMode mode);

Example

limelight->SetStreamMode(wom::LimelightStreamMode::kPiPMain);

SetSnapshot

Sets the snapshot mode of the limelight.

You can see all of the types of snapshot modes here.

void SetSnapshot(wom::LimelightSnapshot mode);

Example

limelight->SetSnapshot(wom::LimelightSnapshotMode::kSingle);

SetCrop

Sets the crop of the limelight.

void SetCrop(std::array<double, 4> crop);

Example

limelight->SetCrop({0.0, 0.0, 0.0, 0.0});

IsAtSetPoseVision

Checks if the limelight is at the set pose.

bool IsAtSetPoseVision(frc::Pose3d pose, units::second_t dt);

Example

bool isAtSetPose = limelight->IsAtSetPoseVision(frc::Pose3d(0_m, 0_m, 0_rad), 0_s);

GetSpeed

Gets the speed of the limelight between two poses.

units::meters_per_second_t GetSpeed(frc::Pose3d pose1, frc::Pose3d pose2, units::second_t dt);

Example

units::meters_per_second_t speed = limelight->GetSpeed(frc::Pose3d(0_m, 0_m, 0_rad), frc::Pose3d(0_m, 0_m, 0_rad), 0_s);

GetPose

Gets the pose of the limelight.

frc::Pose3d GetPose();

Example

frc::Pose3d pose = limelight->GetPose();