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] Erroneous retrieval of Camera's intrinsic matrix camera_matrix_ [ROS Noetic] #46

Closed
real-Sandip-Das opened this issue May 31, 2024 · 1 comment

Comments

@real-Sandip-Das
Copy link
Contributor

Upon adding a few lines to the function callback_image(in aruco_tracker.cpp) for logging as follows:

  void callback_image(const sensor_msgs::ImageConstPtr &img_msg) {
    ROS_INFO_STREAM("distortion_coeffs_:");
    ROS_INFO_STREAM(distortion_coeffs_);
    ROS_INFO_STREAM("camera_matrix_:");
    ROS_INFO_STREAM(camera_matrix_);
    ROS_INFO_STREAM("marker_obj_points_:");
    ROS_INFO_STREAM(marker_obj_points_);

It was observed that the program was retrieving the camera's intrinsic matrix in a wrong way
the float64[12] P field(in 'sensor_msgs::CameraInfo') is supposed to be a 3x4 matrix whereas the program is assuming it as a 3x3 matrix

console log:

[ INFO] [1717179696.576882516]: camera_matrix_:
[ INFO] [1717179696.576928720]: [933.15867, 0, 657.59;
 0, 0, 933.1586;
 400.36993, 0, 0]
[ INFO] [1717179696.576959502]: marker_obj_points_:
[ INFO] [1717179696.577009891]: [-0.0055, 0.0055, 0;
 0.0055, 0.0055, 0;
 0.0055, -0.0055, 0;
 -0.0055, -0.0055, 0]
[ INFO] [1717179696.640044745]: distortion_coeffs_:
[ INFO] [1717179696.640184108]: [0;
 0;
 0;
 0]

published camera info(output of rostopic echo /cv_camera/camera_info):

header: 
  seq: 308
  stamp: 
    secs: 1717179691
    nsecs: 133644523
  frame_id: "camera"
height: 480
width: 640
distortion_model: "plumb_bob"
D: []
K: [933.15867, 0.0, 657.59, 0.0, 933.1586, 400.36993, 0.0, 0.0, 1.0]
R: [1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0]
P: [933.15867, 0.0, 657.59, 0.0, 0.0, 933.1586, 400.36993, 0.0, 0.0, 0.0, 1.0, 0.0]
binning_x: 0
binning_y: 0
roi: 
  x_offset: 0
  y_offset: 0
  height: 0
  width: 0
  do_rectify: False
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

No branches or pull requests

2 participants