Skip to content

Commit

Permalink
forgot to delete old offset method
Browse files Browse the repository at this point in the history
  • Loading branch information
GGreenix committed Dec 10, 2024
1 parent 3b2fa8d commit d33d67f
Show file tree
Hide file tree
Showing 2 changed files with 2 additions and 82 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -178,8 +178,7 @@ protected CVPipelineResult process(Frame frame, AprilTagPipelineSettings setting
new TrackedTarget(
detection,
null,
new TargetCalculationParameters(false, null, null, null, null, frameStaticProperties),
new Point(settings.getStaticCrop().x, settings.getStaticCrop().y));
new TargetCalculationParameters(false, null, null, null, null, frameStaticProperties));

targetList.add(target);
}
Expand Down Expand Up @@ -239,8 +238,7 @@ protected CVPipelineResult process(Frame frame, AprilTagPipelineSettings setting
detection,
tagPoseEstimate,
new TargetCalculationParameters(
false, null, null, null, null, frameStaticProperties),
new Point(settings.getStaticCrop().x, settings.getStaticCrop().y));
false, null, null, null, null, frameStaticProperties));

var correctedBestPose =
MathUtils.convertOpenCVtoPhotonTransform(target.getBestCameraToTarget3d());
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -176,84 +176,6 @@ public int getClassID() {
return m_classId;
}

public TrackedTarget(
AprilTagDetection tagDetection,
AprilTagPoseEstimate tagPose,
TargetCalculationParameters params,
Point croppedOffset) {
m_targetOffsetPoint =
new Point(
tagDetection.getCenterX() + croppedOffset.x,
tagDetection.getCenterY() + croppedOffset.y);
m_robotOffsetPoint = new Point();
var yawPitch =
TargetCalculations.calculateYawPitch(
params.cameraCenterPoint.x,
tagDetection.getCenterX(),
params.horizontalFocalLength,
params.cameraCenterPoint.y,
tagDetection.getCenterY(),
params.verticalFocalLength,
params.cameraCal);
m_yaw = yawPitch.getFirst();
m_pitch = yawPitch.getSecond();
var bestPose = new Transform3d();
var altPose = new Transform3d();

if (tagPose != null) {
if (tagPose.error1 <= tagPose.error2) {
bestPose = tagPose.pose1;
altPose = tagPose.pose2;
} else {
bestPose = tagPose.pose2;
altPose = tagPose.pose1;
}

bestPose = MathUtils.convertApriltagtoOpenCV(bestPose);
altPose = MathUtils.convertApriltagtoOpenCV(altPose);

m_bestCameraToTarget3d = bestPose;
m_altCameraToTarget3d = altPose;

m_poseAmbiguity = tagPose.getAmbiguity();

var tvec = new Mat(3, 1, CvType.CV_64FC1);
tvec.put(
0,
0,
new double[] {
bestPose.getTranslation().getX(),
bestPose.getTranslation().getY(),
bestPose.getTranslation().getZ()
});
setCameraRelativeTvec(tvec);

// Opencv expects a 3d vector with norm = angle and direction = axis
var rvec = new Mat(3, 1, CvType.CV_64FC1);
MathUtils.rotationToOpencvRvec(bestPose.getRotation(), rvec);
setCameraRelativeRvec(rvec);
}

double[] corners = tagDetection.getCorners();
Point[] cornerPoints =
new Point[] {
new Point(corners[0] + croppedOffset.x, corners[1] + croppedOffset.y),
new Point(corners[2] + croppedOffset.x, corners[3] + croppedOffset.y),
new Point(corners[4] + croppedOffset.x, corners[5] + croppedOffset.y),
new Point(corners[6] + croppedOffset.x, corners[7] + croppedOffset.y)
};
m_targetCorners = List.of(cornerPoints);
MatOfPoint contourMat = new MatOfPoint(cornerPoints);
m_approximateBoundingPolygon = new MatOfPoint2f(cornerPoints);
m_mainContour = new Contour(contourMat);
m_area = m_mainContour.getArea() / params.imageArea * 100;
m_fiducialId = tagDetection.getId();
m_shape = null;

// TODO implement skew? or just yeet
m_skew = 0;
}

public TrackedTarget(
ArucoDetectionResult result,
AprilTagPoseEstimate tagPose,
Expand Down

0 comments on commit d33d67f

Please sign in to comment.