Skip to content

aruco: new feature testCharucoCornersCollinear() in charuco.hpp/cpp#2514

Merged
alalek merged 5 commits intoopencv:3.4from
amy-tabb:testCharucoCornersCollinear3.4
May 12, 2020
Merged

aruco: new feature testCharucoCornersCollinear() in charuco.hpp/cpp#2514
alalek merged 5 commits intoopencv:3.4from
amy-tabb:testCharucoCornersCollinear3.4

Conversation

@amy-tabb
Copy link
Copy Markdown
Contributor

When using charuco corners for calibration, specifically in the robotics context when full-pattern images of the charuco boards are not gauranteed, there are cases when the chaurco corners identified are collinear.

The corners (in my application) are usually axis aligned, but when these identified corners are axis aligned or just linear (some diagonal within the pattern), using these corners will result in errors via CV_ASSERT checks, or poor results b/c of the numerical issues of using collinear points for estimating calibration parameters.

There does not exist any functionality w/in the opencv_contrib module for checking whether the charuco corners are collinear, given a charuco board. In charuco.cpp, there is function static bool _arePointsEnoughForPoseEstimation(const vector< Point3f > &points) called by estimatePoseCharucoBoard(). This function is local to charuco.cpp, though, and only checks for axis-aligned collinear charuco corners.

The new feature is a function in charuco.hpp/.cpp that checks for collinear charuco corners, testCharucoCornersCollinear().

mwe.zip

The MWE mwe.zip (with some input images) alters calibrate_camera_charuco.cpp to demonstrate situations in which calibration fails when there are collinear charuco corners. In 3.4, the warning message

** On entry to DLASCLS parameter number  4 had an illegal value

is displayed and the intrinisic camera calibration matrix contains nan values.

In 4.3/master, an exception is thrown:

terminate called after throwing an instance of 'cv::Exception'
  what():  OpenCV(4.3.0-dev) /home/atabb/git/opencv-charuco/charuco-bool-feature/opencv/modules/calib3d/src/calibration.cpp:1213: error: (-215:Assertion failed) fabs(sc) > DBL_EPSILON in function 'cvFindExtrinsicCameraParams2'

The image below illustrate one such image. I did not have a diagonal case detected in my dataset, but created one to test.

image_00018

image_00016_diag

Within the MWE, I show how I would use this new feature -- to choose whether to include (or not) detected charuco boards.

//			// TODO Uncomment this when testing the new feature.
//			bool collinear = testCharucoCornersCollinear(charucoboard, currentCharucoIds);
//
//			cout << "file " << vectorFiles[i] << " is collinear ? " << collinear << endl;
//
//			if (currentCharucoCorners.size() >= 6 && collinear== false){
//				{
//					allCharucoCorners.push_back(currentCharucoCorners);
//					allCharucoIds.push_back(currentCharucoIds);
//				}
//			}

			// TODO  comment this when testing the new feature
			if (currentCharucoCorners.size() >= 6){
				{
					allCharucoCorners.push_back(currentCharucoCorners);
					allCharucoIds.push_back(currentCharucoIds);
				}
			}

For this PR, I included everything in the PR versus putting the failure cases in a separate issue. I am new to submitting PRs to OpenCV, let me know what works better. I also used the 3.4 branch this time.

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 OpenCV (BSD) License.
  • To the best of my knowledge, the proposed patch is not based on a code under GPL or other license that is incompatible with OpenCV
  • The PR is proposed to proper branch
  • There is reference to original bug report and related work
  • There is accuracy test, performance test and test data in opencv_extra repository, if applicable
    Patch to opencv_extra has the same branch name.
  • The feature is well documented and sample code can be built with the project CMake

@amy-tabb
Copy link
Copy Markdown
Contributor Author

The build failed b/c the parameter names didn't match those in the function. I tried to fix that in charuco.hpp and committed the branch again.

Copy link
Copy Markdown
Member

@alalek alalek left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

It would be nice if you can add simple test for testCharucoCornersCollinear() function

* The number of ids in charucoIDs should be <= the number of chessboard corners in the board. This functions checks whether the charuco corners are on a straight line (returns true, if so), or not (false). Axis parallel, as well as diagonal and other straight lines detected. Degenerate cases: for number of charucoIDs <= 2, the function returns true.
*/
CV_EXPORTS_W bool testCharucoCornersCollinear(const Ptr<CharucoBoard> &_board,
InputArray _charucoIds);
Copy link
Copy Markdown
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

_board

You can use parameter names without underscore symbol in headers (no need to synchronize with .cpp)

Copy link
Copy Markdown
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

OK

-indentation fixes
-switched order of the test for nCharucoCorners > 2 as suggested
@amy-tabb
Copy link
Copy Markdown
Contributor Author

Re: add simple test for testCharucoCornersCollinear() can you refer me to some ref materials, and/or give me some idea of what you have in mind? What would be tested? I read the performance tests page from https://github.com/opencv/opencv/wiki/How_to_contribute and it didn't seem quite relevant.

@alalek
Copy link
Copy Markdown
Member

alalek commented Apr 28, 2020

Consider adding test into this file.

No need to put/read image somewhere, just hard-code corner values in test code directly (you can dump them from your example pictures above).

TEST(Charuco, testCharucoCornersCollinear_true)
{
    ... create CharucoBoard and fill hard-coded collinear corners ...
    ... with identifiers ...
    bool result = cv::testCharucoCornersCollinear(board, charucoIds);
    EXPECT_TRUE(result);
}

TEST(Charuco, testCharucoCornersCollinear_false)
{
    ... create CharucoBoard and fill hard-coded corners ...
    ... with identifiers ...
    bool result = cv::testCharucoCornersCollinear(board, charucoIds);
    EXPECT_FALSE(result);
}

@amy-tabb
Copy link
Copy Markdown
Contributor Author

Ok -- thanks for the explanation, which I understood. I'll give this a try another day this week.

@amy-tabb
Copy link
Copy Markdown
Contributor Author

I created the test and ran it successfully on my system. Before the build system went down for maintenance, it indicated the test code wasn't in compliance w/ C++98, so I tried to fix that on the last commit.

Copy link
Copy Markdown
Member

@alalek alalek left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Well done! Thank you for contribution 👍

@alalek alalek merged commit aec1f71 into opencv:3.4 May 12, 2020
@alalek alalek mentioned this pull request May 12, 2020
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Projects

None yet

Development

Successfully merging this pull request may close these issues.

2 participants