Skip to content

Commit

Permalink
Address comments
Browse files Browse the repository at this point in the history
obama.png
  • Loading branch information
mcm001 committed May 10, 2024
1 parent 4de4833 commit f663a26
Show file tree
Hide file tree
Showing 5 changed files with 63 additions and 57 deletions.
35 changes: 2 additions & 33 deletions photon-client/src/components/cameras/CameraCalibrationCard.vue
Original file line number Diff line number Diff line change
Expand Up @@ -62,37 +62,6 @@ const getUniqueVideoFormatsByResolution = (): VideoFormat[] => {
return uniqueResolutions;
};
// const getUniqueVideoFormatsByResolution = (): VideoFormat[] => {
// const uniqueResolutions: VideoFormat[] = [];
// useCameraSettingsStore().currentCameraSettings.uniqueVideoFormats.forEach((format) => {
// const calib = useCameraSettingsStore().getCalibrationCoeffs(format.resolution);
// if (calib !== undefined) {
// // For each error, square it, sum the squares, and divide by total points N
// if (calib.meanErrors.length) format.mean = calib.meanErrors.reduce((a, b) => a + b, 0) / calib.meanErrors.length;
// else format.mean = NaN;
// format.horizontalFOV =
// 2 * Math.atan2(format.resolution.width / 2, calib.cameraIntrinsics.data[0]) * (180 / Math.PI);
// format.verticalFOV =
// 2 * Math.atan2(format.resolution.height / 2, calib.cameraIntrinsics.data[4]) * (180 / Math.PI);
// format.diagonalFOV =
// 2 *
// Math.atan2(
// Math.sqrt(
// format.resolution.width ** 2 +
// (format.resolution.height / (calib.cameraIntrinsics.data[4] / calib.cameraIntrinsics.data[0])) ** 2
// ) / 2,
// calib.cameraIntrinsics.data[0]
// ) *
// (180 / Math.PI);
// }
// uniqueResolutions.push(format);
// });
// uniqueResolutions.sort(
// (a, b) => b.resolution.width + b.resolution.height - (a.resolution.width + a.resolution.height)
// );
// return uniqueResolutions;
// };
const getUniqueVideoResolutionStrings = (): { name: string; value: number }[] =>
getUniqueVideoFormatsByResolution().map<{ name: string; value: number }>((f) => ({
name: `${getResolutionString(f.resolution)}`,
Expand All @@ -109,7 +78,7 @@ const squareSizeIn = ref(1);
const markerSizeIn = ref(0.75);
const patternWidth = ref(8);
const patternHeight = ref(8);
const boardType = ref<CalibrationBoardTypes>(CalibrationBoardTypes.Chessboard);
const boardType = ref<CalibrationBoardTypes>(CalibrationBoardTypes.Charuco);
const useMrCalRef = ref(true);
const useMrCal = computed<boolean>({
get() {
Expand Down Expand Up @@ -317,7 +286,7 @@ const setSelectedVideoFormat = (format: VideoFormat) => {
:items="getUniqueVideoResolutionStrings()"
/>
<pv-select
v-show="isCalibrating"
v-show="isCalibrating && boardType != CalibrationBoardTypes.Charuco"
v-model="useCameraSettingsStore().currentPipelineSettings.streamingFrameDivisor"
label="Decimation"
tooltip="Resolution to which camera frames are downscaled for detection. Calibration still uses full-res"
Expand Down
1 change: 0 additions & 1 deletion photon-client/src/types/WebsocketDataTypes.ts
Original file line number Diff line number Diff line change
Expand Up @@ -57,7 +57,6 @@ export interface WebsocketCameraSettingsUpdate {
outputStreamPort: number;
pipelineNicknames: string[];
videoFormatList: WebsocketVideoFormat;
uniqueFormatList: WebsocketVideoFormat;
cameraQuirks: QuirkyCamera;
}
export interface WebsocketNTUpdate {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -23,10 +23,6 @@
import java.util.stream.Collectors;
import org.opencv.calib3d.Calib3d;
import org.opencv.core.*;
import org.opencv.core.Mat;
import org.opencv.core.MatOfDouble;
import org.opencv.core.MatOfPoint2f;
import org.opencv.core.Size;
import org.photonvision.common.logging.LogGroup;
import org.photonvision.common.logging.Logger;
import org.photonvision.common.util.math.MathUtils;
Expand Down Expand Up @@ -121,13 +117,31 @@ protected CameraCalibrationCoefficients process(CalibrationInput in) {

protected CameraCalibrationCoefficients calibrateOpenCV(
List<FindBoardCornersPipe.FindBoardCornersPipeResult> in, double fxGuess, double fyGuess) {
List<Mat> objPoints = in.stream().map(it -> it.objectPoints).collect(Collectors.toList());
List<Mat> imgPts = in.stream().map(it -> it.imagePoints).collect(Collectors.toList());
if (objPoints.size() != imgPts.size()) {
List<MatOfPoint3f> objPointsIn =
in.stream().map(it -> it.objectPoints).collect(Collectors.toList());
List<MatOfPoint2f> imgPointsIn =
in.stream().map(it -> it.imagePoints).collect(Collectors.toList());
List<MatOfFloat> levelsArr = in.stream().map(it -> it.levels).collect(Collectors.toList());

if (objPointsIn.size() != imgPointsIn.size() || objPointsIn.size() != levelsArr.size()) {
logger.error("objpts.size != imgpts.size");
return null;
}

// And delete rows depending on the level -- otherwise, level has no impact for opencv
List<Mat> objPoints = new ArrayList<>();
List<Mat> imgPoints = new ArrayList<>();
for (int i = 0; i < objPointsIn.size(); i++) {
MatOfPoint3f objPtsOut = new MatOfPoint3f();
MatOfPoint2f imgPtsOut = new MatOfPoint2f();

deleteIgnoredPoints(
objPointsIn.get(i), imgPointsIn.get(i), levelsArr.get(i), objPtsOut, imgPtsOut);

objPoints.add(objPtsOut);
imgPoints.add(imgPtsOut);
}

Mat cameraMatrix = new Mat(3, 3, CvType.CV_64F);
MatOfDouble distortionCoefficients = new MatOfDouble();
List<Mat> rvecs = new ArrayList<>();
Expand All @@ -145,7 +159,7 @@ protected CameraCalibrationCoefficients calibrateOpenCV(

Calib3d.calibrateCameraExtended(
objPoints,
imgPts,
imgPoints,
new Size(in.get(0).size.width, in.get(0).size.height),
cameraMatrix,
distortionCoefficients,
Expand All @@ -171,6 +185,8 @@ protected CameraCalibrationCoefficients calibrateOpenCV(
distortionCoefficients.release();
rvecs.forEach(Mat::release);
tvecs.forEach(Mat::release);
objPoints.forEach(Mat::release);
imgPoints.forEach(Mat::release);

return new CameraCalibrationCoefficients(
in.get(0).size,
Expand Down Expand Up @@ -381,6 +397,32 @@ private List<BoardObservation> createObservations(
return observations;
}

/** Delete all rows of mats where level is < 0. Useful for opencv */
private void deleteIgnoredPoints(
MatOfPoint3f objPtsMatIn,
MatOfPoint2f imgPtsMatIn,
MatOfFloat levelsMat,
MatOfPoint3f objPtsMatOut,
MatOfPoint2f imgPtsMatOut) {
var levels = levelsMat.toArray();
var objPtsIn = objPtsMatIn.toArray();
var imgPtsIn = imgPtsMatIn.toArray();

var objPtsOut = new ArrayList<Point3>();
var imgPtsOut = new ArrayList<Point>();

for (int i = 0; i < levels.length; i++) {
if (levels[i] >= 0) {
// point survives
objPtsOut.add(objPtsIn[i]);
imgPtsOut.add(imgPtsIn[i]);
}
}

objPtsMatOut.fromList(objPtsOut);
imgPtsMatOut.fromList(imgPtsOut);
}

public static class CalibratePipeParams {
// Size (in # of corners) of the calibration object
public int boardHeight;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -249,7 +249,7 @@ private FindBoardCornersPipeResult findBoardCorners(Pair<Mat, Mat> in) {
this.imageSize = new Size(inFrame.width(), inFrame.height());

if (params.type == UICalibrationData.BoardType.CHARUCOBOARD) {
Mat ObjPoints =
Mat objPoints =
new Mat(); // 3 dimensional currentObjectPoints, the physical target ChArUco Board
Mat imgPoints =
new Mat(); // 2 dimensional currentImagePoints, the likely distorted board on the flat
Expand All @@ -274,20 +274,20 @@ private FindBoardCornersPipeResult findBoardCorners(Pair<Mat, Mat> in) {
// If we can't find a board, give up
return null;
}
board.matchImagePoints(detectedCornersList, detectedIds, ObjPoints, imgPoints);
board.matchImagePoints(detectedCornersList, detectedIds, objPoints, imgPoints);

// draw the charuco board
Objdetect.drawDetectedCornersCharuco(
outFrame, detectedCorners, detectedIds, new Scalar(0, 0, 255)); // Red Text

imgPoints.copyTo(outBoardCorners);
ObjPoints.copyTo(objPts);
objPoints.copyTo(objPts);

// Since charuco can still detect without the whole board we need to send mrcal "fake" (all
// values less than zero) points and then tell it to ignore them (setting the corresponding
// level to -1). Since opencv calibration does not require the w*h to be the same we don't
// need to do this if not using mrcal.
if (params.useMrCal) {
// Since charuco can still detect without the whole board we need to send "fake" (all
// values less than zero) points and then tell it to ignore that corner by setting the
// corresponding level to -1. Calibrate3dPipe deals with piping this into the correct format
// for each backend
{
Point[] boardCorners =
new Point[(this.params.boardHeight - 1) * (this.params.boardWidth - 1)];
Point3[] objectPoints =
Expand All @@ -312,7 +312,7 @@ private FindBoardCornersPipeResult findBoardCorners(Pair<Mat, Mat> in) {
outLevels.fromArray(levels);
}
imgPoints.release();
ObjPoints.release();
objPoints.release();
detectedCorners.release();
detectedIds.release();

Expand Down Expand Up @@ -372,7 +372,6 @@ public static class FindCornersPipeParams {
final double markerSize;
final FrameDivisor divisor;
final int tagFamily;
final boolean useMrCal;

public FindCornersPipeParams(
int boardHeight,
Expand All @@ -381,16 +380,14 @@ public FindCornersPipeParams(
int tagFamily,
double gridSize,
double markerSize,
FrameDivisor divisor,
boolean useMrCal) {
FrameDivisor divisor) {
this.boardHeight = boardHeight;
this.boardWidth = boardWidth;
this.tagFamily = tagFamily;
this.type = type;
this.gridSize = gridSize; // meter
this.markerSize = markerSize; // meter
this.divisor = divisor;
this.useMrCal = useMrCal;
}

@Override
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -90,8 +90,7 @@ protected void setPipeParamsImpl() {
settings.tagFamily,
settings.gridSize,
settings.markerSize,
settings.streamingFrameDivisor,
settings.useMrCal);
settings.streamingFrameDivisor);
findBoardCornersPipe.setParams(findCornersPipeParams);

Calibrate3dPipe.CalibratePipeParams calibratePipeParams =
Expand Down

0 comments on commit f663a26

Please sign in to comment.