Photon Module
class PhotonModule(cameraName: String, val cameraPos: Transform3d, fieldLayout: AprilTagFieldLayout) : Camera
The PhotonModule class represents a single PhotonVision camera setup with its associated PhotonPoseEstimator and position information.
Integrates with WPILib 2026 vision estimation APIs for improved pose accuracy. Implements the Camera interface for unified vision system integration.
Usage Example:
val camera = PhotonModule(
cameraName = "frontCamera",
cameraPos = Transform3d(Translation3d(0.3, 0.0, 0.2), Rotation3d(0.0, Math.toRadians(-15.0), 0.0)),
fieldLayout = AprilTagFields.k2024Crescendo.loadAprilTagLayoutField()
)
// Get latest measurement
val measurement = camera.getLatestMeasurement()
measurement?.let {
swerveDrive.addVisionMeasurement(it.pose, it.timestampSeconds, it.stdDevs)
}Content copied to clipboard
Properties
Functions
Link copied to clipboard
Gets all unprocessed vision measurements since the last call.
Link copied to clipboard
Gets all unread PhotonPipelineResults from the PhotonCamera.
Link copied to clipboard
Gets the distance to a tag.
Link copied to clipboard
Gets the latest vision measurement from the camera.
Link copied to clipboard
Gets the latest PhotonPipelineResult from the camera.
Link copied to clipboard
Gets the horizontal offset to the currently tracked target.
Link copied to clipboard
Gets the vertical offset to the currently tracked target.
Link copied to clipboard
fun updateEstimatedStdDevs(result: PhotonPipelineResult, estimatedPose: EstimatedRobotPose?, singleTargetVector: Matrix<N3, N1> = DEFAULT_SINGLE_TARGET_STD_DEVS, multiTargetVector: Matrix<N3, N1> = DEFAULT_MULTI_TARGET_STD_DEVS)
Updates the estimated standard deviations based on the provided result.