Maurice 2025
Team 668's robot for Reefscape
Loading...
Searching...
No Matches
LimelightHelpers Class Reference

Static Public Member Functions

None flush ()
 
list[float] get_botpose (str limelight_name)
 
Pose2d get_botpose_2d (str limelight_name)
 
Pose2d get_botpose_2d_wpiblue (str limelight_name)
 
Pose2d get_botpose_2d_wpired (str limelight_name)
 
Pose3d get_botpose_3d (str limelight_name)
 
Pose3d get_botpose_3d_targetspace (str limelight_name)
 
Pose3d get_botpose_3d_wpiblue (str limelight_name)
 
Pose3d get_botpose_3d_wpired (str limelight_name)
 
PoseEstimate get_botpose_estimate_wpiblue (str limelight_name)
 
PoseEstimate get_botpose_estimate_wpiblue_megatag2 (str limelight_name)
 
PoseEstimate get_botpose_estimate_wpired (str limelight_name)
 
PoseEstimate get_botpose_estimate_wpired_megatag2 (str limelight_name)
 
list[float] get_botpose_targetspace (str limelight_name)
 
list[float] get_botpose_wpiblue (str limelight_name)
 
list[float] get_botpose_wpired (str limelight_name)
 
Pose3d get_camerapose_3d_robotspace (str limelight_name)
 
Pose3d get_camerapose_3d_targetspace (str limelight_name)
 
list[float] get_camerapose_robotspace (str limelight_name)
 
list[float] get_camerapose_targetspace (str limelight_name)
 
str get_classifier_class (str limelight_name)
 
float get_classifier_class_index (str limelight_name)
 
float get_current_pipeline_index (str limelight_name)
 
str get_current_pipeline_type (str limelight_name)
 
str get_detector_class (str limelight_name)
 
float get_detector_class_index (str limelight_name)
 
float get_fiducial_id (str limelight_name)
 
IMUData get_IMU_data (str limelight_name)
 
str get_JSON_dump (str limelight_name)
 
float get_latency_capture (str limelight_name)
 
float get_latency_pipeline (str limelight_name)
 
DoubleArrayEntry get_limelight_double_array_entry (str table_name, str entry_name)
 
float get_limelight_NTDouble (str table_name, str entry_name)
 
list[float] get_limelight_NTDoubleArray (str table_name, str entry_name)
 
str get_limelight_NTString (str table_name, str entry_name)
 
list[str] get_limelight_NTStringArray (str table_name, str entry_name)
 
NetworkTable get_limelight_NTTable (str table_name)
 
NetworkTableEntry get_limelight_NTTableEntry (str table_name, str entry_name)
 
ParseResult|None get_limelight_url_string (str table_name, str request)
 
str get_neural_class_id (str limelight_name)
 
list[float] get_python_script_data (str limelight_name)
 
list[str] get_raw_barcode_data (str limelight_name)
 
list[RawDetectionget_raw_detections (str limelight_name)
 
list[RawFiducialget_raw_fiducials (str limelight_name)
 
list[float] get_t2d_array (str limelight_name)
 
float get_ta (str limelight_name)
 
list[float] get_target_color (str limelight_name)
 
float get_target_count (str limelight_name)
 
Pose3d get_targetpose_3d_cameraspace (str limelight_name)
 
Pose3d get_targetpose_3d_robotspace (str limelight_name)
 
list[float] get_targetpose_cameraspace (str limelight_name)
 
list[float] get_targetpose_robotspace (str limelight_name)
 
bool get_tv (str limelight_name)
 
float get_tx (str limelight_name)
 
float get_txnc (str limelight_name)
 
float get_ty (str limelight_name)
 
float get_tync (str limelight_name)
 
list[float] pose_2d_to_array (Pose2d pose)
 
list[float] pose_3d_to_array (Pose3d pose)
 
None print_pose_estimate (PoseEstimate pose)
 
None set_camerapose_robotspace (str limelight_name, float forward, float side, float up, float roll, float pitch, float yaw)
 
None set_crop_window (str limelight_name, float crop_x_min, float crop_x_max, float crop_y_min, float crop_y_max)
 
None set_fiducial_3d_offset (str limelight_name, float x, float y, float z)
 
None set_fiducial_downscaling_override (str limelight_name, float downscale)
 
None set_fiducial_id_filters_override (str limelight_name, list[int] valid_ids)
 
None set_imu_mode (str limelight_name, int mode)
 
None set_LED_to_force_blink (str limelight_name)
 
None set_LED_to_force_off (str limelight_name)
 
None set_LED_to_force_on (str limelight_name)
 
None set_LED_to_pipeline_control (str limelight_name)
 
None set_limelight_NTDouble (str table_name, str entry_name, float val)
 
None set_limelight_NTDoubleArray (str table_name, str entry_name, list[float] val)
 
None set_pipeline_index (str limelight_name, int pipeline_index)
 
None set_priority_tag_id (str limelight_name, int tag_id)
 
None set_python_script_data (str limelight_name, list[float] outgoing_python_data)
 
None set_robot_orientation (str limelight_name, float yaw, float yaw_rate, float pitch, float pitch_rate, float roll, float roll_rate)
 
None set_robot_orientation_no_flush (str limelight_name, float yaw, float yaw_rate, float pitch, float pitch_rate, float roll, float roll_rate)
 
None set_stream_mode_to_PiPMain (str limelight_name)
 
None set_stream_mode_to_PiPSecondary (str limelight_name)
 
None set_stream_mode_to_standard (str limelight_name)
 
Pose2d to_Pose2D (list[float] in_data)
 
Pose3d to_Pose3D (list[float] in_data)
 
bool valid_pose_estimate (PoseEstimate pose)
 

Static Protected Member Functions

float _extract_array_entry (list[float] in_data, int position)
 
PoseEstimate _get_botpose_estimate (str limelight_name, str entry_name, bool is_megatag_2)
 
str _sanitize_name (str|None name)
 
None _set_robot_orientation (str limelight_name, float yaw, float yaw_rate, float pitch, float pitch_rate, float roll, float roll_rate, bool flush)
 

Static Protected Attributes

 _double_array_entries = ConcurrentDefaultDict(DoubleArrayEntry)
 

Detailed Description

    LimelightHelpers provides static methods and classes for interfacing with Limelight vision cameras in FRC.
    This library supports all Limelight features including AprilTag tracking, Neural Networks, and standard color/retroreflective tracking.

Member Function Documentation

◆ _extract_array_entry()

float _extract_array_entry ( list[float] in_data,
int position )
staticprotected

◆ _get_botpose_estimate()

PoseEstimate _get_botpose_estimate ( str limelight_name,
str entry_name,
bool is_megatag_2 )
staticprotected

◆ _sanitize_name()

str _sanitize_name ( str | None name)
staticprotected

◆ _set_robot_orientation()

None _set_robot_orientation ( str limelight_name,
float yaw,
float yaw_rate,
float pitch,
float pitch_rate,
float roll,
float roll_rate,
bool flush )
staticprotected

◆ flush()

None flush ( )
static

◆ get_botpose()

list[float] get_botpose ( str limelight_name)
static

◆ get_botpose_2d()

Pose2d get_botpose_2d ( str limelight_name)
static
        Gets the Pose2d for easy use with Odometry vision pose estimator
        (addVisionMeasurement)
        @param limelight_name
        @return Pose2d object

◆ get_botpose_2d_wpiblue()

Pose2d get_botpose_2d_wpiblue ( str limelight_name)
static
        Gets the Pose2d for easy use with Odometry vision pose estimator
        (addVisionMeasurement)
        @param limelight_name Name/identifier of the Limelight
        @return Pose2d object representing the robot's position and orientation in Blue Alliance field space

◆ get_botpose_2d_wpired()

Pose2d get_botpose_2d_wpired ( str limelight_name)
static
        Gets the Pose2d for easy use with Odometry vision pose estimator
        (addVisionMeasurement)
        @param limelight_name Name/identifier of the Limelight
        @return Pose2d object representing the robot's position and orientation in Red Alliance field space

◆ get_botpose_3d()

Pose3d get_botpose_3d ( str limelight_name)
static

◆ get_botpose_3d_targetspace()

Pose3d get_botpose_3d_targetspace ( str limelight_name)
static
        Gets the robot's 3D pose with respect to the currently tracked target's coordinate system.
        @param limelight_name Name/identifier of the Limelight
        @return Pose3d object representing the robot's position and orientation relative to the target

◆ get_botpose_3d_wpiblue()

Pose3d get_botpose_3d_wpiblue ( str limelight_name)
static
        (Recommended) Gets the robot's 3D pose in the WPILib Blue Alliance Coordinate System.
        @param limelight_name Name/identifier of the Limelight
        @return Pose3d object representing the robot's position and orientation in Blue Alliance field space

◆ get_botpose_3d_wpired()

Pose3d get_botpose_3d_wpired ( str limelight_name)
static
        (Not Recommended) Gets the robot's 3D pose in the WPILib Red Alliance Coordinate System.
        @param limelight_name Name/identifier of the Limelight
    @return Pose3d object representing the robot's position and orientation in Red Alliance field space

◆ get_botpose_estimate_wpiblue()

PoseEstimate get_botpose_estimate_wpiblue ( str limelight_name)
static
        Gets the MegaTag1 Pose2d and timestamp for use with WPILib pose estimator (addVisionMeasurement) in the WPILib Blue alliance coordinate system.
        @param limelight_name Name/identifier of the Limelight
        @return PoseEstimate object

◆ get_botpose_estimate_wpiblue_megatag2()

PoseEstimate get_botpose_estimate_wpiblue_megatag2 ( str limelight_name)
static
        Gets the MegaTag2 Pose2d and timestamp for use with WPILib pose estimator (addVisionMeasurement) in the WPILib Blue alliance coordinate system.
        Make sure you are calling setRobotOrientation() before calling this method.
        @param limelight_name Name/identifier of the Limelight
        @return PoseEstimate object

◆ get_botpose_estimate_wpired()

PoseEstimate get_botpose_estimate_wpired ( str limelight_name)
static
        Gets the MegaTag1 Pose2d and timestamp for use with WPILib pose estimator (addVisionMeasurement) in the WPILib Red alliance coordinate system.
        @param limelight_name Name/identifier of the Limelight
        @return PoseEstimate object

◆ get_botpose_estimate_wpired_megatag2()

PoseEstimate get_botpose_estimate_wpired_megatag2 ( str limelight_name)
static
        Gets the MegaTag2 Pose2d and timestamp for use with WPILib pose estimator (addVisionMeasurement) in the WPILib Red alliance coordinate system.
        Make sure you are calling setRobotOrientation() before calling this method.
        @param limelight_name Name/identifier of the Limelight
        @return PoseEstimate object

◆ get_botpose_targetspace()

list[float] get_botpose_targetspace ( str limelight_name)
static

◆ get_botpose_wpiblue()

list[float] get_botpose_wpiblue ( str limelight_name)
static

◆ get_botpose_wpired()

list[float] get_botpose_wpired ( str limelight_name)
static

◆ get_camerapose_3d_robotspace()

Pose3d get_camerapose_3d_robotspace ( str limelight_name)
static
        Gets the camera's 3D pose with respect to the robot's coordinate system.
        @param limelight_name Name/identifier of the Limelight
        @return Pose3d object representing the camera's position and orientation relative to the robot

◆ get_camerapose_3d_targetspace()

Pose3d get_camerapose_3d_targetspace ( str limelight_name)
static
        Gets the camera's 3D pose with respect to the currently tracked target's coordinate system.
        @param limelight_name Name/identifier of the Limelight
        @return Pose3d object representing the camera's position and orientation relative to the target

◆ get_camerapose_robotspace()

list[float] get_camerapose_robotspace ( str limelight_name)
static

◆ get_camerapose_targetspace()

list[float] get_camerapose_targetspace ( str limelight_name)
static

◆ get_classifier_class()

str get_classifier_class ( str limelight_name)
static
        Gets the current neural classifier result class name.
        @param limelight_name Name of the Limelight camera
    @return Class name string from classifier pipeline

◆ get_classifier_class_index()

float get_classifier_class_index ( str limelight_name)
static
        Gets the classifier class index from the currently running neural classifier pipeline
        @param limelight_name Name of the Limelight camera
        @return Class index from classifier pipeline

◆ get_current_pipeline_index()

float get_current_pipeline_index ( str limelight_name)
static
        Gets the active pipeline index.
        @param limelight_name Name of the Limelight camera
        @return Current pipeline index (0-9)

◆ get_current_pipeline_type()

str get_current_pipeline_type ( str limelight_name)
static
        Gets the current pipeline type.
        @param limelight_name Name of the Limelight camera
        @return Pipeline type string (e.g. "retro", "apriltag", etc.)

◆ get_detector_class()

str get_detector_class ( str limelight_name)
static
        Gets the primary neural detector result class name.
        @param limelight_name Name of the Limelight camera
        @return Class name string from detector pipeline

◆ get_detector_class_index()

float get_detector_class_index ( str limelight_name)
static
        Gets the detector class index from the primary result of the currently running neural detector pipeline.
        @param limelight_name Name of the Limelight camera
        @return Class index from detector pipeline

◆ get_fiducial_id()

float get_fiducial_id ( str limelight_name)
static

◆ get_IMU_data()

IMUData get_IMU_data ( str limelight_name)
static
        Gets the current IMU data from NetworkTables.
        IMU data is formatted as [robotYaw, Roll, Pitch, Yaw, gyroX, gyroY, gyroZ, accelX, accelY, accelZ].
        Returns all zeros if data is invalid or unavailable.
        @param limelight_name Name/identifier of the Limelight
        @return IMUData object containing all current IMU data

◆ get_JSON_dump()

str get_JSON_dump ( str limelight_name)
static
        Gets the full JSON results dump.
        @param limelight_name Name of the Limelight camera
    @return JSON string containing all current results

◆ get_latency_capture()

float get_latency_capture ( str limelight_name)
static
        Gets the capture latency.
        @param limelight_name Name of the Limelight camera
        @return Capture latency in milliseconds

◆ get_latency_pipeline()

float get_latency_pipeline ( str limelight_name)
static
        Gets the pipeline's processing latency contribution.
        @param limelight_name Name of the Limelight camera
        @return Pipeline latency in milliseconds

◆ get_limelight_double_array_entry()

DoubleArrayEntry get_limelight_double_array_entry ( str table_name,
str entry_name )
static

◆ get_limelight_NTDouble()

float get_limelight_NTDouble ( str table_name,
str entry_name )
static

◆ get_limelight_NTDoubleArray()

list[float] get_limelight_NTDoubleArray ( str table_name,
str entry_name )
static

◆ get_limelight_NTString()

str get_limelight_NTString ( str table_name,
str entry_name )
static

◆ get_limelight_NTStringArray()

list[str] get_limelight_NTStringArray ( str table_name,
str entry_name )
static

◆ get_limelight_NTTable()

NetworkTable get_limelight_NTTable ( str table_name)
static

◆ get_limelight_NTTableEntry()

NetworkTableEntry get_limelight_NTTableEntry ( str table_name,
str entry_name )
static

◆ get_limelight_url_string()

ParseResult | None get_limelight_url_string ( str table_name,
str request )
static

◆ get_neural_class_id()

str get_neural_class_id ( str limelight_name)
static

◆ get_python_script_data()

list[float] get_python_script_data ( str limelight_name)
static

◆ get_raw_barcode_data()

list[str] get_raw_barcode_data ( str limelight_name)
static

◆ get_raw_detections()

list[RawDetection] get_raw_detections ( str limelight_name)
static
        Gets the latest raw neural detector results from NetworkTables

        @param limelight_name Name/identifier of the Limelight
        @return Array of RawDetection objects containing detection details

◆ get_raw_fiducials()

list[RawFiducial] get_raw_fiducials ( str limelight_name)
static
        Gets the latest raw fiducial/AprilTag detection results from NetworkTables.

        @param limelight_name Name/identifier of the Limelight
        @return Array of RawFiducial objects containing detection details

◆ get_t2d_array()

list[float] get_t2d_array ( str limelight_name)
static
        T2D is an array that contains several targeting metrics
        @param limelight_name Name of the Limelight camera
        @return Array containing  [targetValid, targetCount, targetLatency, captureLatency, tx, ty, txnc, tync, ta, tid, targetClassIndexDetector,
        targetClassIndexClassifier, targetLongSidePixels, targetShortSidePixels, targetHorizontalExtentPixels, targetVerticalExtentPixels, targetSkewDegrees]

◆ get_ta()

float get_ta ( str limelight_name)
static
        Gets the target area as a percentage of the image (0-100%).
        @param limelight_name Name of the Limelight camera ("" for default)
        @return Target area percentage (0-100)

◆ get_target_color()

list[float] get_target_color ( str limelight_name)
static

◆ get_target_count()

float get_target_count ( str limelight_name)
static
        Gets the number of targets currently detected.
        @param limelight_name Name of the Limelight camera
        @return Number of detected targets

◆ get_targetpose_3d_cameraspace()

Pose3d get_targetpose_3d_cameraspace ( str limelight_name)
static
        Gets the target's 3D pose with respect to the camera's coordinate system.
        @param limelight_name Name/identifier of the Limelight
        @return Pose3d object representing the target's position and orientation relative to the camera

◆ get_targetpose_3d_robotspace()

Pose3d get_targetpose_3d_robotspace ( str limelight_name)
static
        Gets the target's 3D pose with respect to the robot's coordinate system.
        @param limelight_name Name/identifier of the Limelight
        @return Pose3d object representing the target's position and orientation relative to the robot
        :param limelight_name:
        :return:

◆ get_targetpose_cameraspace()

list[float] get_targetpose_cameraspace ( str limelight_name)
static

◆ get_targetpose_robotspace()

list[float] get_targetpose_robotspace ( str limelight_name)
static

◆ get_tv()

bool get_tv ( str limelight_name)
static
        Does the Limelight have a valid target?
        @param limelight_name Name of the Limelight camera ("" for default)
        @return True if a valid target is present, false otherwise

◆ get_tx()

float get_tx ( str limelight_name)
static
        Gets the horizontal offset from the crosshair to the target in degrees.
        @param limelight_name Name of the Limelight camera ("" for default)
        @return Horizontal offset angle in degrees

◆ get_txnc()

float get_txnc ( str limelight_name)
static
        Gets the horizontal offset from the principal pixel/point to the target in degrees.  This is the most accurate 2d metric if you are using a calibrated camera, and you don't need adjustable crosshair functionality.
        @param limelight_name Name of the Limelight camera ("" for default)
        @return Horizontal offset angle in degrees

◆ get_ty()

float get_ty ( str limelight_name)
static
        Gets the vertical offset from the crosshair to the target in degrees.
        @param limelight_name Name of the Limelight camera ("" for default)
        @return Vertical offset angle in degrees

◆ get_tync()

float get_tync ( str limelight_name)
static
        Gets the vertical offset from the principal pixel/point to the target in degrees. This is the most accurate 2d metric if you are using a calibrated camera, and you don't need adjustable crosshair functionality.
        @param limelight_name Name of the Limelight camera ("" for default)
        @return Vertical offset angle in degrees

◆ pose_2d_to_array()

list[float] pose_2d_to_array ( Pose2d pose)
static
        Converts a Pose2d object to an array of doubles in the format [x, y, z, roll, pitch, yaw].
        Translation components are in meters, rotation components are in degrees.
        Note: z, roll, and pitch will be 0 since Pose2d only contains x, y, and yaw.

        @param pose The Pose2d object to convert
        @return A 6-element array containing [x, y, 0, 0, 0, yaw]

◆ pose_3d_to_array()

list[float] pose_3d_to_array ( Pose3d pose)
static
        Converts a Pose3d object to an array of doubles in the format [x, y, z, roll, pitch, yaw].
        Translation components are in meters, rotation components are in degrees.

        @param pose The Pose3d object to convert
        @return A 6-element array containing [x, y, z, roll, pitch, yaw]

◆ print_pose_estimate()

None print_pose_estimate ( PoseEstimate pose)
static
        Prints detailed information about a PoseEstimate to standard output.
        Includes timestamp, latency, tag count, tag span, average tag distance,
        average tag area, and detailed information about each detected fiducial.

        @param pose The PoseEstimate object to print. If null, prints "No PoseEstimate available."

◆ set_camerapose_robotspace()

None set_camerapose_robotspace ( str limelight_name,
float forward,
float side,
float up,
float roll,
float pitch,
float yaw )
static
        Sets the camera pose relative to the robot.
        @param limelight_name Name/identifier of the Limelight
        @param forward offset in meters
        @param side offset in meters
        @param up offset in meters
        @param roll angle in degrees
        @param pitch angle in degrees
        @param yaw angle in degrees

◆ set_crop_window()

None set_crop_window ( str limelight_name,
float crop_x_min,
float crop_x_max,
float crop_y_min,
float crop_y_max )
static
        Sets the crop window for the camera. The crop window in the UI must be completely open.
        @param limelight_name Name/identifier of the Limelight
        @param crop_x_min Minimum X value (-1 to 1)
        @param crop_x_max Maximum X value (-1 to 1)
        @param crop_y_min Minimum Y value (-1 to 1)
        @param crop_y_max Maximum Y value (-1 to 1)

◆ set_fiducial_3d_offset()

None set_fiducial_3d_offset ( str limelight_name,
float x,
float y,
float z )
static
        Sets the 3D point-of-interest offset for the current fiducial pipeline.
        https://docs.limelightvision.io/docs/docs-limelight/pipeline-apriltag/apriltag-3d#point-of-interest-tracking
        @param limelight_name Name/identifier of the Limelight
        @param x offset in meters
        @param y offset in meters
        @param z offset in meters

◆ set_fiducial_downscaling_override()

None set_fiducial_downscaling_override ( str limelight_name,
float downscale )
static
        Sets the downscaling factor for AprilTag detection.
        Increasing downscale can improve performance at the cost of potentially reduced detection range.
        @param limelight_name Name/identifier of the Limelight
        @param downscale Valid values are 1.0 (no downscale), 1.5, 2.0, 3.0, 4.0. Set to 0 for pipeline control.

◆ set_fiducial_id_filters_override()

None set_fiducial_id_filters_override ( str limelight_name,
list[int] valid_ids )
static
        Overrides the valid AprilTag IDs that will be used for localization.
        Tags not in this list will be ignored for robot pose estimation.
        @param limelight_name Name/identifier of the Limelight
        @param valid_ids Array of valid AprilTag IDs to track

◆ set_imu_mode()

None set_imu_mode ( str limelight_name,
int mode )
static
        Configures the IMU mode for MegaTag2 Localization
        @param limelight_name Name/identifier of the Limelight
        @param mode IMU mode.

◆ set_LED_to_force_blink()

None set_LED_to_force_blink ( str limelight_name)
static

◆ set_LED_to_force_off()

None set_LED_to_force_off ( str limelight_name)
static

◆ set_LED_to_force_on()

None set_LED_to_force_on ( str limelight_name)
static

◆ set_LED_to_pipeline_control()

None set_LED_to_pipeline_control ( str limelight_name)
static
        Sets LED mode to be controlled by the current pipeline.
        @param limelight_name Name/identifier of the Limelight

◆ set_limelight_NTDouble()

None set_limelight_NTDouble ( str table_name,
str entry_name,
float val )
static

◆ set_limelight_NTDoubleArray()

None set_limelight_NTDoubleArray ( str table_name,
str entry_name,
list[float] val )
static

◆ set_pipeline_index()

None set_pipeline_index ( str limelight_name,
int pipeline_index )
static

◆ set_priority_tag_id()

None set_priority_tag_id ( str limelight_name,
int tag_id )
static

◆ set_python_script_data()

None set_python_script_data ( str limelight_name,
list[float] outgoing_python_data )
static

◆ set_robot_orientation()

None set_robot_orientation ( str limelight_name,
float yaw,
float yaw_rate,
float pitch,
float pitch_rate,
float roll,
float roll_rate )
static
        Sets robot orientation values used by MegaTag2 localization algorithm.
        @param limelight_name Name/identifier of the Limelight
        @param yaw Robot yaw in degrees. 0 = robot facing red alliance wall in FRC
        @param yaw_rate (Unnecessary) Angular velocity of robot yaw in degrees per second
        @param pitch (Unnecessary) Robot pitch in degrees
        @param pitch_rate (Unnecessary) Angular velocity of robot pitch in degrees per second
        @param roll (Unnecessary) Robot roll in degrees
        @param roll_rate (Unnecessary) Angular velocity of robot roll in degrees per second

◆ set_robot_orientation_no_flush()

None set_robot_orientation_no_flush ( str limelight_name,
float yaw,
float yaw_rate,
float pitch,
float pitch_rate,
float roll,
float roll_rate )
static

◆ set_stream_mode_to_PiPMain()

None set_stream_mode_to_PiPMain ( str limelight_name)
static
        Enables Picture-in-Picture mode with secondary stream in the corner.
        @param limelight_name Name/identifier of the Limelight

◆ set_stream_mode_to_PiPSecondary()

None set_stream_mode_to_PiPSecondary ( str limelight_name)
static
        Enables Picture-in-Picture mode with primary stream in the corner.
        @param limelight_name Name/identifier of the Limelight

◆ set_stream_mode_to_standard()

None set_stream_mode_to_standard ( str limelight_name)
static
        Enables standard side-by-side stream mode.
        @param limelight_name Name/identifier of the Limelight

◆ to_Pose2D()

Pose2d to_Pose2D ( list[float] in_data)
static
        Takes a 6-length array of pose data and converts it to a Pose2d object.
        Uses only x, y, and yaw components, ignoring z, roll, and pitch.
        Array format: [x, y, z, roll, pitch, yaw] where angles are in degrees.
        @param in_data Array containing pose data [x, y, z, roll, pitch, yaw]
        @return Pose2d object representing the pose, or empty Pose2d if invalid data

◆ to_Pose3D()

Pose3d to_Pose3D ( list[float] in_data)
static
        Takes a 6-length array of pose data and converts it to a Pose3d object.
        Array format: [x, y, z, roll, pitch, yaw] where angles are in degrees.
        @param in_data Array containing pose data [x, y, z, roll, pitch, yaw]
        @return Pose3d object representing the pose, or empty Pose3d if invalid data

◆ valid_pose_estimate()

bool valid_pose_estimate ( PoseEstimate pose)
static

Member Data Documentation

◆ _double_array_entries

_double_array_entries = ConcurrentDefaultDict(DoubleArrayEntry)
staticprotected

The documentation for this class was generated from the following file: