Closed GPrathap closed 5 years ago
Hi Geesara,
please excuse my late reply. You just need to mutiply the bytes per voxel with the voxels per map. Also, it looks like you have an extra &
before your first pointer.
size_t num_voxels = NXY*NXY*NZ; // dimensions of the distance voxelmap
using DistanceVoxel::init_floodfill_distance::manhattan_dist_t;
cudaMemcpy(dev_manhattan_distances__device_ptr, dev_manhattan_distances_host_ptr, sizeof(manhattan_dist_t) * num_voxels, cudaMemcpyDeviceToHost);
Let me know if you have more questions.
DistanceVoxel::extract_byte_distance::free_space_t dev_free_space_ptr; DistanceVoxel::init_floodfill_distance::manhattan_dist_t dev_manhattan_distancesdevice_ptr; DistanceVoxel::init_floodfill_distance::manhattan_dist_t dev_manhattan_distances_host_ptr; pbaDistanceVoxmap->extract_distances(dev_free_space_ptr, 2.5); pbaDistanceVoxmap->init_floodfill(dev_free_space_ptr, dev_manhattan_distances__device_ptr, 2.5); size_t num_voxels = voxel_cube_sizevoxel_cube_size*voxel_cube_size; cudaMemcpy(dev_manhattan_distancesdevice_ptr, dev_manhattan_distances_host_ptr, sizeof(DistanceVoxel::init_floodfill_distance::manhattan_dist_t)*num_voxels, cudaMemcpyDeviceToHost);
I have this error now (:
<2019-04-09 02:56:08.739> CudaLog(Error)::cuHandleError: an illegal memory access was encountered in /root/project/gpu-voxels/packages/gpu_voxels/src/gpu_voxels/voxelmap/DistanceVoxelMap.hpp on line 686. <2019-04-09 02:56:08.739> VoxelmapLog(Info)::init_floodfill: init_floodfill for 134217728 voxels terminate called after throwing an instance of 'thrust::system::system_error' what(): parallel_for failed: an illegal memory access was encountered
@GPrathap sorry for missing this earlier.
Were you able to fix the problem?
It looks like you omit from your example the neccessary cudaMalloc calls to allocate memory for device arrays for the dev_free_space_ptr
and dev_manhattan_distances__device_ptr
pointers.
Yeap, I've gone with another approach which worked smoothly. Anyway thanks for the reply
This problem is related to this: https://github.com/fzi-forschungszentrum-informatik/gpu-voxels/issues/97
Can you give me a way to copy from GPU to CPU,
thrust::device_ptr dvm_thrust_ptr(pbaDistanceVoxmap->getDeviceDataPtr());
DistanceVoxel::extract_byte_distance::free_space_t dev_free_space_ptr; DistanceVoxel::init_floodfill_distance::manhattan_dist_t dev_manhattan_distances__device_ptr; DistanceVoxel::init_floodfill_distance::manhattan_dist_t* dev_manhattan_distances_host_ptr; pbaDistanceVoxmap->extract_distances(dev_free_space_ptr, 2.5); pbaDistanceVoxmap->init_floodfill(dev_free_space_ptr, dev_manhattan_distances__device_ptr, 2.5);
// TODO cudaMemcpy dev_floodfill_distances_ptr to host_floodfill_distances This part is not clear? I could try this way?
cudaMemcpy(&dev_manhattan_distances__device_ptr, dev_manhattan_distances_host_ptr, sizeof(DistanceVoxel::init_floodfill_distance::manhattan_dist_t), cudaMemcpyDeviceToHost);
How do you know the size of the vector to be copied?