mirror of
https://github.com/PhotonVision/photonvision
synced 2026-06-19 00:41:41 +00:00
Auto-generate packet dataclasses with Jinja (#1374)
This commit is contained in:
@@ -177,7 +177,11 @@ public class OpenCVTest {
|
||||
prop.getIntrinsics(), prop.getDistCoeffs(), camRt, target.getFieldVertices());
|
||||
var pnpSim =
|
||||
OpenCVHelp.solvePNP_SQUARE(
|
||||
prop.getIntrinsics(), prop.getDistCoeffs(), target.getModel().vertices, targetCorners);
|
||||
prop.getIntrinsics(),
|
||||
prop.getDistCoeffs(),
|
||||
target.getModel().vertices,
|
||||
targetCorners)
|
||||
.get();
|
||||
|
||||
// check solvePNP estimation accuracy
|
||||
assertSame(relTarget.getRotation(), pnpSim.best.getRotation());
|
||||
@@ -212,7 +216,11 @@ public class OpenCVTest {
|
||||
prop.getIntrinsics(), prop.getDistCoeffs(), camRt, target.getFieldVertices());
|
||||
var pnpSim =
|
||||
OpenCVHelp.solvePNP_SQPNP(
|
||||
prop.getIntrinsics(), prop.getDistCoeffs(), target.getModel().vertices, targetCorners);
|
||||
prop.getIntrinsics(),
|
||||
prop.getDistCoeffs(),
|
||||
target.getModel().vertices,
|
||||
targetCorners)
|
||||
.get();
|
||||
|
||||
// check solvePNP estimation accuracy
|
||||
assertSame(relTarget.getRotation(), pnpSim.best.getRotation());
|
||||
|
||||
@@ -37,10 +37,7 @@ class PhotonCameraTest {
|
||||
var packet = new Packet(1);
|
||||
var ret = new PhotonPipelineResult();
|
||||
packet.setData(new byte[0]);
|
||||
if (packet.getSize() < 1) {
|
||||
return;
|
||||
}
|
||||
PhotonPipelineResult.serde.pack(packet, ret);
|
||||
PhotonPipelineResult.photonStruct.pack(packet, ret);
|
||||
});
|
||||
}
|
||||
}
|
||||
|
||||
@@ -130,7 +130,7 @@ class PhotonPoseEstimatorTest {
|
||||
new TargetCorner(3, 4),
|
||||
new TargetCorner(5, 6),
|
||||
new TargetCorner(7, 8)))));
|
||||
cameraOne.result.setRecieveTimestampMicros((long) (11 * 1e6));
|
||||
cameraOne.result.setReceiveTimestampMicros((long) (11 * 1e6));
|
||||
|
||||
PhotonPoseEstimator estimator =
|
||||
new PhotonPoseEstimator(aprilTags, PoseStrategy.LOWEST_AMBIGUITY, new Transform3d());
|
||||
@@ -217,7 +217,7 @@ class PhotonPoseEstimatorTest {
|
||||
new TargetCorner(5, 6),
|
||||
new TargetCorner(7, 8)))));
|
||||
|
||||
cameraOne.result.setRecieveTimestampMicros((long) (4 * 1e6));
|
||||
cameraOne.result.setReceiveTimestampMicros((long) (4 * 1e6));
|
||||
|
||||
PhotonPoseEstimator estimator =
|
||||
new PhotonPoseEstimator(
|
||||
@@ -306,7 +306,7 @@ class PhotonPoseEstimatorTest {
|
||||
new TargetCorner(3, 4),
|
||||
new TargetCorner(5, 6),
|
||||
new TargetCorner(7, 8)))));
|
||||
cameraOne.result.setRecieveTimestampMicros((long) (17 * 1e6));
|
||||
cameraOne.result.setReceiveTimestampMicros((long) (17 * 1e6));
|
||||
|
||||
PhotonPoseEstimator estimator =
|
||||
new PhotonPoseEstimator(
|
||||
@@ -396,7 +396,7 @@ class PhotonPoseEstimatorTest {
|
||||
new TargetCorner(3, 4),
|
||||
new TargetCorner(5, 6),
|
||||
new TargetCorner(7, 8)))));
|
||||
cameraOne.result.setRecieveTimestampMicros((long) (1 * 1e6));
|
||||
cameraOne.result.setReceiveTimestampMicros((long) (1 * 1e6));
|
||||
|
||||
PhotonPoseEstimator estimator =
|
||||
new PhotonPoseEstimator(
|
||||
@@ -478,7 +478,7 @@ class PhotonPoseEstimatorTest {
|
||||
new TargetCorner(3, 4),
|
||||
new TargetCorner(5, 6),
|
||||
new TargetCorner(7, 8)))));
|
||||
cameraOne.result.setRecieveTimestampMicros((long) (7 * 1e6));
|
||||
cameraOne.result.setReceiveTimestampMicros((long) (7 * 1e6));
|
||||
|
||||
estimatedPose = estimator.update(cameraOne.result);
|
||||
pose = estimatedPose.get().estimatedPose;
|
||||
@@ -519,7 +519,7 @@ class PhotonPoseEstimatorTest {
|
||||
new TargetCorner(3, 4),
|
||||
new TargetCorner(5, 6),
|
||||
new TargetCorner(7, 8)))));
|
||||
result.setRecieveTimestampMicros((long) (20 * 1e6));
|
||||
result.setReceiveTimestampMicros((long) (20 * 1e6));
|
||||
|
||||
PhotonPoseEstimator estimator =
|
||||
new PhotonPoseEstimator(
|
||||
@@ -529,7 +529,7 @@ class PhotonPoseEstimatorTest {
|
||||
|
||||
// Empty result, expect empty result
|
||||
cameraOne.result = new PhotonPipelineResult();
|
||||
cameraOne.result.setRecieveTimestampMicros((long) (1 * 1e6));
|
||||
cameraOne.result.setReceiveTimestampMicros((long) (1 * 1e6));
|
||||
Optional<EstimatedRobotPose> estimatedPose = estimator.update(cameraOne.result);
|
||||
assertFalse(estimatedPose.isPresent());
|
||||
|
||||
@@ -629,7 +629,7 @@ class PhotonPoseEstimatorTest {
|
||||
new TargetCorner(3, 4),
|
||||
new TargetCorner(5, 6),
|
||||
new TargetCorner(7, 8))))); // 3 3 3 ambig .4
|
||||
cameraOne.result.setRecieveTimestampMicros(20 * 1000000);
|
||||
cameraOne.result.setReceiveTimestampMicros(20 * 1000000);
|
||||
|
||||
PhotonPoseEstimator estimator =
|
||||
new PhotonPoseEstimator(
|
||||
|
||||
@@ -481,11 +481,12 @@ class VisionSystemSimTest {
|
||||
visionSysSim.update(robotPose);
|
||||
var results =
|
||||
VisionEstimation.estimateCamPosePNP(
|
||||
camera.getCameraMatrix().get(),
|
||||
camera.getDistCoeffs().get(),
|
||||
camera.getLatestResult().getTargets(),
|
||||
layout,
|
||||
TargetModel.kAprilTag16h5);
|
||||
camera.getCameraMatrix().get(),
|
||||
camera.getDistCoeffs().get(),
|
||||
camera.getLatestResult().getTargets(),
|
||||
layout,
|
||||
TargetModel.kAprilTag16h5)
|
||||
.get();
|
||||
Pose3d pose = new Pose3d().plus(results.best);
|
||||
assertEquals(5, pose.getX(), .01);
|
||||
assertEquals(1, pose.getY(), .01);
|
||||
@@ -500,11 +501,12 @@ class VisionSystemSimTest {
|
||||
visionSysSim.update(robotPose);
|
||||
results =
|
||||
VisionEstimation.estimateCamPosePNP(
|
||||
camera.getCameraMatrix().get(),
|
||||
camera.getDistCoeffs().get(),
|
||||
camera.getLatestResult().getTargets(),
|
||||
layout,
|
||||
TargetModel.kAprilTag16h5);
|
||||
camera.getCameraMatrix().get(),
|
||||
camera.getDistCoeffs().get(),
|
||||
camera.getLatestResult().getTargets(),
|
||||
layout,
|
||||
TargetModel.kAprilTag16h5)
|
||||
.get();
|
||||
pose = new Pose3d().plus(results.best);
|
||||
assertEquals(5, pose.getX(), .01);
|
||||
assertEquals(1, pose.getY(), .01);
|
||||
|
||||
Reference in New Issue
Block a user