fictionlab / ros_aruco_opencv

ROS wrapper for ArUco Opencv module
MIT License
16 stars 16 forks source link

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

Closed real-Sandip-Das closed 5 months ago

real-Sandip-Das commented 5 months ago

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];

bjsowa commented 5 months ago

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