speedup insertPointCloud

268 views
Skip to first unread message

Pierrick Koch

unread,
Jun 11, 2014, 3:58:31 AM6/11/14
to oct...@googlegroups.com
Hello everyone,

I am interested in using octomap's binary tree in a specific case
where I only wish to keep each scan in separate files, I need an
efficient file structure both in memory usage and time to build/save.

For example, my scans come from a Velodyne HDL-64 (~100m range),
I want to down-sample 512 scans at 0.1m:
- with PCL+VoxelGridFilter, mean time is 0.023 seconds per scan, mean
file size (.pcd) is 726 KB.
- with octomap, mean time is 1 second, mean file size (.bt) is 171 KB.

Is there any way to speedup the octomap::OcTree::insertPointCloud method ?
ie. is there a way to get the `.bt` file structure without raycasting ?

See the valgrind graph resulting of 25 iterations[1].

[1] http://homepages.laas.fr/pkoch/pub/octomap-hdl64.png

Cheers,
--
Pierrick Koch

Felix Endres

unread,
Jun 11, 2014, 4:20:58 AM6/11/14
to oct...@googlegroups.com
Hi

Am 11.06.2014 09:58, schrieb Pierrick Koch:
> Hello everyone,
>
> I am interested in using octomap's binary tree in a specific case
> where I only wish to keep each scan in separate files, I need an
> efficient file structure both in memory usage and time to build/save.
>
> For example, my scans come from a Velodyne HDL-64 (~100m range),
> I want to down-sample 512 scans at 0.1m:
> - with PCL+VoxelGridFilter, mean time is 0.023 seconds per scan, mean
> file size (.pcd) is 726 KB.
> - with octomap, mean time is 1 second, mean file size (.bt) is 171 KB.
>
> Is there any way to speedup the octomap::OcTree::insertPointCloud method ?
> ie. is there a way to get the `.bt` file structure without raycasting ?

That way you would loose the distinction between "free" and "unknown".
If that is okay for you, you could insert your VoxelGridFiltered cloud
manually, i.e., by iterating over the cloud, using something like
ocTree.setNodeValue(cloud.x,cloud.y,cloud.z, ocTree.clamping_thres_max);
for every point.

Cheers,
Felix

Armin Hornung

unread,
Jun 11, 2014, 9:02:25 AM6/11/14
to oct...@googlegroups.com
You will also lose the ability to clear previously seen endpoints (e.g.
to correct sensor noise). But if you really just want to store the end
points, what Felix suggested works best and will result in much smaller
files. Alternatively, you can use
"octree.updateNode(cloud.x,cloud.y,cloud.z, true)".

You could also (as alternative or in addition) pre-sample your data with
PCL before insertion or use the flag "discretize" (newly added) in
insertPointCloud(). There is also parallelization support which you need
to enable during CMake configuration with the flag OCTOMAP_OMP (and tune
with the env. var OMP_NUM_THREADS).

More details on how to speed up scan insertions were discussed
previously on this list, e.g. here:
https://groups.google.com/forum/#!topic/octomap/rsD2tPs-6tc

Cheers,
Armin

--
Dr. Armin Hornung
Humanoid Robots Lab, Albert-Ludwigs-Universitaet Freiburg
Contact: http://www.informatik.uni-freiburg.de/~hornunga

Reply all
Reply to author
Forward
0 new messages