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
302 stars 85 forks source link

help getting voxel grid back from device #57

Open jvarley opened 6 years ago

jvarley commented 6 years ago

Hi,

I want to use your library to perform several operations on a voxel grid, after completion, I want to pull the voxel grid back of the device and pass it back to some other code I have. I was trying the following for a 40^3 voxel grid.

 voxellist::BitVectorVoxelList  *map = gvl->getMap("myHandVoxellist")->as<voxellist::BitVectorVoxelList>();

      MapType map_type = map->getTemplateType();
      uint32_t buffer_size = map->getMemoryUsage();
      char* buffer = new char[buffer_size];
cudaMemcpy((void*)buffer, map->getDeviceDataPtr(), buffer_size, cudaMemcpyDeviceToHost);

When I run the above code, my buffer is of size 32 40 40 * 40 how do I convert this data to a 40^3 bool array representing occupancy? I don't understand why there are 32 bits per voxel.

Thanks, Jake

Squelsh commented 6 years ago

Hi Jake, currently there are no "Binary" Voxels. The closest thing to a Voxel that can only be occupied or free is the BitVector Voxel. These Voxels carry a payload of 256 Bits, which have 5 preset "meanings" like "free" / "occupied" / "unknonw" /... See here: http://www.gpu-voxels.org/doxygen/html/namespacegpu__voxels.html#ac66bc7e0215fdac802af307c6c1860b1 Another Voxel would be the Probabilistic Voxel that carries a probability for its occupancy.

The whole idea behind GPU-Voxels is, that you keep the data on the GPU most of the time and do all the relevant calculations there. And only copy back a leight-weight result, like a single Boolean "collision"/"no collision".

So your conversion into a char-array will not work. Of course you could copy the whole map back onto your Host-RAM, and read out the Bits, but there is not point in doing that.

Here is a bit of code that shows you, how to read the BitVector which you get as a collisions result:

/*!
 * \brief GraspEvaluator::evaluateGrasp Checks sweep. eBVM_SV_0 != stretched out, nut eBVM_SV_0 == First angle increment!
 * Streached out pose is saved in eBVM_OCCUPIED
 * \param offset
 * \param result Vector of values that indicate first collision per finger. 0 means first angle increment, not stretched out pose!
 * \return Number of detected collisions
 */
size_t GraspEvaluator::evaluateGrasp(const Vector3i &offset, std::vector<int32_t> &first_collision_index)
{
  static size_t num_evaluated_grasps(0); // For statistics
  ++num_evaluated_grasps;

  BitVectorVoxel bits_in_collision;

  size_t num_colls;

  num_colls = m_gvl->getMap("myGraspSweepVoxellist")->as<voxellist::BitVectorVoxelList>()->collideWithTypes(m_gvl->getMap("myObjectVoxelmap")->as<voxelmap::ProbVoxelMap>(), bits_in_collision, 1.0, offset);

  //std::cout << "Detected " << num_colls << " collisions " << std::endl;
  //std::cout << "with bits \n" << bits_in_collision << std::endl;

  first_collision_index.resize(5);
  first_collision_index.assign(5, -1); // This marks, that no collision was found.
  for(u_int32_t joint_number = 0;  joint_number < 5; joint_number++)
  {
    for(u_int32_t i = (joint_number*m_num_finger_motion_steps); i < (m_num_finger_motion_steps*(joint_number+1)); i++)
    {
      if(bits_in_collision.bitVector().getBit(eBVM_SWEPT_VOLUME_START + i))
      {
        first_collision_index[joint_number] = i- (m_num_finger_motion_steps*joint_number);
        //std::cout << "collision of joint " << joint_number << " at step "  << (i-m_num_finger_motion_steps*joint_number) << std::endl;
        break;
      }
    }
  }
  return num_colls;
}

Hope that helps. If not, please explain your use case briefly, so I can give you a hint, on how to achieve your goals.

Cheers, Andreas

jvarley commented 6 years ago

Hi Andreas,

Thanks for your quick reply. I am using your library to build up voxel grids that I want to save as binvox files to use for training a CNN. I was just trying to find the easiest way to get my grid of the gpu.

I got it working with:

image

bsaund commented 6 years ago

Just adding my experiences, I have run into several cases where syncing back to the host has been useful: 1) Debugging, 2) adding only specific links of my robot to the map, 3) pass the full voxelmap to a different process. Obviously this syncing is slow, but sometimes that is okay.

I implemented the robot::syncToHost(), as I don't believe there is a way to get the (private) device pointer to the robot link point clouds.

The above cudaMemcpy works, but requires compiling with nvcc, adding additional overhead to using the library.

Squelsh commented 6 years ago

Thanks Brad, I absolutely understand your first point. I don't have access to the current code version here, abut I think we have a syncToHost in the MetaPointCloud by now. Sorry if I am right and you put work into that. Next release is really close. Here are my thoughts on the other points:

@ 2) Why do you need to get the pointclouds back to the host for that? There are getters in the MetaPointCloud to access and transform sub-clouds of the robot. Still this requires some extra lines of code in the robot class.

@ 3) CUDA offers you a special construct to pass mapped pointers on device memory via several host processes. We use this already to share the device data between the main program and the visualizer program via Boost inter-process-communication, so that we do not need to download data just to upoad it again with the visualizer process.

Squelsh commented 6 years ago

Oh, BTW: @ 2) Always think about the discretization errors, if you work with models, that you download from a Voxel-datastructure instead of the original pointcloud.

bsaund commented 6 years ago

Thanks for the suggestions.

I still support the syncToHost methods, as when I don't care about fast execution I prefer to avoid editing gpu_voxels directly, and also I am much slower at writing GPU code.