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

Revision history [back]

Are you saying that each of your single point cloud contains > 91 Mio points? There is no way octomap_server can handle that with 60 Hz. The most expensive operation is the 3D ray casting, and that is done for each single ray. You may not need all of these points if you are only interested in a resolution of 5cm. I would suggest running a PCL voxel_grid filter first to down-sample your point clouds. You could avoid the expensive ray casting by just updating the end points in the map as occpuied, this merging free and unknown space (but losing the ability to clear out volumes). You would need to write this yourself in ROS using OctoMap.

Another bottleneck with large point clouds may be the serialization and deserialization when running it through a filtering and map building pipeline. I'm pretty sure that any ROS node just doing this with 91 Mio pts at 60Hz will also saturate the CPU. You can avoid that by using the nodelet version (new feature in trunk).

To get an idea of the performance of just octomap map building (which octomap_server uses) you can run our tool "graph2tree" that should be in your ROS installation. You can create the source scan graph files yourself or use one of our example data sets.

From my own experience, octomap_server can handle point clouds from the Kinect with a resolution of 2.5cm at 10 Hz in a tabletop setting (e.g. for manipulation).