Class LibVisionSubsystem
java.lang.Object
edu.wpi.first.wpilibj2.command.SubsystemBase
com.flarerobotics.lib.subsystem.vision.LibVisionSubsystem
- All Implemented Interfaces:
edu.wpi.first.util.sendable.Sendable
,edu.wpi.first.wpilibj2.command.Subsystem
public class LibVisionSubsystem
extends edu.wpi.first.wpilibj2.command.SubsystemBase
A preset vision subsystem used for robot localization via AprilTags. Supports Limelight,
Photon and Photon Simulation.
-
Nested Class Summary
Nested ClassesModifier and TypeClassDescriptionstatic interface
The consumer functional interface for the addVisionMeasurement method. -
Field Summary
FieldsModifier and TypeFieldDescriptionstatic final RectangularRegion
The region representing the rectangular field.static final edu.wpi.first.apriltag.AprilTagFieldLayout
The AprilTag layout of the field. -
Constructor Summary
ConstructorsConstructorDescriptionLibVisionSubsystem
(LibVisionSubsystem.VisionConsumer addMeasurement, LibVisionIO... cameras) Constructs a new LibVisionSubsystem. -
Method Summary
Modifier and TypeMethodDescriptioncom.flarerobotics.lib.subsystem.vision.VisionIOInputsAutoLogged[]
Returns the camera inputs.Returns the cameras as an IO interface array.boolean
getTV()
Returns whether the vision detects a valid target.boolean
getTV
(int cameraIndex) Returns whether the vision detects a valid target.edu.wpi.first.math.geometry.Rotation2d
getTX
(int cameraIndex) Returns the X angle to the best target, which can be used for simple servoing with vision.edu.wpi.first.math.geometry.Rotation2d
getTY
(int cameraIndex) Returns the Y angle to the best target, which can be used for simple servoing with vision.void
periodic()
void
setAngularStdDevBaseline
(double baseline) Sets the baseline for the angular standard deviations.void
setAngularStdDevFactor_MT2
(double factor) Sets the angular standard deviations factor applied for MegaTag2.void
setCameraStdDevFactors
(double[] factors) Sets the standard deviation factors for each camera in the same order it was provided in the constructor.void
setLinearStdDevBaseline
(double baseline) Sets the baseline for the linear standard deviations.void
setLinearStdDevFactor_MT2
(double factor) Sets the linear deviations factor applied for MegaTag2.void
setMaxAmbiguity
(double max) Sets the maximum ambiguity for the robot's pose.void
setMaxHeight
(edu.wpi.first.units.measure.Distance height) Sets the height threshold (invalidation point) for the vision pose.Methods inherited from class edu.wpi.first.wpilibj2.command.SubsystemBase
addChild, getName, getSubsystem, initSendable, setName, setSubsystem
Methods inherited from class java.lang.Object
clone, equals, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, wait
Methods inherited from interface edu.wpi.first.wpilibj2.command.Subsystem
defer, getCurrentCommand, getDefaultCommand, register, removeDefaultCommand, run, runEnd, runOnce, setDefaultCommand, simulationPeriodic, startEnd, startRun
-
Field Details
-
kLayout
public static final edu.wpi.first.apriltag.AprilTagFieldLayout kLayoutThe AprilTag layout of the field. -
kFieldRegion
The region representing the rectangular field.
-
-
Constructor Details
-
LibVisionSubsystem
Constructs a new LibVisionSubsystem.- Parameters:
addMeasurement
- The consumer to add a vision measurement. Recommended to use a WPILib pose estimator.cameras
- The IO interfaces to provide for each individual camera.
-
-
Method Details
-
periodic
public void periodic() -
getTX
public edu.wpi.first.math.geometry.Rotation2d getTX(int cameraIndex) Returns the X angle to the best target, which can be used for simple servoing with vision.- Parameters:
cameraIndex
- The index of the camera to use.- Returns:
- The X angle to the bast target.
-
getTY
public edu.wpi.first.math.geometry.Rotation2d getTY(int cameraIndex) Returns the Y angle to the best target, which can be used for simple servoing with vision.- Parameters:
cameraIndex
- The index of the camera to use.- Returns:
- The Y angle to the best target.
-
getTV
public boolean getTV()Returns whether the vision detects a valid target.- Returns:
- True if a valid target is detected.
-
getTV
public boolean getTV(int cameraIndex) Returns whether the vision detects a valid target.- Parameters:
cameraIndex
- The index of the camera.- Returns:
- True if a valid target is detected.
-
getCamerasIO
Returns the cameras as an IO interface array.- Returns:
- The camera array.
-
getCameraInputs
public com.flarerobotics.lib.subsystem.vision.VisionIOInputsAutoLogged[] getCameraInputs()Returns the camera inputs.- Returns:
- The input array.
-
setMaxHeight
public void setMaxHeight(edu.wpi.first.units.measure.Distance height) Sets the height threshold (invalidation point) for the vision pose. Defaults to 1 meter.- Parameters:
height
- The max height.
-
setMaxAmbiguity
public void setMaxAmbiguity(double max) Sets the maximum ambiguity for the robot's pose. Defaults to 0.3.- Parameters:
max
- The maximum ambiguity.
-
setLinearStdDevBaseline
public void setLinearStdDevBaseline(double baseline) Sets the baseline for the linear standard deviations. Defaults to 0.02.Standard deviations are for 1 meter distance and 1 tag. Is adjusted automatically based on distance and the number of tags.
- Parameters:
baseline
- The baseline.
-
setAngularStdDevBaseline
public void setAngularStdDevBaseline(double baseline) Sets the baseline for the angular standard deviations. Defaults to 0.06.Standard deviations are for 1 meter distance and 1 tag. Is adjusted automatically based on distance and the number of tags.
- Parameters:
baseline
- The baseline.
-
setLinearStdDevFactor_MT2
public void setLinearStdDevFactor_MT2(double factor) Sets the linear deviations factor applied for MegaTag2. Defaults to 0.5.- Parameters:
factor
- The factor.
-
setAngularStdDevFactor_MT2
public void setAngularStdDevFactor_MT2(double factor) Sets the angular standard deviations factor applied for MegaTag2. Defaults to Infinity.- Parameters:
factor
- The factor.
-
setCameraStdDevFactors
public void setCameraStdDevFactors(double[] factors) Sets the standard deviation factors for each camera in the same order it was provided in the constructor.- Parameters:
factors
- The factors.
-