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

Add python simulation #1532

Merged
merged 82 commits into from
Nov 10, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
82 commits
Select commit Hold shift + click to select a range
4b132fc
create stub module and fill in most of SimCameraProperties
LucienMorey Nov 5, 2024
cbfa745
Rename VisionTargetSystem
james-ward Nov 6, 2024
dc095a6
Stub PhotoCameraSim methods
james-ward Nov 6, 2024
817bb45
Raise exception for unimplemented methods
james-ward Nov 6, 2024
1657ee3
Add blank TargetModel class
james-ward Nov 6, 2024
ec894a4
Implement VisionTargetSim
james-ward Nov 6, 2024
24eb29d
Add generating functions for AprilTag target types
james-ward Nov 6, 2024
159e8ba
WIP: VisionSystemSim
james-ward Nov 6, 2024
5a3e0f4
Trivial interpolation implementation + minor bugfixes
james-ward Nov 6, 2024
61c0c33
fix capitalisation on geometry methods
LucienMorey Nov 6, 2024
9df553e
fill in targetModel class
LucienMorey Nov 6, 2024
5f04b31
fix python list type issue
LucienMorey Nov 6, 2024
b8d2e4c
fix improperly constructed Pose3d
LucienMorey Nov 6, 2024
7f9d9fe
fix incorrect return type for resetCameraTransforms
LucienMorey Nov 6, 2024
964eea2
ensure data is not none if it is to be used
LucienMorey Nov 6, 2024
b73ffc1
remove rogue import
LucienMorey Nov 6, 2024
ce459a0
rename member var
LucienMorey Nov 6, 2024
0c85851
format and fix temp exception syntax
LucienMorey Nov 6, 2024
c1605b5
fill in canSeeCorner method
LucienMorey Nov 6, 2024
ba0a9ab
fill in consumeNextEntryTime
LucienMorey Nov 6, 2024
628b216
fix capitalisation in targetModel
LucienMorey Nov 6, 2024
f5c95d3
add cameraTargetRelation class
LucienMorey Nov 6, 2024
c372827
add NTTopicSet class
LucienMorey Nov 6, 2024
f0c189e
add cscore dependency for sim things
LucienMorey Nov 6, 2024
6c41c21
fix missing self arg
LucienMorey Nov 6, 2024
c53f99e
fill in canSeeTargetPose
LucienMorey Nov 6, 2024
c263f02
formatting
LucienMorey Nov 6, 2024
75d6b1c
work on constuctor and submitProcessedFrame
LucienMorey Nov 6, 2024
d213f3a
fix up capitalisation in VisionTargetSim
LucienMorey Nov 6, 2024
0d96c25
update nt connection construction method
LucienMorey Nov 6, 2024
badeee1
Add additional helper classes
james-ward Nov 7, 2024
381792c
Make tag definitions class members
james-ward Nov 7, 2024
3b1da63
Correctly access subtable
james-ward Nov 7, 2024
a0c215c
Fix minor typos
james-ward Nov 7, 2024
faf20f7
Use numpy arrays in calculations
james-ward Nov 7, 2024
5934d86
Implement process method
james-ward Nov 7, 2024
3456f90
Remove completed TODO
james-ward Nov 7, 2024
1521822
Use RotTrlTransform3d
james-ward Nov 7, 2024
348e87a
Flatten intrinsic arrays before publishing
james-ward Nov 7, 2024
fba9d75
Ignore retval for SolvePnp
james-ward Nov 7, 2024
c825d05
run black
LucienMorey Nov 7, 2024
89b3fff
Send correct hash
james-ward Nov 7, 2024
a77879f
update return type
LucienMorey Nov 7, 2024
e693569
Pack and send pipeline results
james-ward Nov 7, 2024
61edd8c
Use best estimate for alt in sim
james-ward Nov 7, 2024
6dda0c8
Add multipnp results
james-ward Nov 7, 2024
62181a9
Store min area rect corners in target
james-ward Nov 7, 2024
248a1ed
Use RotTrlTransform3d for getVisibleLine
james-ward Nov 7, 2024
dbf5ffc
Remove erroneous print statement
james-ward Nov 8, 2024
d05d3ca
Implement missing methods in OpenCVHelp.py
james-ward Nov 8, 2024
e0a644d
Add SolvePnpSquare
james-ward Nov 9, 2024
c877db9
Bugfix: use correct constructor
james-ward Nov 9, 2024
5e755d7
Add additional cameras to sim
james-ward Nov 9, 2024
b396e49
formatting
LucienMorey Nov 9, 2024
f7ffc3e
Fix member names after auto-generation code merge
james-ward Nov 9, 2024
79640c9
Implement spherical target sim
james-ward Nov 9, 2024
9b3925a
start test harness with testVisibilityCupidShuffle func
LucienMorey Nov 10, 2024
6a088e4
explicitly construct int to prevent casting
LucienMorey Nov 10, 2024
89165a8
add missing break statement
LucienMorey Nov 10, 2024
eb5dfea
fix missed default initialisers
LucienMorey Nov 10, 2024
f47057c
add dependnecy on cv or rio cv
LucienMorey Nov 10, 2024
b333274
format test harness
LucienMorey Nov 10, 2024
c2da321
fix deadly boolean logic sads
LucienMorey Nov 10, 2024
eefd132
control types to be compatible with cv2 on sad pathway
LucienMorey Nov 10, 2024
61f2f7c
add test for not visible vert 1
LucienMorey Nov 10, 2024
a1fc188
add remaining test harness bar single todo around unimplemented function
LucienMorey Nov 10, 2024
47c5cc4
fix bad function call
LucienMorey Nov 10, 2024
6d675a8
handle type construction properly
LucienMorey Nov 10, 2024
176b7cc
fix name error
LucienMorey Nov 10, 2024
90bfa49
fix index error
LucienMorey Nov 10, 2024
f0fa85e
Minor bugfixes to suppress test warnings
james-ward Nov 10, 2024
4b69981
remove double import
LucienMorey Nov 10, 2024
44ea8f0
raise exceptions properly
LucienMorey Nov 10, 2024
e6841fb
Enable message UUID checking
james-ward Nov 9, 2024
0c5f15a
format
LucienMorey Nov 10, 2024
b6e00ac
fix import
LucienMorey Nov 10, 2024
f6ea4ae
format out of diff things cause formating is broken now
LucienMorey Nov 10, 2024
0f1d711
pin numpy to a working version
LucienMorey Nov 10, 2024
94960b1
try isort
LucienMorey Nov 10, 2024
928fed9
Use real TimeInterpolatablePose3dBuffer
auscompgeek Nov 10, 2024
24feb3c
Apply wpiformat fixes from builder
james-ward Nov 10, 2024
c739fe5
More formatting
james-ward Nov 10, 2024
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
5 changes: 5 additions & 0 deletions photon-lib/py/photonlibpy/estimation/__init__.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
from .cameraTargetRelation import CameraTargetRelation
from .openCVHelp import OpenCVHelp
from .rotTrlTransform3d import RotTrlTransform3d
from .targetModel import TargetModel
from .visionEstimation import VisionEstimation
25 changes: 25 additions & 0 deletions photon-lib/py/photonlibpy/estimation/cameraTargetRelation.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,25 @@
import math

from wpimath.geometry import Pose3d, Rotation2d, Transform3d
from wpimath.units import meters


class CameraTargetRelation:
def __init__(self, cameraPose: Pose3d, targetPose: Pose3d):
self.camPose = cameraPose
self.camToTarg = Transform3d(cameraPose, targetPose)
self.camToTargDist = self.camToTarg.translation().norm()
self.camToTargDistXY: meters = math.hypot(
self.camToTarg.translation().X(), self.camToTarg.translation().Y()
)
self.camToTargYaw = Rotation2d(self.camToTarg.X(), self.camToTarg.Y())
self.camToTargPitch = Rotation2d(self.camToTargDistXY, -self.camToTarg.Z())
self.camToTargAngle = Rotation2d(
math.hypot(self.camToTargYaw.radians(), self.camToTargPitch.radians())
)
self.targToCam = Transform3d(targetPose, cameraPose)
self.targToCamYaw = Rotation2d(self.targToCam.X(), self.targToCam.Y())
self.targToCamPitch = Rotation2d(self.camToTargDistXY, -self.targToCam.Z())
self.targtoCamAngle = Rotation2d(
math.hypot(self.targToCamYaw.radians(), self.targToCamPitch.radians())
)
200 changes: 200 additions & 0 deletions photon-lib/py/photonlibpy/estimation/openCVHelp.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,200 @@
import math
from typing import Any, Tuple

import cv2 as cv
import numpy as np
from wpimath.geometry import Rotation3d, Transform3d, Translation3d

from ..targeting import PnpResult, TargetCorner
from .rotTrlTransform3d import RotTrlTransform3d

NWU_TO_EDN = Rotation3d(np.array([[0, -1, 0], [0, 0, -1], [1, 0, 0]]))
EDN_TO_NWU = Rotation3d(np.array([[0, 0, 1], [-1, 0, 0], [0, -1, 0]]))


class OpenCVHelp:
@staticmethod
def getMinAreaRect(points: np.ndarray) -> cv.RotatedRect:
return cv.RotatedRect(*cv.minAreaRect(points))

@staticmethod
def translationNWUtoEDN(trl: Translation3d) -> Translation3d:
return trl.rotateBy(NWU_TO_EDN)

@staticmethod
def rotationNWUtoEDN(rot: Rotation3d) -> Rotation3d:
return -NWU_TO_EDN + (rot + NWU_TO_EDN)

@staticmethod
def translationToTVec(translations: list[Translation3d]) -> np.ndarray:
retVal: list[list] = []
for translation in translations:
trl = OpenCVHelp.translationNWUtoEDN(translation)
retVal.append([trl.X(), trl.Y(), trl.Z()])
return np.array(
retVal,
dtype=np.float32,
)

@staticmethod
def rotationToRVec(rotation: Rotation3d) -> np.ndarray:
retVal: list[np.ndarray] = []
rot = OpenCVHelp.rotationNWUtoEDN(rotation)
rotVec = rot.getQuaternion().toRotationVector()
retVal.append(rotVec)
return np.array(
retVal,
dtype=np.float32,
)

@staticmethod
def avgPoint(points: list[Tuple[float, float]]) -> Tuple[float, float]:
x = 0.0
y = 0.0
for p in points:
x += p[0]
y += p[1]
return (x / len(points), y / len(points))

@staticmethod
def pointsToTargetCorners(points: np.ndarray) -> list[TargetCorner]:
corners = [TargetCorner(p[0, 0], p[0, 1]) for p in points]
return corners

@staticmethod
def cornersToPoints(corners: list[TargetCorner]) -> np.ndarray:
points = [[[c.x, c.y]] for c in corners]
return np.array(points)

@staticmethod
def projectPoints(
cameraMatrix: np.ndarray,
distCoeffs: np.ndarray,
camRt: RotTrlTransform3d,
objectTranslations: list[Translation3d],
) -> np.ndarray:
objectPoints = OpenCVHelp.translationToTVec(objectTranslations)
rvec = OpenCVHelp.rotationToRVec(camRt.getRotation())
tvec = OpenCVHelp.translationToTVec(
[
camRt.getTranslation(),
]
)

pts, _ = cv.projectPoints(objectPoints, rvec, tvec, cameraMatrix, distCoeffs)
return pts

@staticmethod
def reorderCircular(
elements: list[Any] | np.ndarray, backwards: bool, shiftStart: int
) -> list[Any]:
size = len(elements)
reordered = []
dir = -1 if backwards else 1
for i in range(size):
index = (i * dir + shiftStart * dir) % size
if index < 0:
index += size
reordered.append(elements[index])
return reordered

@staticmethod
def translationEDNToNWU(trl: Translation3d) -> Translation3d:
return trl.rotateBy(EDN_TO_NWU)

@staticmethod
def rotationEDNToNWU(rot: Rotation3d) -> Rotation3d:
return -EDN_TO_NWU + (rot + EDN_TO_NWU)

@staticmethod
def tVecToTranslation(tvecInput: np.ndarray) -> Translation3d:
return OpenCVHelp.translationEDNToNWU(Translation3d(tvecInput))

@staticmethod
def rVecToRotation(rvecInput: np.ndarray) -> Rotation3d:
return OpenCVHelp.rotationEDNToNWU(Rotation3d(rvecInput))

@staticmethod
def solvePNP_Square(
cameraMatrix: np.ndarray,
distCoeffs: np.ndarray,
modelTrls: list[Translation3d],
imagePoints: np.ndarray,
) -> PnpResult | None:
modelTrls = OpenCVHelp.reorderCircular(modelTrls, True, -1)
imagePoints = np.array(OpenCVHelp.reorderCircular(imagePoints, True, -1))
objectMat = np.array(OpenCVHelp.translationToTVec(modelTrls))

alt: Transform3d | None = None
for tries in range(2):
retval, rvecs, tvecs, reprojectionError = cv.solvePnPGeneric(
objectMat,
imagePoints,
cameraMatrix,
distCoeffs,
flags=cv.SOLVEPNP_IPPE_SQUARE,
)

best = Transform3d(
OpenCVHelp.tVecToTranslation(tvecs[0]),
OpenCVHelp.rVecToRotation(rvecs[0]),
)
if len(tvecs) > 1:
alt = Transform3d(
OpenCVHelp.tVecToTranslation(tvecs[1]),
OpenCVHelp.rVecToRotation(rvecs[1]),
)

if not math.isnan(reprojectionError[0, 0]):
break
else:
pt = imagePoints[0]
pt[0, 0] -= 0.001
pt[0, 1] -= 0.001
imagePoints[0] = pt

if math.isnan(reprojectionError[0, 0]):
print("SolvePNP_Square failed!")
return None

if alt:
return PnpResult(
best=best,
bestReprojErr=reprojectionError[0, 0],
alt=alt,
altReprojErr=reprojectionError[1, 0],
ambiguity=reprojectionError[0, 0] / reprojectionError[1, 0],
)
else:
# We have no alternative so set it to best as well
return PnpResult(
best=best,
bestReprojErr=reprojectionError[0],
alt=best,
altReprojErr=reprojectionError[0],
)

@staticmethod
def solvePNP_SQPNP(
cameraMatrix: np.ndarray,
distCoeffs: np.ndarray,
modelTrls: list[Translation3d],
imagePoints: np.ndarray,
) -> PnpResult | None:
objectMat = np.array(OpenCVHelp.translationToTVec(modelTrls))

retval, rvecs, tvecs, reprojectionError = cv.solvePnPGeneric(
objectMat, imagePoints, cameraMatrix, distCoeffs, flags=cv.SOLVEPNP_SQPNP
)

error = reprojectionError[0, 0]
best = Transform3d(
OpenCVHelp.tVecToTranslation(tvecs[0]), OpenCVHelp.rVecToRotation(rvecs[0])
)

if math.isnan(error):
return None

# We have no alternative so set it to best as well
result = PnpResult(best=best, bestReprojErr=error, alt=best, altReprojErr=error)
return result
32 changes: 32 additions & 0 deletions photon-lib/py/photonlibpy/estimation/rotTrlTransform3d.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,32 @@
from typing import Self

from wpimath.geometry import Pose3d, Rotation3d, Transform3d, Translation3d


class RotTrlTransform3d:
def __init__(
self, rot: Rotation3d = Rotation3d(), trl: Translation3d = Translation3d()
):
self.rot = rot
self.trl = trl

def inverse(self) -> Self:
invRot = -self.rot
invTrl = -(self.trl.rotateBy(invRot))
return type(self)(invRot, invTrl)

def getTransform(self) -> Transform3d:
return Transform3d(self.trl, self.rot)

def getTranslation(self) -> Translation3d:
return self.trl

def getRotation(self) -> Rotation3d:
return self.rot

def apply(self, trlToApply: Translation3d) -> Translation3d:
return trlToApply.rotateBy(self.rot) + self.trl

@classmethod
def makeRelativeTo(cls, pose: Pose3d) -> Self:
return cls(pose.rotation(), pose.translation()).inverse()
Loading
Loading