fzi-forschungszentrum-informatik / gpu-voxels

GPU-Voxels is a CUDA based library which allows high resolution volumetric collision detection between animated 3D models and live pointclouds from 3D sensors of all kinds.
Other
304 stars 85 forks source link

Convert octomap into gpu-voxel #48

Open xtycoon opened 7 years ago

xtycoon commented 7 years ago

Hi, I found this project from this issue in Octomap.

I wanna know whether there is an approach to convert my octomap into the gpu-voxel octree with out the origin pointcloud.

Squelsh commented 7 years ago

Hi! The file formats are incompatible. As far as I can remember, we once had the OctoMap linked in our code, to share the High-Level-API with GPU-Voxels. Mainly for performance comparisons. But I am quite sure, that the common data was a PointCloud which was inserted into OctoMap and GPU-Voxels.

BUT: Have a look at the serialization functions of GPU-Voxels and Octomap. Both offer a Save-to-File function: https://github.com/fzi-forschungszentrum-informatik/gpu-voxels/blob/master/packages/gpu_voxels/src/gpu_voxels/octree/GvlNTree.hpp#L484 and a corresponding Read-from-File.

I am sure that you can write a converter. On GPU-Voxels side, the serializer generates a list of Octree-Nodes, stating their status: See gpu-voxels/packages/gpu_voxels/src/gpu_voxels/octree/EnvNodesProbabilistic.h for the data structure of probabilistic nodes or gpu-voxels/packages/gpu_voxels/src/gpu_voxels/octree/RobotNodes.h for BitVector nodes.

See https://github.com/fzi-forschungszentrum-informatik/gpu-voxels/blob/master/packages/gpu_voxels/src/gpu_voxels/octree/NTree.hpp#L3205

Hope this helps! If you are doing this, I am happy to support you. And even happier, if you send me pull requests (:

Squelsh commented 7 years ago

Oh, BTW: The GPU-Voxels Octree is serialized as a stream of Leaf-Nodes. So all information is extracted as minimal sized Voxels (can be interpreted as pointcloud of the voxel-centers together with occupancy information). Perhaps the Octomap can do this, too? Then the conversion would be super easy.

xtycoon commented 7 years ago

Octomap seems also serialized by coordinate of the each cell's center. I do not require gpu-voxel directly read the file of octomap.

I am currently converting the octomap into a pointcloud vector in which elements are the center of the octomap's leaf nodes and insert those pointclouds into a gpu-voxel octree, as the following code shows. `
//otsize is read from octomap

   gvl = gpu_voxels::GpuVoxels::getInstance();
  gvl->initialize(otsize.x, otsize.y, otsize.z, myOctomap.getResolution());
  gvl->addMap(gpu_voxels::MT_BITVECTOR_OCTREE,"octree");
  vector<Vector3f> pointClouds;

for(OcTree::leaf_iterator it = ot.begin_leafs(), end = ot.end_leafs(); it != end; ++it)
{
    Vector3f vector3f(it.getX(),it.getY(),it.getZ());
    pointClouds.push_back(vector3f);
}

gvl->insertPointCloudIntoMap(pointClouds,"octree",eBVM_OCCUPIED);

` Are there any problems with this approach?

Squelsh commented 7 years ago

This was my first idea. A problem will occur, if you have a larger Octree-Node, which is completely occupied. I don't know, how the OctoMap will serialize this: Will it be broken down into hundreds of small Leaf nodes (like GPU Voxels does)? Or will it be exported as an annotated inner node, together with its size/level in the tree?

In the first case, you can use the proposed method. Otherwise you would need a helper function to manually generate the leaf nodes from an inner node.

The other thing that you will loose is the information about the free space. Or can you also export the free-space nodes from OctoMap (if OctoMap has free space representation).

xtycoon commented 7 years ago

As far as I know (in my current work) , leaf nodes of octomap are same which means I do not concern about the multi-resolution problem. Therefore , if there is a large node which is completely occupied and the node is not a leaf node, the node is also break up into several occupied child nodes.

wendwosen commented 5 years ago

Hello @Squelsh. I wanted to know if @xtycoon managed to convert the octomap pointcloud to a form compatible with gpu-voxels point cloud using the method proposed above. I am intending to use a simulated pointcloud from ros.

thank you.

cjue commented 5 years ago

Hi @wendwosen, please excuse my late reply.

If I understand correctly, you want to directly insert a PointCloud from ROS to GPU-Voxels. There is already an example for subscribing to a sensor_msgs/pointcloud2 and inserting it into GPU-Voxels data-structures.

Or is your input already in octomap?