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

When using rtabmap to build a map, how to fill the blanks in the map and remove objects outside the map?

asked 2020-03-31 08:29:13 -0600

willzoe gravatar image

The robot I use is turtlebot2, and I use a ZED stereo camera instead of an RGBD camera, without using a lidar sensor.

When I used the rtabmap algorithm to make my robot build a map in the room, I found that the results were as shown below:

image description

Radial black parts on the right, bottom, and left should not have appeared on the map because they are beyond the scope of the room.

I want to know how to remove them?

The light gray part in the middle (L-shaped, with path passing) is empty without obstacles. But they don't seem to be completely filled, and some are left blank (around the start and end of the path).

What should I do to make these areas that should be ground also marked light gray?

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
2

answered 2020-04-03 16:54:50 -0600

matlabbe gravatar image

To remove far points, set a max range for the local occpuancy grids. To fill unknown space, we need to enable ray tracing (which is enabled by default using a lidar). Here are two approaches:

2D approach: faster/less memory, though obstacles may be cleared wrongly if they don't appear in the field of view of the camera

Grid/RangeMax=3
Grid/RayTracing=true
Grid/3D=false
Grid/MaxObstacleHeight=2

3D approach: slower/more memory needed, ray tracing is done in 3D, so it is safer for obstacles that camera don't see anymore

Grid/RangeMax=3
Grid/RayTracing=true
Grid/3D=true
Grid/MaxObstacleHeight=2

If you can assume that all obstacles in front of the robot can always be seen in the field of view of camera, I would go for the 2D case for cpu/memory efficiency.

edit flag offensive delete link more

Comments

If I use the above 2D method or 3D method, do I have to add a lidar to the robot?

Can I enable ray tracing when only using zed stereo camera, and then configure the above parameters to fill the unknown space?

willzoe gravatar image willzoe  ( 2020-04-06 22:27:25 -0600 )edit
1

No, they work also with the depth image of the camera. The map you are seeing is from depth image in 3D by default (without ray tracing). Ray tracing can be enabled with cameras.

matlabbe gravatar image matlabbe  ( 2020-04-08 09:16:54 -0600 )edit

How to enable ray tracing with cameras? I refer to zed_nodelet_example and use depthimage_to_laserscan node to convert the depth image generated by the camera into 2D scan. Is this method feasible?

By the way, this example zed_nodelet_example uses nodelet, and I use node. Which one should I choose?

willzoe gravatar image willzoe  ( 2020-04-08 10:04:21 -0600 )edit

I have enabled ray tracing, and the resulting 2D map has no holes.

willzoe gravatar image willzoe  ( 2020-04-09 10:59:22 -0600 )edit
1

We can also convert the depth image to a laser scan, for which RTAB-Map will do ray tracing by default. It is not necessarily though, as if you set parameter Grid/RayTracing to true, it will also do it with depth images. In general, using nodelet is the preferred approach for efficiency. For example, if two nodelets are in the same manager and images should be shared between them, the image topics won't be serialized and deserialized, only a copy of the pointer in memory would be required.

matlabbe gravatar image matlabbe  ( 2020-04-17 14:58:58 -0600 )edit

1) According to the above, when I set the parameter Grid / RayTracing to true and Grid / 3D to false, rtabmap convert the depth image to a laser scan. Is it possible for rtabmap to publish sensor_msgs / LaserScan type topics? (By using rostopic find sensor_msgs / LaserScan I did not find the related topic published by rtabmap.)

2) I found two similar parameters gen_scan_max_depth and Grid/RangeMax. I want to know what is the difference between them.

3) The following warning is displayed:

[ WARN] [1588091904.327305697]: /proj_map topic is deprecated! Subscribe to /grid_map topic instead.

What parameters should I set to enable /proj_map topic to be published?

willzoe gravatar image willzoe  ( 2020-04-28 04:20:23 -0600 )edit
  • /proj_map is exactly the same topic than /grid_map. If you need a laser scan topic, use pointcloud_to_laserscan or depthimage_to_laserscan. Rtabmap doesn't republish it, it is actually converted in its local occupancy grid format (all those Grid/ parameters).

  • gen_scan_max_depth works with gen_scan argument to rtabmap node, it will make a scan exactly like depthimage_to_laserscan node (the advantage is that it can support multiple cameras to create the scan, assuming the depth cameras are installed like on a rig parallel to ground).

  • When using Grid/RayTracing to true and Grid/3D to false, it will do something like pointcloud_to_laserscan, for arbitrarily any 3D point clouds (projecting obstacles to ground then ray tracing to them).

matlabbe gravatar image matlabbe  ( 2020-05-12 11:22:39 -0600 )edit

Question Tools

2 followers

Stats

Asked: 2020-03-31 08:29:13 -0600

Seen: 1,346 times

Last updated: Apr 03 '20