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

octomap_server performance issues?

asked 2013-01-13 12:22:36 -0600

anonymousSnowMan gravatar image

updated 2013-01-13 17:17:29 -0600

Hi,

I'm currently running octomap_server from the latest svn (checked out on 10/01/13) under ROS-Fuerte.

EDIT1: I'm working with complex 3d laser scan data which is moving at a reasonable speed (1m/s, perhaps more). The sensor data is of a building and grounds complex covering 300m by 200m by 50m in elevation throughout the loop.

EDIT2: More details about the point cloud and ROS .bag file:

Point cloud contains over 91,000,000 individual points
ROS .bag file contains over 90,000 messages

If I publish the data in real time (playing back a .bag file through rosbag which contains the PointCloud2 scan and relevant transform), octomap_server quickly falls behind and within 60 seconds it hits 100% CPU load and starts to drop scans. This has been observed on both a Core 2 Duo and a Core i7 (1st generation), both with 4gb of RAM under Ubuntu 11.10.

Is this an issue with the configuration paramaters in the .launch file? Currently latch is 'false', 'sensor_model/max_range' is '3.0' and resolution is '0.1' (I would prefer 0.05, but it can't even handle 0.1).

Would there be a significant performance increase by implementing an octomap octree in code outside of octomap_server; i.e. write my own node?

Is octomap_server capable of operating with real-time sensor data?

Thanks in advance.

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
4

answered 2013-01-13 22:00:50 -0600

AHornung gravatar image

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).

edit flag offensive delete link more

Comments

The entire data set contains over 91 million points, consisting of 90000 individual scans of around 1080 points each (40Hz Hokuyo). The problem with down-sampling is that many points are only seen by the laser once, potentially resulting in lost points from the down-sample?

anonymousSnowMan gravatar image anonymousSnowMan  ( 2013-01-14 10:29:46 -0600 )edit

Additionally; the CPU load hits 100% (and hence drops points) even when publishing at a rate of 0.01, or approximately 0.4 Hz. Albeit it takes a lot longer to reach that point. With the ray casting only being done from the current sensor position, what is generating this CPU load over time?

anonymousSnowMan gravatar image anonymousSnowMan  ( 2013-01-14 10:56:39 -0600 )edit

So, your single point clouds are in truth 2D laser lines? Is the laser mounted fixed (similar to the New College dataset), or do you obtain 3D pointclouds on a pan-tilt unit? In the latter case I would combine all scans from a similar viewpoint into a single pointcloud and batch-insert that.

AHornung gravatar image AHornung  ( 2013-01-17 02:06:05 -0600 )edit

The insertion of complete 3D clouds is optimized in OctoMap, it will be much faster. Down-sampling (PCL voxelgrid) will only remove points close to others, not single isolated ones.

AHornung gravatar image AHornung  ( 2013-01-17 02:07:53 -0600 )edit

To get details about what's taking long, set the log level of octomap_server to DEBUG with rxconsole or use a profiler: http://answers.ros.org/question/31278/how-to-generate-call-graph-for-ros-code/ (this should be easier in "plain" OctoMap conversion with graph2tree, offline without ROS)

AHornung gravatar image AHornung  ( 2013-01-17 02:11:21 -0600 )edit

Finally: I just sped up map building in OctoMap by 20-30% using OpenMP, feedback and further contributions are welcome! https://github.com/OctoMap/octomap ("devel-openmp" branch)

AHornung gravatar image AHornung  ( 2013-01-17 02:12:45 -0600 )edit

Performance on the existing source build of Octomap was greatly increased by increasing the chunk size of the point cloud being fed to octomap_server. I've opened a new question with regards to the devel-openmp branch installation problems.

anonymousSnowMan gravatar image anonymousSnowMan  ( 2013-01-20 11:21:09 -0600 )edit

AHornung, just being curious and currently troubled, you said octomap can manage a 10Hz framerate from kinect pointclouds. Currently I am executing it but the rate I get for the /occupied_cells_vis_array topic is between 0.5 and 0.3 Hz. Could you elaborate on the setup you had?.

Aridane gravatar image Aridane  ( 2013-12-10 04:56:00 -0600 )edit

Question Tools

Stats

Asked: 2013-01-13 12:22:36 -0600

Seen: 1,951 times

Last updated: Jan 13 '13