introlab / rtabmap_ros

RTAB-Map's ROS package.
http://wiki.ros.org/rtabmap_ros
BSD 3-Clause "New" or "Revised" License
966 stars 557 forks source link

Clear free space for big areas #467

Open BaptisteLucas opened 4 years ago

BaptisteLucas commented 4 years ago

Hi, I'm using RTABMAP for mapping with RGBD camera and robot odometry. It works very well for pretty small size area, but the total area can be rather big. But for a big arear it doesn't works at all because it doesn't clear free space. My camera provide depth datas from 0.25m to 5.5m but accurate datas from 0.25m to 3.0m Rtabmap is configured with: Grid/RangeMax = 3.0 cloud_max_depth = 5.5 Vis/MaxDepth = 5.0 If the robot see an obstacle until 3.0m away, an obstacle is marked into the map and all the arear between the camera and the obstacle is cleared (free space) : it works perfectly. If obstacles are far than 3m, the area from the robot to 3m away (into the field of view of the camera) needs to be cleared. But for now it stills unknow arear. So I cannot map a large room becaurse all the center of the room will still unknow area instead of free space.

Maybe I forgot a parameter ?

BaptisteLucas commented 4 years ago

Edit: It seems that I need to use laserscan for mapping with raytracing. I tried but an other problem appears ! if there is a Nan value into my laserscan topic, then the corresponding scan angle is marked as cleared (free space) into the map. That create some map behind walls, very not good! I tried to remove Nan values from my laserscan and replace it by a small values 0.26m and to set the Grid/RangeMin to 0.3m. But the corresponding scan angle still marked as empty area (until Grid/rangeMax distance). I hope these data will be ignored but not. I tryed to set "map_empty_ray_tracing" and "Grid/RayTracing" to false without any success.

Any ideas ?

screenShot_Rviz-laserscan

matlabbe commented 4 years ago

Hi, I did some experiments with this example and I cannot reproduce what you are seeing. When using the laser scan of the the bag and setting your range limits by adding:

<param name="Grid/RangeMin"   type="string" value="0.25"/>
<param name="Grid/RangeMax"   type="string" value="3"/>

to demo_robot_mapping.launch, I get this:

roslaunch rtabmap_ros demo_robot_mapping.launch rviz:=true rtabmapviz:=false
rosbag play --clock demo_mapping.bag

Screenshot from 2020-09-27 13-33-57

I also checked how invalid values are set in the laser scans, they are set of inf. They should be ignored for ray tracing.

Ray tracing should also work when using RGB-D camera when Grid/FromDepth=true. To test this, set Grid/FromDepth to true here, then add those parameters:

<param name="Grid/RangeMin"   type="string" value="0.25"/>
<param name="Grid/RangeMax"   type="string" value="3"/>
<param name="Grid/RayTracing"   type="string" value="true"/>
<param name="Grid/MaxObstacleHeight" type="string" value="1"/>

Here is the result:

roslaunch rtabmap_ros demo_robot_mapping.launch rviz:=true rtabmapviz:=false
rosbag play --clock demo_mapping.bag

Screenshot from 2020-09-27 13-39-37

You can also check figures 14 to 16 of this paper for more examples.

cheers, Mathieu

BaptisteLucas commented 3 years ago

Hi Mathieu, Thank you for this detailed analyze. The only differance that I found is the invalid data format. In my case it is Nan and for you it's Inf. I will try to change Nan by Inf into the laserscan topic to be sure.

regards, Baptiste