ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

registering depth image on different image size

asked 2021-12-29 11:30:08 -0500

max_ros gravatar image

updated 2022-01-03 05:00:58 -0500

Hi everyone.

I do want to register my depth image onto an mochrome image using depth_image_proc register.

I do publish the transform between the frame_ids using a static tranform publisher (see launch file).

This all seems to work fine in general as my registered depth topic is valid in rviz and receives frames. However, they are only black. Thereby, my depth image has a resolution of 848 x 480, whereas my monochrome image only has 640 x 512 px.

Also, to proof it works, I registered the depth image to another rgb camera (with a fitting resolution) and it worked there.

The rectified images look fine to me, so I think the internal calibrations should be good.

My guess is, that this is either a problem with the external calibration (that I did with an external tool due to the different resolutions) or could the resolutions itself be a problem for the remapping?

Do you maybe have hints how to debug this, as I do not really know how to proceed anyomore?

Thanks in advance.

my launch file:

<launch>
  <arg name="namespace_ir" default="gas_camera"/>
  <arg name="namespace_vis" default="realsense"/>


  <!-- gas_cam --> 
  <include file="$(find gas_cam)/launch/gas_cam.launch"> 
        <arg name="namespace" value="$(arg namespace_ir)" />
   </include>  

  <!-- realsense --> 
    <include file="$(find realsense2_camera)/launch/rs_camera.launch"  ns="$(arg namespace_vis)"> 
        <arg name="filters" value="pointcloud" />
        <arg name="tf_prefix" value="rs" />
   </include>


  <!-- tf2 -->   
    <node pkg="tf2_ros" type="static_transform_publisher" name="rs_2_ir" args="-0.062249 -0.083060 0.006821 0.00465763 0.052355 0.02046292  rs_link ir_kam_frame" />


  <!-- stereo proc for image registration -->
    <node pkg="nodelet" type="nodelet" name="nodelet_manager" args="manager" />
    <node pkg="nodelet" type="nodelet" name="nodelet1" args="load depth_image_proc/register nodelet_manager">
        <remap from="depth/camera_info" to="/$(arg namespace_vis)/camera/depth/camera_info"/>
        <remap from="rgb/camera_info" to="/$(arg namespace_ir)/camera_info"/>
        <remap from="depth/image_rect" to="/$(arg namespace_vis)/camera/depth/image_rect_raw"/>
    </node>

    <!-- RVIZ -->
    <node pkg="rviz" type="rviz" name="rviz" args="-d $(find gas_cam)/rviz/default_visualization.rviz"/>
</launch>

Edit (due to @lucasw 's comments): Here the camera infos. Please don't care about the different time stamps - the synchronization works (I just copied them using rosecho).

One thing to know when comparing the different camera infos is that the camera differ stongly in their angle of fiew: - ir_kam f ~ 25 mm (12° halfangle) - realsense f~ 2mm (I'd guess 50° halfangle)

camera info depth cam:

header: 
  seq: 67
  stamp: 
    secs: 1640873968
    nsecs: 393739462
  frame_id: "rs_depth_optical_frame"
height: 480
width: 848
distortion_model: "plumb_bob"
D: [0.0, 0.0, 0.0, 0.0, 0.0]
K: [422.76092529296875, 0.0, 422.03045654296875, 0.0, 422.76092529296875, 238.31170654296875, 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: [422.76092529296875, 0.0, 422.03045654296875, 0.0, 0.0, 422.76092529296875, 238.31170654296875, 0.0, 0.0, 0 ...
(more)
edit retag flag offensive close merge delete

Comments

It should be fine to go to a different resolution (though you may want to use fill_upsampling_holes, but you'll at least want to see some pixels are getting set and not just pure black), but there could be something wrong with the camera_info coming out of the monochrome image- can you echo a single camera_info from the not-working monochrome camera and the working rgb camera and add those to your question? (You could add a depth camera camera_info also)

If you set up an rviz Camera configured to use the monochrome camera_info does rviz show a reasonable view through it?

Probably isn't your problem but I've always had strange issues with tf2_ros static_transform_publisher and have always gone back to the older tf1 version rather than debug it to the point of asking a good question here or opening an issue or even fixing it.

lucasw gravatar image lucasw  ( 2021-12-29 22:49:20 -0500 )edit
1

Hi @lucasw, thanks for the quick answer and your thoughts!

I edited the question to provied the info you asked for. As the shown frames look fairly reasonable on the grid, I also don't think tf2_static_publisher is the problem...

max_ros gravatar image max_ros  ( 2021-12-30 08:34:20 -0500 )edit

Try setting the monochrome camera distortion to all zeros like the other cameras- that final distortion coefficient of -25 doesn't seem right.

Another test of the monochrome camera calibration is to put the monochrome camera through the image rectification nodelet to see if the undistorted output looks reasonable.

The monochrome camera fx/fy parameters of 1649 (where the other cameras look to have much wider angles-of-view) makes me wonder if that camera is pointed at small part of the depth image where there are no depth points. Or are there depth values covering the whole image?

lucasw gravatar image lucasw  ( 2021-12-30 09:03:21 -0500 )edit

Monochrome camera calibration: I guess you're right about the -25, this seems strange. I did another calibration, that has 0.xxx value in this position. However, the screenshot that I added to the question shows the rectified monochrome image still with this 25 number. Setting the distortion coefficients all to 0 doesn't change the seen behaviour of the black registered depth map.

dense depth map: good idea! However, I think the screenshot shows an example of an dense depthmap - and the registered depth map stays black...

max_ros gravatar image max_ros  ( 2021-12-30 09:55:47 -0500 )edit
1

Another debug is to use https://github.com/lucasw/vimjay/blob... (or otherwise manually publish a fictional camera info) instead of your real camera_info and make the numbers similar to the working camera or the not-working camera and anywhere in-between see if anything there causes the problem.

Additionally you could hook up an interactive tf publisher (https://github.com/lucasw/rviz_intera... and there are other options) instead of using the static transform publisher and see if moving frames around causes the problem, the trivial case is where there is no difference at all from depth to other camera, then slowly moving it further away or rotate.

lucasw gravatar image lucasw  ( 2021-12-30 10:50:28 -0500 )edit

First: These dynamic reconfigure tools are awesome, thanks a lot for sharing!

Second: happy new year^^

Third: Interesting observation: Before playing around with the interactive tf publisher I though to check the trivial case. And even there, using my calibration data, I get a black images only for the registered depth image. When using your dynamic camera_info script, I manage to finally see registered depth data, so I guess it must be the calibraiton :-)

P.S. I haven't yet set the fill_upsampling_hole parameter. As I understand from this , this is as parameter which isn't yet documented in the wiki? If this is correct (sorry for the newby question) - how would I set a nodelet parameter in the launch file?

max_ros gravatar image max_ros  ( 2022-01-03 02:54:10 -0500 )edit

1 Answer

Sort by » oldest newest most voted
2

answered 2022-01-03 11:45:53 -0500

lucasw gravatar image

(summarizing comments above into an answer)

Use rviz Camera to see that the view from either camera is approximately correct (could put a Grid in the field of view of both cameras).

One debug is to use https://github.com/lucasw/vimjay/blob... (or otherwise manually publish a fictional camera info) instead of your real camera_info and make the numbers similar to the working camera or the not-working camera and anywhere in-between see if anything there causes the problem. Doing a rectification on the depth or secondary camera output if not already rectified (distortion coefficients should be all zeros in camera info) should show reasonable results (straight lines should be straight), otherwise a re-calibration is necessary. Distortion coefficients shouldn't be too big (>1.0 is especially suspicious), though of course vary a lot.

Check that there are any depth values in the depth image where the secondary camera is pointed.

Additionally you could hook up an interactive tf publisher (https://github.com/lucasw/rviz_intera... and there are other options) instead of using the static transform publisher and see if moving frames around causes the problem, the trivial case is where there is no difference at all from depth to other camera, then slowly moving it further away or rotate.

If the depth image is low resolution or much wider angle than the camera that is the target for register then there may be large gaps between valid pixels that would result in a mostly black image (maybe totally black in the extreme case where the non-depth camera is so narrow/telephoto that not a single depth pixel is anywhere in the image), setting fill_upsampling_holes to true will fill that in.

<node name="depth_to_other_camera" pkg="nodelet" type="nodelet"
      args="load depth_image_proc/register nodelet_manager">
  ...
  <param name="fill_upsampling_holes" value="true />
</node>
edit flag offensive delete link more

Comments

upvote for a really helpful answer!!!

max_ros gravatar image max_ros  ( 2022-01-04 02:39:23 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2021-12-29 11:30:08 -0500

Seen: 523 times

Last updated: Jan 03 '22