NVIDIA-ISAAC-ROS / isaac_ros_dnn_stereo_depth

NVIDIA-accelerated, deep learned stereo disparity estimation
https://developer.nvidia.com/isaac-ros-gems
Apache License 2.0
92 stars 10 forks source link

Disparty node does not work with Oak-D Pro camera #26

Closed JohannesPankert closed 4 months ago

JohannesPankert commented 4 months ago

Hello

I am trying to get the stereo matching node to work with my Oak-D Pro camera. I followed the example of the Realsense launchfile.

The preprocessing steps with the nvidia nodes (mono2rgb, rectify, resize) all seem to work correctly.

The disparity node does not publish disparity images though. I both tried the node with live images and with a ros2 bag that I recorded. I modified the rosbag to make sure that the left and right images and their camera_info messages are time synced correctly.

The disparity node works with the example rosbag provided in isaac_ros_assets/isaac_ros_ess/rosbags/ess_rosbag

This is the output of the disparity node with log level debug: It looks like it does receive the images but there is no error message or other indication on why it does not produce the disparity image.

Do you have any ideas what else I can try to get this to work?

[component_container_mt-2] [DEBUG] [1721642150.012326264] [rcl]: Calling timer
[component_container_mt-2] [DEBUG] [1721642150.012857975] [rcl]: Calling timer
[component_container_mt-2] [DEBUG] [1721642150.112262956] [rcl]: Calling timer
[component_container_mt-2] [DEBUG] [1721642150.112877727] [rcl]: Calling timer
[component_container_mt-2] [DEBUG] [1721642150.180548313] [rcl]: Subscription taking message
[component_container_mt-2] [DEBUG] [1721642150.180607003] [rcl]: Subscription taking message
[component_container_mt-2] [DEBUG] [1721642150.180664223] [rcl]: Subscription taking message
[component_container_mt-2] [DEBUG] [1721642150.180695753] [rcl]: Subscription take succeeded: true
[component_container_mt-2] [DEBUG] [1721642150.180712083] [NitrosCameraInfo]: [convert_to_custom] Conversion started
[component_container_mt-2] [DEBUG] [1721642150.180840084] [rcl]: Subscription taking message
[component_container_mt-2] [DEBUG] [1721642150.180888084] [rcl]: Subscription take succeeded: true
[component_container_mt-2] [DEBUG] [1721642150.180902334] [NitrosCameraInfo]: [convert_to_custom] Conversion started
[component_container_mt-2] [DEBUG] [1721642150.180962934] [NitrosCameraInfo]: [convert_to_custom] Conversion completed
[component_container_mt-2] [DEBUG] [1721642150.180973814] [NitrosTypeBase]: [Copy Constructor] Copying a Nitros-typed object for handle = 2234
[component_container_mt-2] [DEBUG] [1721642150.180990884] [rcl]: Subscription take succeeded: true
[component_container_mt-2] [DEBUG] [1721642150.181003794] [NitrosImage]: [convert_to_custom] Conversion started
[component_container_mt-2] [DEBUG] [1721642150.181012824] [disparity]: [NitrosSubscriber] Received a Nitros-typed messgae
[component_container_mt-2] [DEBUG] [1721642150.181093714] [disparity]: [NitrosSubscriber]   eid: 2234
[component_container_mt-2] [DEBUG] [1721642150.181103814] [disparity]: [NitrosSubscriber]   data_format_name: nitros_camera_info
[component_container_mt-2] [DEBUG] [1721642150.181110744] [disparity]: [NitrosSubscriber]   msg_base: 
[component_container_mt-2] [DEBUG] [1721642150.181118364] [disparity]: [NitrosSubscriber]   Receiver's pointer: 0x7ab9cc4870b0
[component_container_mt-2] [DEBUG] [1721642150.181126874] [disparity]: [NitrosSubscriber] Updated frame_id=oak_right_camera_optical_frame
[component_container_mt-2] [DEBUG] [1721642150.181119714] [NitrosImage]: [image size]  [1658880].
[component_container_mt-2] [DEBUG] [1721642150.181077044] [NitrosCameraInfo]: [convert_to_custom] Conversion completed
[component_container_mt-2] [DEBUG] [1721642150.181161384] [NitrosTypeBase]: [Copy Constructor] Copying a Nitros-typed object for handle = 2236
[component_container_mt-2] [DEBUG] [1721642150.181143834] [disparity]: [NitrosSubscriber] Pushed a message entity (eid=2234) to the appliation
[component_container_mt-2] [DEBUG] [1721642150.181178664] [disparity]: [NitrosSubscriber] Received a Nitros-typed messgae
[component_container_mt-2] [DEBUG] [1721642150.181201624] [disparity]: [NitrosSubscriber]   eid: 2236
[component_container_mt-2] [DEBUG] [1721642150.181210054] [disparity]: [NitrosSubscriber]   data_format_name: nitros_camera_info
[component_container_mt-2] [DEBUG] [1721642150.181217824] [disparity]: [NitrosSubscriber]   msg_base: 
[component_container_mt-2] [DEBUG] [1721642150.181225084] [disparity]: [NitrosSubscriber]   Receiver's pointer: 0x7ab9cc4866c0
[component_container_mt-2] [DEBUG] [1721642150.181233474] [disparity]: [NitrosSubscriber] Updated frame_id=oak_left_camera_optical_frame
[component_container_mt-2] [DEBUG] [1721642150.181067064] [rcl]: Subscription take succeeded: true
[component_container_mt-2] [DEBUG] [1721642150.181181794] [NitrosTypeBase]: [Destructor]Dstroying a Nitros-typed object for handle = 2234
[component_container_mt-2] [DEBUG] [1721642150.181266704] [NitrosTypeBase]: [Destructor]Dstroying a Nitros-typed object for handle = 2234
[component_container_mt-2] [DEBUG] [1721642150.181250014] [disparity]: [NitrosSubscriber] Pushed a message entity (eid=2236) to the appliation
[component_container_mt-2] [DEBUG] [1721642150.181287284] [NitrosTypeBase]: [Destructor]Dstroying a Nitros-typed object for handle = 2236
[component_container_mt-2] [DEBUG] [1721642150.181295375] [NitrosTypeBase]: [Destructor]Dstroying a Nitros-typed object for handle = 2236
[component_container_mt-2] [DEBUG] [1721642150.181258234] [NitrosImage]: [convert_to_custom] Conversion started
[component_container_mt-2] [DEBUG] [1721642150.181377945] [NitrosImage]: [image size]  [1658880].
[component_container_mt-2] [DEBUG] [1721642150.181675645] [NitrosImage]: [convert_to_custom] Conversion completed (resulting handle=2249)
[component_container_mt-2] [DEBUG] [1721642150.181684505] [NitrosTypeBase]: [Copy Constructor] Copying a Nitros-typed object for handle = 2249
[component_container_mt-2] [DEBUG] [1721642150.181697785] [disparity]: [NitrosSubscriber] Received a Nitros-typed messgae
[component_container_mt-2] [DEBUG] [1721642150.181711155] [disparity]: [NitrosSubscriber]   eid: 2249
[component_container_mt-2] [DEBUG] [1721642150.181717125] [disparity]: [NitrosSubscriber]   data_format_name: nitros_image_rgb8
[component_container_mt-2] [DEBUG] [1721642150.181722215] [disparity]: [NitrosSubscriber]   msg_base: 
[component_container_mt-2] [DEBUG] [1721642150.181727155] [disparity]: [NitrosSubscriber]   Receiver's pointer: 0x7ab9cc004040
[component_container_mt-2] [DEBUG] [1721642150.181732805] [disparity]: [NitrosSubscriber] Updated frame_id=oak_left_camera_optical_frame
[component_container_mt-2] [DEBUG] [1721642150.181742615] [disparity]: [NitrosSubscriber] Pushed a message entity (eid=2249) to the appliation
[component_container_mt-2] [DEBUG] [1721642150.181753895] [NitrosTypeBase]: [Destructor]Dstroying a Nitros-typed object for handle = 2249
[component_container_mt-2] [DEBUG] [1721642150.181760245] [NitrosTypeBase]: [Destructor]Dstroying a Nitros-typed object for handle = 2249
[component_container_mt-2] [DEBUG] [1721642150.181913396] [NitrosImage]: [convert_to_custom] Conversion completed (resulting handle=2243)
[component_container_mt-2] [DEBUG] [1721642150.181925746] [NitrosTypeBase]: [Copy Constructor] Copying a Nitros-typed object for handle = 2243
[component_container_mt-2] [DEBUG] [1721642150.181941526] [disparity]: [NitrosSubscriber] Received a Nitros-typed messgae
[component_container_mt-2] [DEBUG] [1721642150.181955666] [disparity]: [NitrosSubscriber]   eid: 2243
[component_container_mt-2] [DEBUG] [1721642150.181963606] [disparity]: [NitrosSubscriber]   data_format_name: nitros_image_rgb8
[component_container_mt-2] [DEBUG] [1721642150.181970516] [disparity]: [NitrosSubscriber]   msg_base: 
[component_container_mt-2] [DEBUG] [1721642150.181977406] [disparity]: [NitrosSubscriber]   Receiver's pointer: 0x7ab9cc003ef0
[component_container_mt-2] [DEBUG] [1721642150.181985296] [disparity]: [NitrosSubscriber] Updated frame_id=oak_right_camera_optical_frame
[component_container_mt-2] [DEBUG] [1721642150.182036556] [disparity]: [NitrosSubscriber] Pushed a message entity (eid=2243) to the appliation
[component_container_mt-2] [DEBUG] [1721642150.182050566] [NitrosTypeBase]: [Destructor]Dstroying a Nitros-typed object for handle = 2243
[component_container_mt-2] [DEBUG] [1721642150.182056656] [NitrosTypeBase]: [Destructor]Dstroying a Nitros-typed object for handle = 2243
REB427 commented 4 months ago

Hi Johannes, I had a similar issue with an OAK camera. Nvidia EES Node needs images from left and right camera with same timestamp. You can configure depthai-ros to publish rectified synchronised left and right images. This is the config I used for a OAK-D-Pro_W POE camera:

/oak: ros__parameters: camera: i_ip: '192.168.24.81' i_enable_ir: false i_pipeline_type: Depth i_nn_type: none left: i_fps: 20.0 i_resolution: 400P right: i_fps: 20.0 i_resolution: 400P stereo: i_publish_synced_rect_pair: true i_output_disparity: true

i_publish_synced_rect_pair is the important part. Published images will have same timestamp and will be rectified.

Hope this helps

JohannesPankert commented 4 months ago

Thank you for the help.

I tried to launch the camera with your parameters but the disparity node is still not producing results. How exactly is your pipeline setup? You take the rectified images from the camera, convert them to RGB, resize them and feed them into the disparity node? Are there any particular flags you had to set in the nvidia launchfiles?

REB427 commented 4 months ago
  1. I changed ImageConverter.cpp of depth_bridge to change output images to RGB.

  2. I run camera.launch.py with the parameter I sent you. I also added a mapping to the launch file because EES awaits images on the right topic: remappings=[('/oak/left/image_rect', '/left/image_rect'), ('/oak/right/image_rect', '/right/image_rect'), ('/oak/left/camera_info', '/left/camera_info'), ('/oak/right/camera_info', '/right/camera_info')]

  3. Check with rviz or ros2 topic echo if images are published on the right topics

  4. run EES (I changed no parameters) ros2 launch isaac_ros_ess isaac_ros_ess.launch.py engine_file_path:=${ISAAC_ROS_WS}/isaac_ros_assets/models/dnn_stereo_disparity/dnn_stereo_disparity_v4.0.0/ess.engine threshold:=0.0

Images will be resized to EES required size automatically, so no need for that. Also no need for recitfying because the published images are already rectified.

JohannesPankert commented 4 months ago

Thank you very much for your help. I got things to work with your parameters and figured out what was wrong with my setup.

I had the parameters left.i_publish_topic: true and right.i_publish_topic: true set which caused double publishing of both raw and rectified camera info messages on the /left/camera_info and /right/camera_info topics. For future readers: Make sure that those parameters are set to false to only get the rectified camera_info messages.