How does rtabmap deal with dynamic objects?

classic Classic list List threaded Threaded
12 messages Options
Reply | Threaded
Open this post in threaded view
|

How does rtabmap deal with dynamic objects?

asabet
When I simulate rtabmap in gazebo, the point cloud and occupancy cells corresponding to the missing object is not removed upon subsequent rescans of the area.
Reply | Threaded
Open this post in threaded view
|

Re: How does rtabmap deal with dynamic objects?

matlabbe
Administrator
Hi,

For the general point cloud created in rtabmapviz or MapCloud rviz plugin, objects won't be cleared. For the occupancy grid, it should clear missing objects, as long as the sensor can see the floor under it or that laser scans can hit another object/wall behind the area of the missing object. If you have screenshots or even a database to share, it would be easier to see the problem.
Reply | Threaded
Open this post in threaded view
|

Re: How does rtabmap deal with dynamic objects?

FeKl
Hi Mathieu,

I've another question/remark concerning dynamic objects in a dynamic environment.

I think, the best way is to remove the dynamic object in the depth image (via setting the value to 0 with a corresponding bounding box which surrounds the object). To do this, it could be possible to use an object detection algorithm:
1. Detect the object with the bounding box
2. mask the depth image with the corresponding bounding box
3. feed rtabmap with the rgb image and the masked depth image

But what about the problem if the object detector does not always detect the object? It could be possible that in one frame, a specific object has been detectet, but in the next frame it has NOT been detected. This would affect the 3D map (cloud_map) as well the odometry...

Can you give me some hints how to deal with this problem, especially in ROS and with the published topic "cloud_map"?

Kind regards,

Felix
Reply | Threaded
Open this post in threaded view
|

Re: How does rtabmap deal with dynamic objects?

matlabbe
Administrator
Hi Felix,

For odometry, as long as most features tracked are from structures that are static, it would not affect too much the performance.

For mapping, if spurious objects are added to map, they will indeed appear in cloud_map. You would then need to use octomap_occupied_space instead in which dynamic objects can be cleared. This has however a cost, as 3D ray tracing should be done.

cheers,
Mathieu
Reply | Threaded
Open this post in threaded view
|

Re: How does rtabmap deal with dynamic objects?

FeKl
Hi Mathieu,

thanks for your answer.

Did you already tried this, removing dynamic obstacles (e.g. persons) via using octomap_occupied_space?

If yes, can you give me a hint/pipeline of doing this in realtime with ROS? That means: How can I do ray tracing with octomap_occupied_space?

Kind regards,

Felix
Reply | Threaded
Open this post in threaded view
|

Re: How does rtabmap deal with dynamic objects?

matlabbe
Administrator
See Figure 7 of the "RTAB-Map as an Open-Source Lidar and Visual SLAM Library for Large-Scale and Long-Term Online Operation" paper:


Parameters are:
Grid/FromDepth=true
Grid/3D=true
Grid/RayTracing=true

To clear moving people, the sensor should be able to see the background (e.g., a wall behind where the person was). If you see Table 10 in the paper, the computation time is quite high when a loop should be closed.

If you don't need 3D point clouds and if only a 2D map from projected 3D obstacles would be enough, consider using the 2D occupancy grid with tracing instead (grid_map):
Grid/FromDepth=true
Grid/3D=false
Grid/RayTracing=true

cheers,
Mathieu
Reply | Threaded
Open this post in threaded view
|

Re: How does rtabmap deal with dynamic objects?

PeterGa
Hi,

I've tried all the suggestions from the posts above. None worked. Since the discussion is already a few years old, are there any updates regarding this topic?

I want to create a cost map in a dynamic environment using only a RGB-D camera (first in a gazebo simulation). My current setup works fine in a static environment, but when I add moving objects to the simulation, the cost map gets useless over time. I've also tried a filter approach for the rgbd camera, where moving objects are removed from the point cloud, but no satisfying result so far.

I would really appreciate some help or alternative ideas.
Reply | Threaded
Open this post in threaded view
|

Re: How does rtabmap deal with dynamic objects?

matlabbe
Administrator
Hi,

Do you have screenshots of the environment, things to clear?

To see obstacles removed from the point  cloud, make sure to visualize octomap_cloud topic, not map_cloud or mapData. For RGB-D 3D obstacles clearing, make sure Grid/FromDepth is true, Grid/3D is true and Grid/RayTracing is true.

Note that if you are moving in 2D, setting Grid/3D=false can give good results with a lot less computation time.

cheers,
Mathieu
Reply | Threaded
Open this post in threaded view
|

Re: How does rtabmap deal with dynamic objects?

PeterGa
This post was updated on .
Hi Mathieu,

thanks for your reply. I've attached a screenshot that shows the
environment in which the simulated drone is flying. The simulation world
consists mostly of static objects, except for one model of a human,
which is moving up and down on a straight line. I subscribed to the
topic /octomap_grid and set the three parameters that you've mentioned
to true.

On the rviz-image you can see the result. The clearing of dynamic
obstacles does work to some small degree. Every few seconds, a couple of
obstacle points are removed from the grid map, but most of the dynamic
obstacle points are still there. Is it possible to improve the clearing
performance of the octomap with some parameter changes? For instance an
increased update rate or so?

PS: Do you know,  in which launch file of rtabmap_ros I can find the
parameters Grid/3D and Grid/RayTracing? I couldn't find them so I had to
set them manually to true with rosparam set ...

Thanks for your help.

Best regards,
Reply | Threaded
Open this post in threaded view
|

Re: How does rtabmap deal with dynamic objects?

matlabbe
Administrator
Hi,

Parameters can be set under rtabmap node:
<node pkg="rtabmap_ros" type="rtabmap" name="rtabmap" args="-d">
  <param name="Grid/3D" value='true"/>
  <param name="Grid/RayTracing" value='true"/>
  ...
</node>

or

<node pkg="rtabmap_ros" type="rtabmap" name="rtabmap" args="-d --Grid/3D true --Grid/RayTracing true">
  ...
</node>

or if you use rtabmap.launch:
roslaunch rtabmap_ros rtabmap.launch args:="-d --Grid/3D true --Grid/RayTracing true"

To clear obstacles with ray tracing, when the object is not there anymore, the camera/lidar should "see" ground or obstacle behind the occupied cells to clear them, so that ray tracing can ray cast through those occupied cells and change their occupation probability. In your environment:

there are no walls, so if some occupied cells are added 1 meter over the ground and the npc move, there only emptiness behind the occupied cells, so they are likely to stay there.
Reply | Threaded
Open this post in threaded view
|

Re: How does rtabmap deal with dynamic objects?

PeterGa
Thanks.

Placing a wall behind the dynamic object helped the removal of "outdated" points from the octomap_grid. But it still takes several approaches with the drone from different angles until the outdated points from the dynamic obstacle are finally removed. Is this behavior expected when using only a rgbd camera or should the point removal work faster? Would a lidar sensor improve the clearance performance?

I've created a screen cast which shows that behavior. I hope the provided link works for you.

https://www.dropbox.com/s/ohp4l6yb6j8oa4u/Octomap_grid_with_wall.mp4?dl=0

On the video you will see the drone flying around in the simulated world. On the bottom left there is the rgb image of the drone's camera and the the depth image of that camera. Note that the depth image is run through an algorithm that tries to filter out dynamic object in the image (which only works to some degree). So only the the points of the dynamic object that make it through the filter will be shown in the octomap_grid.

Do you think that there is a possibility to further improve the clearing of the dynamic obstacles based on the video? For instance using additional sensors or a higher update frequency for the octomap_grid?

Thank you really much for your help.
Reply | Threaded
Open this post in threaded view
|

Re: How does rtabmap deal with dynamic objects?

matlabbe
Administrator
Hi,

some related parameters to occupancy grid thresholds: https://github.com/introlab/rtabmap_ros/issues/269#issuecomment-413649116

For the problem of clearing obstacles from OctoMap, here is an example:


If the field of view of the camera cannot see the whole space where the object disapeared, there will be remaining occupied cells outside the clearing field-of-view of the camera. A workaround could be to set Grid/3D to false, though you may lost track of 3D obstacles.

cheers,
Mathieu