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

RTABMAP non-overlapping 3D cloud

asked 2017-08-02 12:01:56 -0500

lealem gravatar image

updated 2017-08-04 09:10:13 -0500

Hi, I am using rtabmap using stereo on a robot. Everything seems to work fine, except that the MapCloud does not contain registered clouds. The individual 3D maps (from different graph nodes) "supposedly" are not registered to each other. For example there are multiple (3 or 4) replica of the same scene which are not registered. Here are some details.

Please help, thanks!

edit retag flag offensive close merge delete

Comments

Could you give us details on how you launched RTABMap, what ROS topics you're having difficulties with, the result of view_frames ?

Blupon gravatar image Blupon  ( 2017-08-03 06:08:28 -0500 )edit

I would say the problem is with the cloud data (mapping result), everything else seems to work perfect! And I am launching using the "stereo_mapping.launch" file, with minor modifications (like topic names etc) ps. all the demos work as expected

lealem gravatar image lealem  ( 2017-08-03 09:47:49 -0500 )edit

If you can share the resulting database (dropbox or google drive link), it can be useful.

matlabbe gravatar image matlabbe  ( 2017-08-03 11:08:13 -0500 )edit

here is a link to the launch file i used and the rtabmap database database https://www.dropbox.com/sh/vtp0xao60f... launch file https://www.dropbox.com/s/eiumj3fzs7b...

lealem gravatar image lealem  ( 2017-08-03 13:06:33 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
2

answered 2017-08-04 10:40:39 -0500

matlabbe gravatar image

updated 2017-08-04 10:45:30 -0500

Hi lealem,

At first view the optimized trajectory after loop closure looks good: image description

For the 3D map, there are indeed some problems with the 3D projection. I noticed that the scale of some point clouds are not the same, which would be caused by a poor synchronization between the left and right frames, in particular when the robot is rotating. Here two examples of frames taken before and after rotating at the same place: image description image description

In first screenshot the far wall is about ~10/11 meters from the robot, as in the second screenshot the far wall is about ~5-6 meters from the robot. When rotating, as left and right frames are not synchronized, the disparity changes, making objects appearing more closer. With stereo, it is strongly recommend to use exactly synchronized cameras (e.g., hardware synchronization between left and right cameras), then with rtabmap use approx_sync parameter set to false.

PS: To get the 2D grid map as above, I used parameters: Grid/MaxObstacleHeight=2, Grid/NoiseFilteringRadius=0.15, Grid/NoiseFilteringMinNeighbors=10, Grid/NormalsSegmentation=false, Grid/3D=false and Grid/ProjRayTracing=true.

EDIT: just noticed that you were using approx_sync because of wheel odometry. To use approx_sync=false with wheel odometry, set odom_frame_id so that rtabmap uses TF to get odometry instead of the topic (for which approx_sync should be true).

cheers, Mathieu

edit flag offensive delete link more

Comments

Hi Mathieu, Thank you for the insight. Changed my stereo setup to the "ZED" and works like a charm!

Best, Lealem

lealem gravatar image lealem  ( 2017-08-16 12:00:50 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2017-08-02 12:01:56 -0500

Seen: 561 times

Last updated: Aug 04 '17