Skip to content

Commit

Permalink
Add high FPS so that quick tests don't make the harness fail
Browse files Browse the repository at this point in the history
  • Loading branch information
james-ward committed Nov 24, 2024
1 parent d43da28 commit f455a54
Show file tree
Hide file tree
Showing 2 changed files with 30 additions and 10 deletions.
2 changes: 1 addition & 1 deletion photon-lib/py/photonlibpy/simulation/photonCameraSim.py
Original file line number Diff line number Diff line change
Expand Up @@ -181,7 +181,7 @@ def consumeNextEntryTime(self) -> float | None:
"""
# check if this camera is ready for another frame update
now = wpilib.Timer.getFPGATimestamp()
timestamp = 0
timestamp = 0.0
iter = 0
# prepare next latest update
while now >= self.nextNtEntryTime:
Expand Down
38 changes: 29 additions & 9 deletions photon-lib/py/test/visionSystemSim_test.py
Original file line number Diff line number Diff line change
@@ -1,9 +1,8 @@
import math

import ntcore as nt
import pytest
from photonlibpy.estimation import TargetModel, VisionEstimation
from photonlibpy.photonCamera import PhotonCamera, setVersionCheckEnabled
from photonlibpy.photonCamera import PhotonCamera
from photonlibpy.simulation import PhotonCameraSim, VisionSystemSim, VisionTargetSim
from robotpy_apriltag import AprilTag, AprilTagFieldLayout
from wpimath.geometry import (
Expand All @@ -18,12 +17,6 @@
from wpimath.units import feetToMeters, meters


@pytest.fixture(autouse=True)
def setupCommon() -> None:
nt.NetworkTableInstance.getDefault().startServer()
setVersionCheckEnabled(False)


def test_VisibilityCupidShuffle() -> None:
targetPose = Pose3d(Translation3d(15.98, 0.0, 2.0), Rotation3d(0, 0, math.pi))

Expand All @@ -32,6 +25,8 @@ def test_VisibilityCupidShuffle() -> None:
cameraSim = PhotonCameraSim(camera)
visionSysSim.addCamera(cameraSim, Transform3d())

# Set massive FPS so timing isn't an issue
cameraSim.prop.setFPS(1e6)
cameraSim.prop.setCalibrationFromFOV(640, 480, fovDiag=Rotation2d.fromDegrees(80.0))

visionSysSim.addVisionTargets(
Expand Down Expand Up @@ -93,6 +88,8 @@ def test_NotVisibleVert1() -> None:
cameraSim = PhotonCameraSim(camera)
visionSysSim.addCamera(cameraSim, Transform3d())

# Set massive FPS so timing isn't an issue
cameraSim.prop.setFPS(1e6)
cameraSim.prop.setCalibrationFromFOV(640, 480, fovDiag=Rotation2d.fromDegrees(80.0))

visionSysSim.addVisionTargets(
Expand Down Expand Up @@ -128,6 +125,8 @@ def test_NotVisibleVert2() -> None:
cameraSim = PhotonCameraSim(camera)
visionSysSim.addCamera(cameraSim, robotToCamera)

# Set massive FPS so timing isn't an issue
cameraSim.prop.setFPS(1e6)
cameraSim.prop.setCalibrationFromFOV(
4774, 4774, fovDiag=Rotation2d.fromDegrees(80.0)
)
Expand Down Expand Up @@ -156,6 +155,8 @@ def test_NotVisibleTargetSize() -> None:
cameraSim = PhotonCameraSim(camera)
visionSysSim.addCamera(cameraSim, Transform3d())

# Set massive FPS so timing isn't an issue
cameraSim.prop.setFPS(1e6)
cameraSim.prop.setCalibrationFromFOV(640, 480, fovDiag=Rotation2d.fromDegrees(80.0))
cameraSim.setMinTargetAreaPixels(20.0)
visionSysSim.addVisionTargets(
Expand Down Expand Up @@ -183,6 +184,8 @@ def test_NotVisibleTooFarLeds() -> None:
cameraSim = PhotonCameraSim(camera)
visionSysSim.addCamera(cameraSim, Transform3d())

# Set massive FPS so timing isn't an issue
cameraSim.prop.setFPS(1e6)
cameraSim.prop.setCalibrationFromFOV(640, 480, fovDiag=Rotation2d.fromDegrees(80.0))
cameraSim.setMinTargetAreaPixels(1.0)
cameraSim.setMaxSightRange(10.0)
Expand Down Expand Up @@ -216,6 +219,9 @@ def test_YawAngles(expected_yaw) -> None:
cameraSim = PhotonCameraSim(camera)

visionSysSim.addCamera(cameraSim, Transform3d())

# Set massive FPS so timing isn't an issue
cameraSim.prop.setFPS(1e6)
cameraSim.prop.setCalibrationFromFOV(640, 480, fovDiag=Rotation2d.fromDegrees(80.0))
cameraSim.setMinTargetAreaPixels(0.0)
visionSysSim.addVisionTargets(
Expand Down Expand Up @@ -250,6 +256,9 @@ def test_PitchAngles(expected_pitch) -> None:
camera = PhotonCamera("camera")
cameraSim = PhotonCameraSim(camera)
visionSysSim.addCamera(cameraSim, Transform3d())

# Set massive FPS so timing isn't an issue
cameraSim.prop.setFPS(1e6)
cameraSim.prop.setCalibrationFromFOV(
640, 480, fovDiag=Rotation2d.fromDegrees(120.0)
)
Expand Down Expand Up @@ -316,8 +325,10 @@ def test_distanceCalc(distParam, pitchParam, heightParam) -> None:
)
camera = PhotonCamera("camera")
cameraSim = PhotonCameraSim(camera)

visionSysSim.addCamera(cameraSim, Transform3d())

# Set massive FPS so timing isn't an issue
cameraSim.prop.setFPS(1e6)
cameraSim.prop.setCalibrationFromFOV(
640, 480, fovDiag=Rotation2d.fromDegrees(160.0)
)
Expand Down Expand Up @@ -354,6 +365,9 @@ def test_MultipleTargets() -> None:
camera = PhotonCamera("camera")
cameraSim = PhotonCameraSim(camera)
visionSysSim.addCamera(cameraSim, Transform3d())

# Set massive FPS so timing isn't an issue
cameraSim.prop.setFPS(1e6)
cameraSim.prop.setCalibrationFromFOV(640, 480, fovDiag=Rotation2d.fromDegrees(80.0))
cameraSim.setMinTargetAreaPixels(20.0)

Expand Down Expand Up @@ -451,6 +465,9 @@ def test_PoseEstimation() -> None:
camera = PhotonCamera("camera")
cameraSim = PhotonCameraSim(camera)
visionSysSim.addCamera(cameraSim, Transform3d())

# Set massive FPS so timing isn't an issue
cameraSim.prop.setFPS(1e6)
cameraSim.prop.setCalibrationFromFOV(640, 480, fovDiag=Rotation2d.fromDegrees(90.0))
cameraSim.setMinTargetAreaPixels(20.0)

Expand Down Expand Up @@ -525,6 +542,9 @@ def test_PoseEstimationRotated() -> None:
camera = PhotonCamera("camera")
cameraSim = PhotonCameraSim(camera)
visionSysSim.addCamera(cameraSim, robotToCamera)

# Set massive FPS so timing isn't an issue
cameraSim.prop.setFPS(1e6)
cameraSim.prop.setCalibrationFromFOV(640, 480, fovDiag=Rotation2d.fromDegrees(90.0))
cameraSim.setMinTargetAreaPixels(20.0)

Expand Down

0 comments on commit f455a54

Please sign in to comment.