Skip to content
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

[BUG FIX]: Rectified erroneous retrieval of camera_matrix_ from camera_info/P(assuming 3x3 whereas actually 3x4) [ROS Noetic] #45

Merged
merged 1 commit into from
Jun 4, 2024

Conversation

real-Sandip-Das
Copy link
Contributor

@real-Sandip-Das real-Sandip-Das commented May 31, 2024

camera_info topic's float64[12] P is supposed to be a 3x4 matrix, whereas the function callback_camera_info in aruco_tracker.cpp was previously assuming 3x3

changed line 258 from:
camera_matrix_.at<double>(i / 3, i % 3) = cam_info.P[i];
to:
camera_matrix_.at<double>(i / 3, i % 3) = cam_info.P[i + i/3];

…a_info topic's float64[12] P (a 3x4 matrix, whereas the program was previously assuming 3x3)
@bjsowa
Copy link
Member

bjsowa commented Jun 4, 2024

You're right. I must have somehow missed it as I typically don't use this package with rectified images. This might also explain #31.

For future references: the camera insintric matrix of the rectified images in the left 3x3 portion of the 3x4 P matrix in camera info messages.
image

@bjsowa bjsowa merged commit 2d1e8ac into fictionlab:noetic Jun 4, 2024
1 check passed
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

2 participants