Multiple pointcloud input

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

Multiple pointcloud input

derektan1995
Hi Mathieu,

Hope you are well. I am currently trying out 3D mapping and localization (i.e. 3D SLAM). I hope to to use an external point cloud segmentation tool instead of the one in Rtabmap. Is it possible to input an unfiltered pointcloud into rtabmap for localization (ICP), and a segmented pointcloud into rtabmap for mapping (Grid)?

Regards,
Derek
Reply | Threaded
Open this post in threaded view
|

Re: Multiple pointcloud input

matlabbe
Administrator
Hi Derek,

With subscribe_scan_cloud=true and topic scan_cloud remapped to your unfiltered pointcloud, rtabmap could use it for mapping/localization.

For the occupancy grid, there are currently no input topics for this. This could be indeed a convenient new option when the current segmentation approaches (based on normals (default) or by passthrough filter) cannot be used or are not appropriate for the application. We would need however to think what is the best approach to input that kind of info. My first thought would be to extend RGBDImage topic with PointCloud2 msgs for obstacles, ground and empty cells. The idea is to avoid another layer of optional topics to be synchronized for rtabmap node. The user would have to synchronize himself the topics into a RGBDImage msg and provide that RGBDImage to rtabmap node.

The above however destroys the purpose of RGBDImage that is visual-only. To avoid the user to have to synchronize himself the topics, we would need to add a new msg type "rtabmap_ros/LocalOccupancyGrid" and add it to all possible subscribers of rtabmap node (when a parameter called subscribe_local_grid=true). This requires significantly more works to implement but it would be more general I think. The msg could be:
Header header
sensor_msgs/PointCloud2 obstacles
sensor_msgs/PointCloud2 ground
sensor_msgs/PointCloud2 empty
float32 cell_size
# the grid viewpoint would be computed from the frame_id set in the main header

On rtabmap library side, this would have to be moved up before the first if so that if the input SensorData has already occupancy grid set, we don't regenerate it.

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

Re: Multiple pointcloud input

derektan1995
Hi Mathieu,

Thanks for the reply. I think I will go with the approach of adding the segmented pointcloud topics into 'RGBDImage' to test if it works first. I will then proceed to abstract the 'scan_cloud' topic to contain both the raw pointcloud (for localization) and segmented pointcloud ('obstacle' portion for mapping).

matlabbe wrote
On rtabmap library side, this would have to be moved up before the first if so that if the input SensorData has already occupancy grid set, we don't regenerate it.
 May I check, what do you mean by 'before the first'? From my understanding, the segmented pointcloud topic has to be compressed into a 2D gridmap first. Would I have to perform the compression explicitly somewhere?

In addition, may I check if the clustering and segmentation functionality of the Obstacle Detection Nodelet is embedded inside the core rtabmap node? Both seems to be taking in similar parameters such as 'Grid/MaxGroundAngle' and 'Grid/ClusterRadius' and 'Grid/MinClusterSize'.
Reply | Threaded
Open this post in threaded view
|

Re: Multiple pointcloud input

matlabbe
Administrator
Hi,

The "before the first" is before the first "if", between those lines.

The Obstacle detection nodelet uses exactly the same code used for segmentation inside rtabmap, it is why the same parameters are used.

cheers,
Mathieu