CARVIEW |
Navigation Menu
-
-
Notifications
You must be signed in to change notification settings - Fork 56.2k
Fix crash in ap3p #23607
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
Fix crash in ap3p #23607
Conversation
modules/calib3d/src/ap3p.cpp
Outdated
@@ -256,6 +256,8 @@ int ap3p::computePoses(const double featureVectors[3][4], | |||
int nb_solutions = 0; | |||
for (int i = 0; i < 4; ++i) { | |||
double ctheta1p = s[i]; | |||
if (isnan(ctheta1p)) | |||
continue; |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Hi! Can you provide a reproducer so this can be covered by some test?
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Hi!
Sorry for the delay. Here is the reproducer:
{
const float fx = 1, fy = 1, cx = 0, cy = 0;
cv::ap3p solver(fx, fy, cx, cy);
const std::array<cv::Point2d, 3> cameraPts = { //
cv::Point2d{0.042784865945577621, 0.59844839572906494}, //
cv::Point2d{-0.028428621590137482, 0.60354739427566528}, //
cv::Point2d{0.0046037044376134872, 0.70674681663513184} //
};
const std::array<cv::Point3d, 3> modelPts = { //
cv::Point3d{-0.043258000165224075, 0.020459245890378952, -0.0069921980611979961}, //
cv::Point3d{-0.045648999512195587, 0.0029820732306689024, 0.0079000638797879219}, //
cv::Point3d{-0.043276999145746231, -0.013622495345771313, 0.0080113131552934647} //
};
double R[4][3][3];
double t[4][3];
const int nb_solutions = solver.solve(R, t, //
cameraPts[0].x, cameraPts[0].y, modelPts[0].x, modelPts[0].y, modelPts[0].z, //
cameraPts[1].x, cameraPts[1].y, modelPts[1].x, modelPts[1].y, modelPts[1].z, //
cameraPts[2].x, cameraPts[2].y, modelPts[2].x, modelPts[2].y, modelPts[2].z, //
0, 0, 0, 0, 0, false);
}
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Or, if rely on a public API:
std::vector<Mat> R, t;
solveP3P(modelPts, cameraPts, Mat::eye(3, 3, CV_64F), Mat(), R, t, SOLVEPNP_AP3P);
@alexander-varjo, can you please share your compiler version and target CPU architecture?
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
My setup:
- Compiler: MSVC 14.29.30133
- CPU: i9-10850K
Did you run directly cv::ap3p::solve() or you just used cv::solveP3P() when you tested the reproducer?
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Both, for me problem is not reproduced so it might depend on a compiler
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Can reproduce with the following code on MSVC 14.35.32215
. The app not crashed but nan returned.
Let me check if there is no other solution to this problem.
--- a/modules/calib3d/src/ap3p.cpp
+++ b/modules/calib3d/src/ap3p.cpp
@@ -3,6 +3,7 @@
#include <cmath>
#include <complex>
+#include <iostream>
#if defined (_MSC_VER) && (_MSC_VER <= 1700)
static inline double cbrt(double x) { return (double)cv::cubeRoot((float)x); };
#endif
@@ -256,6 +257,7 @@ int ap3p::computePoses(const double featureVectors[3][4],
int nb_solutions = 0;
for (int i = 0; i < 4; ++i) {
double ctheta1p = s[i];
+ std::cout << i << " " << ctheta1p << std::endl;
if (abs(ctheta1p) > 1)
continue;
double stheta1p = sqrt(1 - ctheta1p * ctheta1p);
#include <opencv2/opencv.hpp>
using namespace cv;
int main(int argc, char** argv) {
const std::array<cv::Point2d, 3> cameraPts = { //
cv::Point2d{0.042784865945577621, 0.59844839572906494}, //
cv::Point2d{-0.028428621590137482, 0.60354739427566528}, //
cv::Point2d{0.0046037044376134872, 0.70674681663513184} //
};
const std::array<cv::Point3d, 3> modelPts = { //
cv::Point3d{-0.043258000165224075, 0.020459245890378952, -0.0069921980611979961}, //
cv::Point3d{-0.045648999512195587, 0.0029820732306689024, 0.0079000638797879219}, //
cv::Point3d{-0.043276999145746231, -0.013622495345771313, 0.0080113131552934647} //
};
std::vector<Mat> R, t;
solveP3P(modelPts, cameraPts, Mat::eye(3, 3, CV_64F), Mat(), R, t, SOLVEPNP_AP3P);
for (int i = 0; i < R.size(); ++i) {
std::cout << R[i] << std::endl;
std::cout << t[i] << std::endl;
std::cout << " " << std::endl;
}
return 0;
}
0 nan
1 nan
2 -nan(ind)
3 -nan(ind)
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
The issue is reproducible with ENABLE_FAST_MATH option in Cmake. I do not get crash, but R and t contains NaNs.
@alexander-varjo Friendly reminder. |
1 similar comment
@alexander-varjo Friendly reminder. |
@dkurt Could you take a look on the reproducer? |
@dkurt Friendly reminder. |
234de5f
to
5eb9556
Compare
I squashed commits, added test and replaced std::isnan with OpenCV version cvIsNaN. The issue is not reproducible even with |
@asmorkalov, For the mentioned test data both R, t will be empty. Just wanted to verify if that's expected and we don't need to look for a root problem in the solver. |
5eb9556
to
168f793
Compare
@dkurt It's hard to say. What I see from implementation it's pure numerical method. There is no randomization or branches in the touched code. The coefficients in solveQuartic are ill-defined and the result is not stable. My understanding, that |
I just checked that #include <opencv2/opencv.hpp>
using namespace cv;
int main(int argc, char** argv) {
const std::array<cv::Point2d, 3> cameraPts = { //
cv::Point2d{0.042784865945577621, 0.59844839572906494}, //
cv::Point2d{-0.028428621590137482, 0.60354739427566528}, //
cv::Point2d{0.0046037044376134872, 0.70674681663513184} //
};
const std::array<cv::Point3d, 3> modelPts = { //
cv::Point3d{-0.043258000165224075, 0.020459245890378952, -0.0069921980611979961}, //
cv::Point3d{-0.045648999512195587, 0.0029820732306689024, 0.0079000638797879219}, //
cv::Point3d{-0.043276999145746231, -0.013622495345771313, 0.0080113131552934647} //
};
std::vector<Mat> R, t;
solveP3P(modelPts, cameraPts, Mat::eye(3, 3, CV_64F), Mat(), R, t, SOLVEPNP_P3P);
// Try apply rvec and tvec to get model points from camera points.
for (int i = 0; i < R.size(); ++i) {
std::cout << "Solution " << i << std::endl;
std::cout << "rvec: " << R[i].reshape(1, 1) << std::endl;
std::cout << "tvec: " << t[i].reshape(1, 1) << std::endl;
for (int j = 0; j < 3; ++j) {
Mat res(modelPts[j]);
res = res.reshape(1, 3);
Mat transform;
cv::Rodrigues(R[i], transform);
res = transform * res + t[i];
std::cout << res.at<double>(0) / res.at<double>(2) << " " << res.at<double>(1) / res.at<double>(2) << std::endl;
}
std::cout << std::endl;
}
return 0;
}
|
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
I have found a bug in solveQuartic
method. It computes incorrect roots for a given test example. Solution is in progress.
Current: [-0.0759858, -0.0759858, -0.0759858, -0.0759858]
Expected: [-0.07598547, -0.07598547, -0.70197669, 0.55000499]
(according to numpy.roots
).
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Can confirm that this PR passes on Raspberry Pi 3 and Clang 3.9.1 (https://downloads.raspberrypi.org/raspbian/images/raspbian-2018-11-15/).
Also reproduced failed tests with disabled fixes by @tomoaki0705 on the same setup:
|
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
👍
…patch-1 Fix crash in ap3p opencv#23607 ### Pull Request Readiness Checklist See details at https://github.com/opencv/opencv/wiki/How_to_contribute#making-a-good-pull-request - [ ] I agree to contribute to the project under Apache 2 License. - [ ] To the best of my knowledge, the proposed patch is not based on a code under GPL or another license that is incompatible with OpenCV - [x] The PR is proposed to the proper branch - [ ] There is a reference to the original bug report and related work - [x] There is accuracy test, performance test and test data in opencv_extra repository, if applicable Patch to opencv_extra has the same branch name. - [x] The feature is well documented and sample code can be built with the project CMake
…patch-1 Fix crash in ap3p opencv#23607 ### Pull Request Readiness Checklist See details at https://github.com/opencv/opencv/wiki/How_to_contribute#making-a-good-pull-request - [ ] I agree to contribute to the project under Apache 2 License. - [ ] To the best of my knowledge, the proposed patch is not based on a code under GPL or another license that is incompatible with OpenCV - [x] The PR is proposed to the proper branch - [ ] There is a reference to the original bug report and related work - [x] There is accuracy test, performance test and test data in opencv_extra repository, if applicable Patch to opencv_extra has the same branch name. - [x] The feature is well documented and sample code can be built with the project CMake
Pull Request Readiness Checklist
See details at https://github.com/opencv/opencv/wiki/How_to_contribute#making-a-good-pull-request
Patch to opencv_extra has the same branch name.