Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Break up masssive python overload hacks #1573

Merged
merged 4 commits into from
Nov 14, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
135 changes: 58 additions & 77 deletions photon-lib/py/photonlibpy/estimation/targetModel.py
Original file line number Diff line number Diff line change
Expand Up @@ -8,86 +8,67 @@


class TargetModel:
def __init__(
self,
*,
width: meters | None = None,
height: meters | None = None,
length: meters | None = None,
diameter: meters | None = None,
verts: List[Translation3d] | None = None
):

def __init__(self):
self.vertices: List[Translation3d] = []
self.isPlanar = False
self.isSpherical = False

if (
width is not None
and height is not None
and length is None
and diameter is None
and verts is None
):
self.isPlanar = True
self.isSpherical = False
self.vertices = [
Translation3d(0.0, -width / 2.0, -height / 2.0),
Translation3d(0.0, width / 2.0, -height / 2.0),
Translation3d(0.0, width / 2.0, height / 2.0),
Translation3d(0.0, -width / 2.0, height / 2.0),
]

return

elif (
length is not None
and width is not None
and height is not None
and diameter is None
and verts is None
):
verts = [
Translation3d(length / 2.0, -width / 2.0, -height / 2.0),
Translation3d(length / 2.0, width / 2.0, -height / 2.0),
Translation3d(length / 2.0, width / 2.0, height / 2.0),
Translation3d(length / 2.0, -width / 2.0, height / 2.0),
Translation3d(-length / 2.0, -width / 2.0, height / 2.0),
Translation3d(-length / 2.0, width / 2.0, height / 2.0),
Translation3d(-length / 2.0, width / 2.0, -height / 2.0),
Translation3d(-length / 2.0, -width / 2.0, -height / 2.0),
]
# Handle the rest of this in the "default" case
elif (
diameter is not None
and width is None
and height is None
and length is None
and verts is None
):
self.isPlanar = False
self.isSpherical = True
self.vertices = [
Translation3d(0.0, -diameter / 2.0, 0.0),
Translation3d(0.0, 0.0, -diameter / 2.0),
Translation3d(0.0, diameter / 2.0, 0.0),
Translation3d(0.0, 0.0, diameter / 2.0),
]
return
elif (
verts is not None
and width is None
and height is None
and length is None
and diameter is None
):
# Handle this in the "default" case
pass
else:
raise Exception("Not a valid overload")
@classmethod
def createPlanar(cls, width: meters, height: meters) -> Self:
tm = cls()

tm.isPlanar = True
tm.isSpherical = False
tm.vertices = [
Translation3d(0.0, -width / 2.0, -height / 2.0),
Translation3d(0.0, width / 2.0, -height / 2.0),
Translation3d(0.0, width / 2.0, height / 2.0),
Translation3d(0.0, -width / 2.0, height / 2.0),
]
return tm

@classmethod
def createCuboid(cls, length: meters, width: meters, height: meters) -> Self:
tm = cls()
verts = [
Translation3d(length / 2.0, -width / 2.0, -height / 2.0),
Translation3d(length / 2.0, width / 2.0, -height / 2.0),
Translation3d(length / 2.0, width / 2.0, height / 2.0),
Translation3d(length / 2.0, -width / 2.0, height / 2.0),
Translation3d(-length / 2.0, -width / 2.0, height / 2.0),
Translation3d(-length / 2.0, width / 2.0, height / 2.0),
Translation3d(-length / 2.0, width / 2.0, -height / 2.0),
Translation3d(-length / 2.0, -width / 2.0, -height / 2.0),
]

tm._common_construction(verts)

return tm

@classmethod
def createSpheroid(cls, diameter: meters) -> Self:
tm = cls()

tm.isPlanar = False
tm.isSpherical = True
tm.vertices = [
Translation3d(0.0, -diameter / 2.0, 0.0),
Translation3d(0.0, 0.0, -diameter / 2.0),
Translation3d(0.0, diameter / 2.0, 0.0),
Translation3d(0.0, 0.0, diameter / 2.0),
]

return tm

@classmethod
def createArbitrary(cls, verts: List[Translation3d]) -> Self:
tm = cls()
tm._common_construction(verts)

# TODO maybe remove this if there is a better/preferred way
# make the python type checking gods happy
assert verts is not None
return tm

def _common_construction(self, verts: List[Translation3d]) -> None:
self.isSpherical = False
if len(verts) <= 2:
self.vertices = []
Expand Down Expand Up @@ -132,8 +113,8 @@ def getIsSpherical(self) -> bool:

@classmethod
def AprilTag36h11(cls) -> Self:
return cls(width=6.5 * 0.0254, height=6.5 * 0.0254)
return cls.createPlanar(width=6.5 * 0.0254, height=6.5 * 0.0254)

@classmethod
def AprilTag16h5(cls) -> Self:
return cls(width=6.0 * 0.0254, height=6.0 * 0.0254)
return cls.createPlanar(width=6.0 * 0.0254, height=6.0 * 0.0254)
33 changes: 2 additions & 31 deletions photon-lib/py/photonlibpy/simulation/photonCameraSim.py
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@ class PhotonCameraSim:
def __init__(
self,
camera: PhotonCamera,
props: SimCameraProperties | None = None,
props: SimCameraProperties = SimCameraProperties.PERFECT_90DEG(),
minTargetAreaPercent: float | None = None,
maxSightRange: meters | None = None,
):
Expand All @@ -48,30 +48,6 @@ def __init__(
self.nextNtEntryTime = int(wpilib.Timer.getFPGATimestamp() * 1e6)
self.tagLayout = AprilTagFieldLayout.loadField(AprilTagField.k2024Crescendo)

if (
camera is not None
and props is None
and minTargetAreaPercent is None
and maxSightRange is None
):
props = SimCameraProperties.PERFECT_90DEG()
elif (
camera is not None
and props is not None
and minTargetAreaPercent is not None
and maxSightRange is not None
):
pass
elif (
camera is not None
and props is not None
and minTargetAreaPercent is None
and maxSightRange is None
):
pass
else:
raise Exception("Invalid Constructor Called")

self.cam = camera
self.prop = props
self.setMinTargetAreaPixels(PhotonCameraSim.kDefaultMinAreaPx)
Expand Down Expand Up @@ -104,12 +80,7 @@ def __init__(
self.ts.updateEntries()

# Handle this last explicitly for this function signature because the other constructor is called in the initialiser list
if (
camera is not None
and props is not None
and minTargetAreaPercent is not None
and maxSightRange is not None
):
if minTargetAreaPercent is not None and maxSightRange is not None:
self.minTargetAreaPercent = minTargetAreaPercent
self.maxSightRange = maxSightRange

Expand Down
100 changes: 41 additions & 59 deletions photon-lib/py/photonlibpy/simulation/simCameraProperties.py
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@


class SimCameraProperties:
def __init__(self, path: str | None = None, width: int = 0, height: int = 0):
def __init__(self):
self.resWidth: int = -1
self.resHeight: int = -1
self.camIntrinsics: np.ndarray = np.zeros((3, 3)) # [3,3]
Expand All @@ -24,59 +24,41 @@ def __init__(self, path: str | None = None, width: int = 0, height: int = 0):
self.latencyStdDev: seconds = 0.0
self.viewplanes: list[np.ndarray] = [] # [3,1]

if path is None:
self.setCalibration(960, 720, fovDiag=Rotation2d(math.radians(90.0)))
else:
raise Exception("not yet implemented")
self.setCalibrationFromFOV(960, 720, fovDiag=Rotation2d(math.radians(90.0)))

def setCalibrationFromFOV(
self, width: int, height: int, fovDiag: Rotation2d
) -> None:
if fovDiag.degrees() < 1.0 or fovDiag.degrees() > 179.0:
fovDiag = Rotation2d.fromDegrees(max(min(fovDiag.degrees(), 179.0), 1.0))
logging.error("Requested invalid FOV! Clamping between (1, 179) degrees...")

resDiag = math.sqrt(width * width + height * height)
diagRatio = math.tan(fovDiag.radians() / 2.0)
fovWidth = Rotation2d(math.atan((diagRatio * (width / resDiag)) * 2))
fovHeight = Rotation2d(math.atan(diagRatio * (height / resDiag)) * 2)

newDistCoeffs = np.zeros((8, 1))

cx = width / 2.0 - 0.5
cy = height / 2.0 - 0.5

fx = cx / math.tan(fovWidth.radians() / 2.0)
fy = cy / math.tan(fovHeight.radians() / 2.0)

newCamIntrinsics = np.array([[fx, 0.0, cx], [0.0, fy, cy], [0.0, 0.0, 1.0]])

self.setCalibrationFromIntrinsics(
width, height, newCamIntrinsics, newDistCoeffs
)

def setCalibration(
def setCalibrationFromIntrinsics(
self,
width: int,
height: int,
*,
fovDiag: Rotation2d | None = None,
newCamIntrinsics: np.ndarray | None = None,
newDistCoeffs: np.ndarray | None = None,
):
# Should be an inverted XOR on the args to differentiate between the signatures

has_fov_args = fovDiag is not None
has_matrix_args = newCamIntrinsics is not None and newDistCoeffs is not None

if (has_fov_args and has_matrix_args) or (
not has_matrix_args and not has_fov_args
):
raise Exception("not a correct function sig")

if has_fov_args:
# really convince python we are doing the right thing
assert fovDiag is not None
if fovDiag.degrees() < 1.0 or fovDiag.degrees() > 179.0:
fovDiag = Rotation2d.fromDegrees(
max(min(fovDiag.degrees(), 179.0), 1.0)
)
logging.error(
"Requested invalid FOV! Clamping between (1, 179) degrees..."
)

resDiag = math.sqrt(width * width + height * height)
diagRatio = math.tan(fovDiag.radians() / 2.0)
fovWidth = Rotation2d(math.atan((diagRatio * (width / resDiag)) * 2))
fovHeight = Rotation2d(math.atan(diagRatio * (height / resDiag)) * 2)

newDistCoeffs = np.zeros((8, 1))

cx = width / 2.0 - 0.5
cy = height / 2.0 - 0.5

fx = cx / math.tan(fovWidth.radians() / 2.0)
fy = cy / math.tan(fovHeight.radians() / 2.0)

newCamIntrinsics = np.array([[fx, 0.0, cx], [0.0, fy, cy], [0.0, 0.0, 1.0]])

# really convince python we are doing the right thing
assert newCamIntrinsics is not None
assert newDistCoeffs is not None
newCamIntrinsics: np.ndarray,
newDistCoeffs: np.ndarray,
) -> None:

self.resWidth = width
self.resHeight = height
Expand Down Expand Up @@ -357,7 +339,7 @@ def PERFECT_90DEG(cls) -> typing.Self:
@classmethod
def PI4_LIFECAM_320_240(cls) -> typing.Self:
prop = cls()
prop.setCalibration(
prop.setCalibrationFromIntrinsics(
320,
240,
newCamIntrinsics=np.array(
Expand Down Expand Up @@ -391,7 +373,7 @@ def PI4_LIFECAM_320_240(cls) -> typing.Self:
@classmethod
def PI4_LIFECAM_640_480(cls) -> typing.Self:
prop = cls()
prop.setCalibration(
prop.setCalibrationFromIntrinsics(
640,
480,
newCamIntrinsics=np.array(
Expand Down Expand Up @@ -425,7 +407,7 @@ def PI4_LIFECAM_640_480(cls) -> typing.Self:
@classmethod
def LL2_640_480(cls) -> typing.Self:
prop = cls()
prop.setCalibration(
prop.setCalibrationFromIntrinsics(
640,
480,
newCamIntrinsics=np.array(
Expand Down Expand Up @@ -459,7 +441,7 @@ def LL2_640_480(cls) -> typing.Self:
@classmethod
def LL2_960_720(cls) -> typing.Self:
prop = cls()
prop.setCalibration(
prop.setCalibrationFromIntrinsics(
960,
720,
newCamIntrinsics=np.array(
Expand Down Expand Up @@ -493,7 +475,7 @@ def LL2_960_720(cls) -> typing.Self:
@classmethod
def LL2_1280_720(cls) -> typing.Self:
prop = cls()
prop.setCalibration(
prop.setCalibrationFromIntrinsics(
1280,
720,
newCamIntrinsics=np.array(
Expand Down Expand Up @@ -527,7 +509,7 @@ def LL2_1280_720(cls) -> typing.Self:
@classmethod
def OV9281_640_480(cls) -> typing.Self:
prop = cls()
prop.setCalibration(
prop.setCalibrationFromIntrinsics(
640,
480,
newCamIntrinsics=np.array(
Expand Down Expand Up @@ -561,7 +543,7 @@ def OV9281_640_480(cls) -> typing.Self:
@classmethod
def OV9281_800_600(cls) -> typing.Self:
prop = cls()
prop.setCalibration(
prop.setCalibrationFromIntrinsics(
800,
600,
newCamIntrinsics=np.array(
Expand Down Expand Up @@ -595,7 +577,7 @@ def OV9281_800_600(cls) -> typing.Self:
@classmethod
def OV9281_1280_720(cls) -> typing.Self:
prop = cls()
prop.setCalibration(
prop.setCalibrationFromIntrinsics(
1280,
720,
newCamIntrinsics=np.array(
Expand Down Expand Up @@ -629,7 +611,7 @@ def OV9281_1280_720(cls) -> typing.Self:
@classmethod
def OV9281_1920_1080(cls) -> typing.Self:
prop = cls()
prop.setCalibration(
prop.setCalibrationFromIntrinsics(
1920,
1080,
newCamIntrinsics=np.array(
Expand Down
2 changes: 1 addition & 1 deletion photon-lib/py/test/openCVHelp_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -150,7 +150,7 @@ def test_SolvePNP_SQPNP():
# (for targets with arbitrary number of non-colinear points > 2)
target = VisionTargetSim(
Pose3d(Translation3d(5.0, 0.5, 1.0), Rotation3d(0.0, 0.0, math.pi)),
TargetModel(
TargetModel.createArbitrary(
verts=[
Translation3d(0.0, 0.0, 0.0),
Translation3d(1.0, 0.0, 0.0),
Expand Down
Loading
Loading