diff --git a/photon-lib/py/photonlibpy/simulation/photonCameraSim.py b/photon-lib/py/photonlibpy/simulation/photonCameraSim.py index fb2fd7d74..bdff61012 100644 --- a/photon-lib/py/photonlibpy/simulation/photonCameraSim.py +++ b/photon-lib/py/photonlibpy/simulation/photonCameraSim.py @@ -4,8 +4,8 @@ import typing import cscore as cs import cv2 as cv import numpy as np -import robotpy_apriltag import wpilib +from robotpy_apriltag import AprilTagField, AprilTagFieldLayout from wpimath.geometry import Pose3d, Transform3d from wpimath.units import meters, seconds @@ -44,9 +44,7 @@ class PhotonCameraSim: self.videoSimProcEnabled: bool = True self.heartbeatCounter: int = 0 self.nextNtEntryTime = int(wpilib.Timer.getFPGATimestamp() * 1e6) - self.tagLayout = robotpy_apriltag.loadAprilTagLayoutField( - robotpy_apriltag.AprilTagField.k2024Crescendo - ) + self.tagLayout = AprilTagFieldLayout.loadField(AprilTagField.k2024Crescendo) if ( camera is not None diff --git a/photon-lib/py/setup.py b/photon-lib/py/setup.py index 00671380a..2c79e64c9 100644 --- a/photon-lib/py/setup.py +++ b/photon-lib/py/setup.py @@ -57,12 +57,12 @@ setup( packages=find_packages(), version=versionString, install_requires=[ - "numpy~=1.25", - "wpilib<2025,>=2024.0.0b2", - "robotpy-wpimath<2025,>=2024.0.0b2", - "robotpy-apriltag<2025,>=2024.0.0b2", - "robotpy-cscore<2025,>=2024.0.0.b2", - "pyntcore<2025,>=2024.0.0b2", + "numpy~=2.1", + "wpilib<2026,>=2025.0.0b1", + "robotpy-wpimath<2026,>=2025.0.0b1", + "robotpy-apriltag<2026,>=2025.0.0b1", + "robotpy-cscore<2026,>=2025.0.0b1", + "pyntcore<2026,>=2025.0.0b1", "robotpy-opencv;platform_machine=='roborio'", "opencv-python;platform_machine!='roborio'", ], diff --git a/photonlib-python-examples/poseest/robot.py b/photonlib-python-examples/poseest/robot.py index 9d82d17a0..800460c6e 100644 --- a/photonlib-python-examples/poseest/robot.py +++ b/photonlib-python-examples/poseest/robot.py @@ -28,7 +28,7 @@ import drivetrain import wpilib import wpimath.geometry from photonlibpy import PhotonCamera, PhotonPoseEstimator, PoseStrategy -from robotpy_apriltag import AprilTagField, loadAprilTagLayoutField +from robotpy_apriltag import AprilTagField, AprilTagFieldLayout kRobotToCam = wpimath.geometry.Transform3d( wpimath.geometry.Translation3d(0.5, 0.0, 0.5), @@ -43,7 +43,7 @@ class MyRobot(wpilib.TimedRobot): self.swerve = drivetrain.Drivetrain() self.cam = PhotonCamera("YOUR CAMERA NAME") self.camPoseEst = PhotonPoseEstimator( - loadAprilTagLayoutField(AprilTagField.k2024Crescendo), + AprilTagFieldLayout.loadField(AprilTagField.k2024Crescendo), PoseStrategy.LOWEST_AMBIGUITY, self.cam, kRobotToCam,