luxonis / depthai-ros

Official ROS Driver for DepthAI Sensors.
MIT License
239 stars 173 forks source link

[BUG] CameraInfo not "reasonable" #467

Open fwarmuth opened 7 months ago

fwarmuth commented 7 months ago

Hey, my overall goal is to do an extrinsic calibration using the MoveIT camera calibration.

Situation:

System: ros1 noetic docker container I run the rgb_pcl.launch with a custom param_file:

/oak:
    camera_i_ip: 192.168.4.169
    camera_i_floodlight_brightness: 800
    camera_i_laser_dot_brightness: 1000
    camera_i_pipeline_type: RGBD
    camera_i_nn_type: none
    rgb_i_resolution: '1080P'
    rgb_r_focus: 125
    rgb_r_set_man_focus: true
    left_i_resolution: '720P'
    right_i_resolution: '720P'
    stereo_i_resolution: '720P'
    stereo_i_stereo_conf_threshold: 255
    stereo_i_subpixel: true
    stereo_i_extended_disp: true
    stereo_i_depth_filter_size: 5

It publishes everything, except /oak/points don't know why, but problem for a different day. (Maybe some one has a hint) I receive a CameraInfoMsg similar to:

header: 
  seq: 30204
  stamp: 
    secs: 1701155449
    nsecs: 762082437
  frame_id: "oak_rgb_camera_optical_frame"
height: 720
width: 1280
distortion_model: "rational_polynomial"
D: [-0.9029932618141174, -54.66876220703125, 0.00040832499507814646, 0.00043196146725676954, 411.0915832519531, -1.0839022397994995, -52.5931510925293, 401.5426940917969]
K: [1039.033447265625, 0.0, 628.4920654296875, 0.0, 1039.033447265625, 374.26031494140625, 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: [1039.033447265625, 0.0, 628.4920654296875, 0.0, 0.0, 1039.033447265625, 374.26031494140625, 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
---

All good right?

Problem:

The MoveIT Camera Calibration Target module, shouts: Target detector has not received reasonable intrinsics. Attempted detection anyway. If one looks in the source code, it does call areIntrinsicsReasonable() -> Definition at line 292 of file handeye_target_base.h.

Therefore it seems that the published (/oak/rgb/camera_info) camera info data is not correct. What can i do about it, i dont want to calibrate the camera by hand - as it provides factory calibration values.

Any hints or pushes in the right direction would be highly appreciated! Cheers

Serafadam commented 7 months ago

Hi

  1. Regarding pointcloud, it should be visible, is the data published on all topics?
  2. Regarding intrinsics, could edit the camera calibration module to print out the contents of it's camera matrix?
saching13 commented 7 months ago
virtual bool areIntrinsicsReasonable()
   {
     return cv::norm(camera_matrix_) != 0. && cv::norm(camera_matrix_, cv::Mat::eye(3, 3, CV_64F)) != 0.;
   }

This is the intrinsics check function.

Here is my python POC on the same camera matrix.

import numpy as np
cam_mat = np.array([[1039.033447265625, 0.0, 628.4920654296875],
                      [0.0, 1039.033447265625, 374.26031494140625], 
                      [0.0, 0.0, 1.0]])
print(cv2.norm(cam_mat)) # -> 1641.418614711522
print(cv2.norm(cam_mat, np.eye(3))) # 0-> 1640.152412104567

So based on this. That is not the topic or the intrinsic that code is receiving. Cross check if the topic sent is correct and the right information matches.

fwarmuth commented 7 months ago

Hey, thanks for fast reply.

  1. I just needed patience, the point cloud is there, but the frequency is super low, normal? After a relaunch of the driver it takes several minutes to receive a single point cloud. Yes i know its a network not USB device, but that can not be as intended?

  2. I guess i don't get what you mean... sorry I looked in the calibration.launch, but i can not figure where the camera_calibration package is located in the ros1 docker container.

I solved the issue by overwriting the intrinsic calibration with my own - but that is not the solution.

regards

fwarmuth commented 7 months ago
virtual bool areIntrinsicsReasonable()
   {
     return cv::norm(camera_matrix_) != 0. && cv::norm(camera_matrix_, cv::Mat::eye(3, 3, CV_64F)) != 0.;
   }

This is the intrinsics check function.

Here is my python POC on the same camera matrix.

import numpy as np
cam_mat = np.array([[1039.033447265625, 0.0, 628.4920654296875],
                      [0.0, 1039.033447265625, 374.26031494140625], 
                      [0.0, 0.0, 1.0]])
print(cv2.norm(cam_mat)) # -> 1641.418614711522
print(cv2.norm(cam_mat, np.eye(3))) # 0-> 1640.152412104567

So based on this. That is not the topic or the intrinsic that code is receiving. Cross check if the topic sent is correct and the right information matches.

Sorry, you wrote while I wrote.