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

rtabmap error "Could not find any PointCloud dataset with id <cloudX>"

asked 2018-03-14 11:40:13 -0500

Haloi gravatar image

updated 2018-03-18 13:04:36 -0500

gvdhoorn gravatar image

Hello together,

im trying to run rtabmap with a naneye stereo cam. The images are rectified and published. While using rtabmap in normal stereomapping mode the error Could not find any PointCloud dataset with id <cloudX> for increasing X appears many times.

Im using the stereo_mapping.launch and only changed approximate sync and topic namespace. And kinetic full installation.

I tried different systems and reinstalled whole ubuntu and ros. Same error ocours again.

Thanks ahead!

Update:

Ros StereoCalibration was used for calibration. And Matlab determines nearly the same values. Only Tx is scaled in mm and Ty != 0 but small. stereo_image_proc is publishing a disparity image, but i can only recognize some edges. I tried to view the Pointcloud2 in rviz but the error: For frame [base_link]: Fixed Frame [map] does not exist shows up. But while processing in Rtabmap Viewer a Point Cloud is shown.

camera_info:

left

header: 
  seq: 430
  stamp: 
    secs: 372000180
    nsecs:         0
  frame_id: "base_link"
height: 250
width: 250
distortion_model: "plumb_bob"

D: [-0.35042452418723935, 0.12846856164772108, -0.001983681892138987, -0.0007020150618879638, 0.0]

K: [216.32097302957894, 0.0, 116.68934823674309, 0.0, 216.72959680793943, 117.49881486113006, 0.0, 0.0, 1.0]

R: [0.9961427784023481, -0.08753401450757768, 0.006112392415202644, 0.08753067792426865, 0.9961614936500219, 0.0008117826527036613, -0.006159988552602093, -0.00027362957528120994, 0.999980989653247]

P: [212.49235049334482, 0.0, 124.71735668182373, 0.0, 0.0, 212.49235049334482, 114.55551147460938, 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

right

header: 
  seq: 1316
  stamp: 
    secs: 431303367
    nsecs:         0
  frame_id: "base_link"
height: 250
width: 250
distortion_model: "plumb_bob"

D: [-0.3571397802529545, 0.14349299686495984, 0.0007979733631606835, 0.000265477807614921, 0.0]

K: [217.01144313802783, 0.0, 116.14327950230813, 0.0, 217.53267767947415, 119.10319721480494, 0.0, 0.0, 1.0]

R: [0.9961499428754478, -0.08762582748298754, 0.0026468220876320063, 0.08762725374854638, 0.9961532420215907, -0.00042756328410479226, -0.0025991748170779505, 0.0006578508917368133, 0.9999964057547779]

P: [212.49235049334482, 0.0, 124.71735668182373, -263.97459304570816, 0.0, 212.49235049334482, 114.55551147460938, 48.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

Update new Images: http://ibb.co/fEoXcx http://ibb.co/h7E5xx http://ibb.co/m1odKc

Bagfile with 100 massages of each Topic:

https://www.dropbox.com/s/shijb3v5r7s...

edit retag flag offensive close merge delete

1 Answer

Sort by » oldest newest most voted
2

answered 2018-03-14 13:27:11 -0500

matlabbe gravatar image

updated 2018-04-06 10:51:39 -0500

cv::StereoBM (in rtabmap) may not be able to generate a disparity image, so the point cloud sent to PCLVisualizer is empty and not added, causing other functions assuming that the cloud is there to throw this error. If you send your stereo images to stereo_img_proc, can it produce a valid disparity image and a point cloud? Can you also update your question with an example of left and right images (those sent to rtabmap) with corresponding camera_info?

EDIT

After trying the bag, here some problems:

  1. Baseline is large: from right camera_info above, -(-263.97/212.49) = 1.24 m. What is the actual baseline between cameras (measured manually or from spec)?
  2. Because of (1), the scale of the point cloud generated is huge. By default on older rtabmap versions, the point clouds are filtered up to 4 meters in 3d Rendering settings. Set max depth to 0 to avoid filtering the clouds.
  3. The images (when comparing left and right) are not correctly rectified, there are some pixel errors along Y axis in images.
  4. You may need to set frame_id of images/camera_infos to "left_optical_frame" for example, and add a static_transform_publisher base_link -> left_optical_frame with transform "0 0 0 -1.570796327 0 -1.570796327" to that point clouds are correctly transformed in ROS coordinates.

A screenshot of the problems: image description Note the y error on left with superposed left and right images. On right the grid is 1 meter, frustums of both cameras are shown for reference (looking upward as there is no optical rotation).

EDIT2: When I tested the bag, I didn't see problem with the number of disparities. See doc of StereoBM. Note that the number of disparities will create a border without disparity values of the same size on the left of the image. On images of 200 pixels width and StereoBM/NumDisparities set to 128, you will have more than half of the image without disparity values. This can create empty clouds if no disparity can be computed for the other half. Thus number of disparities should be lowered for small images. Last note, if you are trying to map a white wall (textureless surface), disparity will be null, causing also an empty cloud. The recent code should not add to PCL visualizer an empty cloud, so the pcl error would not appear anymore.

edit flag offensive delete link more

Comments

Thank you! I have updated the Mainpost.

Haloi gravatar image Haloi  ( 2018-03-15 07:13:48 -0500 )edit

Images you linked are not rectified. If clouds are shown in rtabmap, you may ignore this "error". In recent code (since this commit), this error won't show if a cloud is not added to visualizer.

matlabbe gravatar image matlabbe  ( 2018-03-15 11:08:27 -0500 )edit

I´m Sorry! I updated the images you ask for and attached one image of rtabmap. I think rtabmap is showing only featurepoints. Ignoring the error wont help because rtabmap is crushing after a while. Do you think this problem is caused by bad calibration?

Haloi gravatar image Haloi  ( 2018-03-16 11:59:42 -0500 )edit

If you can record and share a rosbag of just the outputs of the camera (with its tf), it could be useful. In the picture, the yellow/green points are features used for odometry. The dense point cloud is indeed not shown. Can you show the disparity image output of stereo_img_proc?

matlabbe gravatar image matlabbe  ( 2018-03-16 12:15:42 -0500 )edit

I have added an image of the disparity map. Tomorrow i will post a bag file with images and camera_info. Thank you for helping! --> Bagfile is attached in mainpost!

Haloi gravatar image Haloi  ( 2018-03-17 09:40:23 -0500 )edit

Thank you very much! I'm very glad to see a Point Cloud! I'm one week away and than i will test this solution and post a Feedback.

Haloi gravatar image Haloi  ( 2018-03-19 12:43:47 -0500 )edit

Hello again, I have tried a lot and it seems as the setting "Number of disparity" of StereoBM influences that error. By changing this option from 128 to 32 the Error disappeare. Perhaps you know the reason and can update the solution?! Perhaps its a Problem of small resolution?

Haloi gravatar image Haloi  ( 2018-04-04 14:33:25 -0500 )edit

Perhaps is a small number of disparitys good if the calibartion is bad. I'm trying to improve this but the baseline is in mm so calibration is hard. The other problems where good to know too! And im intrested in, if the error appeared in your setup and what you changed exactly of your system. Thanku

Haloi gravatar image Haloi  ( 2018-04-04 14:34:09 -0500 )edit

Question Tools

Stats

Asked: 2018-03-14 11:40:13 -0500

Seen: 1,001 times

Last updated: Apr 06 '18