Package xbot.common.subsystems.vision
Class AprilTagVisionSubsystem
java.lang.Object
edu.wpi.first.wpilibj2.command.SubsystemBase
xbot.common.subsystems.vision.AprilTagVisionSubsystem
- All Implemented Interfaces:
Sendable
,Subsystem
,DataFrameRefreshable
@Singleton
public class AprilTagVisionSubsystem
extends SubsystemBase
implements DataFrameRefreshable
Subsystem for processing AprilTag vision data.
Based on the AdvantageKit sample implementation by team 6328.
-
Constructor Summary
ConstructorsConstructorDescriptionAprilTagVisionSubsystem
(PropertyFactory pf, AprilTagFieldLayout fieldLayout, XCameraElectricalContract contract, AprilTagVisionIOFactory visionIOFactory) -
Method Summary
Modifier and TypeMethodDescriptioncamerasWithTagVisible
(int tagId) Returns the set of cameras that can see the specified tag.List<xbot.common.subsystems.vision.AprilTagVisionCameraHelper>
Retrieves the set of cameras that should be used for pose estimationsGets all the pose observations in this iteration of the scheduler loop.getBestTargetId
(int cameraIndex) Returns the ID of the best target.int
Returns the number of cameras.getCameraPosition
(int cameraIndex) Gets the position of the camera relative to the robot.getLatestTargetObservation
(int cameraIndex) Returns the latest target observation.getTargetObservation
(int cameraIndex, int tagId) Returns the raw observation data for the specified target.getTargetX
(int cameraIndex) Returns the X angle to the best target, which can be used for simple servoing with vision.getTargetX
(int cameraIndex, int tagId) Returns the X angle to the specified target, which can be used for simple servoing with vision.boolean
isCameraConnected
(int cameraIndex) void
periodic()
void
Consumes and processes inputs from the device or subsystem.boolean
tagVisibleByAnyCamera
(int tagId) Returnstrue if any camera can see the specified tag.boolean
tagVisibleByCamera
(int cameraIndex, int tagId) Returnstrue if the camera can see the specified tag.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
-
Constructor Details
-
AprilTagVisionSubsystem
@Inject public AprilTagVisionSubsystem(PropertyFactory pf, AprilTagFieldLayout fieldLayout, XCameraElectricalContract contract, AprilTagVisionIOFactory visionIOFactory)
-
-
Method Details
-
getCameraCount
public int getCameraCount()Returns the number of cameras. -
getCameraPosition
Gets the position of the camera relative to the robot.- Parameters:
cameraIndex
- The index of the camera to use.- Returns:
- The 3D position of the camera relative to the robot.
-
getLatestTargetObservation
Returns the latest target observation.- Parameters:
cameraIndex
- The index of the camera to use.- Returns:
- The latest target observation.
-
getTargetX
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.
-
getTargetX
Returns the X angle to the specified target, which can be used for simple servoing with vision.- Parameters:
cameraIndex
- The index of the camera to use.tagId
- The tag to check.- Returns:
- The X angle to the specified target.
-
getBestTargetId
Returns the ID of the best target.- Parameters:
cameraIndex
- The index of the camera to use.- Returns:
- The ID of the best target.
-
getTargetObservation
public Optional<AprilTagVisionIO.TargetObservation> getTargetObservation(int cameraIndex, int tagId) Returns the raw observation data for the specified target.- Parameters:
cameraIndex
- The index of the camera to use.tagId
- The tag to check.- Returns:
- The raw observation data for the specified target.
-
tagVisibleByCamera
public boolean tagVisibleByCamera(int cameraIndex, int tagId) Returnstrue if the camera can see the specified tag.- Parameters:
cameraIndex
- The camera to check.tagId
- The tag to check.- Returns:
true if the camera can see the tag.
-
tagVisibleByAnyCamera
public boolean tagVisibleByAnyCamera(int tagId) Returnstrue if any camera can see the specified tag.- Parameters:
tagId
- The tag to check.- Returns:
true if any camera can see the tag.
-
camerasWithTagVisible
Returns the set of cameras that can see the specified tag.- Parameters:
tagId
- The tag to check.- Returns:
- The set of cameras that can see the tag.
-
isCameraConnected
public boolean isCameraConnected(int cameraIndex) -
getAllPoseCameras
Retrieves the set of cameras that should be used for pose estimations- Returns:
- The set of cameras that are meant for pose.
-
getAllPoseObservations
Gets all the pose observations in this iteration of the scheduler loop.- Returns:
- A list of pose observations.
-
refreshDataFrame
public void refreshDataFrame()Description copied from interface:DataFrameRefreshable
Consumes and processes inputs from the device or subsystem.- Specified by:
refreshDataFrame
in interfaceDataFrameRefreshable
-
periodic
public void periodic()
-