fast_vgicp_cuda.cuh 3.4 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576777879808182838485868788899091929394959697
  1. #ifndef FAST_GICP_FAST_VGICP_CUDA_CORE_CUH
  2. #define FAST_GICP_FAST_VGICP_CUDA_CORE_CUH
  3. #include <memory>
  4. #include <vector>
  5. #include <Eigen/Core>
  6. #include <Eigen/Geometry>
  7. #include <fast_gicp/gicp/gicp_settings.hpp>
  8. namespace thrust {
  9. template <typename T1, typename T2>
  10. class pair;
  11. template <typename T>
  12. class device_allocator;
  13. template <typename T, typename Alloc>
  14. class device_vector;
  15. } // namespace thrust
  16. namespace fast_gicp {
  17. namespace cuda {
  18. class GaussianVoxelMap;
  19. class FastVGICPCudaCore {
  20. public:
  21. using Points = thrust::device_vector<Eigen::Vector3f, thrust::device_allocator<Eigen::Vector3f>>;
  22. using Indices = thrust::device_vector<int, thrust::device_allocator<int>>;
  23. using Matrices = thrust::device_vector<Eigen::Matrix3f, thrust::device_allocator<Eigen::Matrix3f>>;
  24. using Correspondences = thrust::device_vector<thrust::pair<int, int>, thrust::device_allocator<thrust::pair<int, int>>>;
  25. using VoxelCoordinates = thrust::device_vector<Eigen::Vector3i, thrust::device_allocator<Eigen::Vector3i>>;
  26. EIGEN_MAKE_ALIGNED_OPERATOR_NEW
  27. FastVGICPCudaCore();
  28. ~FastVGICPCudaCore();
  29. void set_resolution(double resolution);
  30. void set_kernel_params(double kernel_width, double kernel_max_dist);
  31. void set_neighbor_search_method(fast_gicp::NeighborSearchMethod method, double radius);
  32. void swap_source_and_target();
  33. void set_source_cloud(const std::vector<Eigen::Vector3f, Eigen::aligned_allocator<Eigen::Vector3f>>& cloud);
  34. void set_target_cloud(const std::vector<Eigen::Vector3f, Eigen::aligned_allocator<Eigen::Vector3f>>& cloud);
  35. void set_source_neighbors(int k, const std::vector<int>& neighbors);
  36. void set_target_neighbors(int k, const std::vector<int>& neighbors);
  37. void find_source_neighbors(int k);
  38. void find_target_neighbors(int k);
  39. void calculate_source_covariances(RegularizationMethod method);
  40. void calculate_target_covariances(RegularizationMethod method);
  41. void calculate_source_covariances_rbf(RegularizationMethod method);
  42. void calculate_target_covariances_rbf(RegularizationMethod method);
  43. void get_source_covariances(std::vector<Eigen::Matrix3f, Eigen::aligned_allocator<Eigen::Matrix3f>>& covs) const;
  44. void get_target_covariances(std::vector<Eigen::Matrix3f, Eigen::aligned_allocator<Eigen::Matrix3f>>& covs) const;
  45. void get_voxel_num_points(std::vector<int>& num_points) const;
  46. void get_voxel_means(std::vector<Eigen::Vector3f, Eigen::aligned_allocator<Eigen::Vector3f>>& means) const;
  47. void get_voxel_covs(std::vector<Eigen::Matrix3f, Eigen::aligned_allocator<Eigen::Matrix3f>>& covs) const;
  48. void get_voxel_correspondences(std::vector<std::pair<int, int>>& correspondences) const;
  49. void create_target_voxelmap();
  50. void update_correspondences(const Eigen::Isometry3d& trans);
  51. double compute_error(const Eigen::Isometry3d& trans, Eigen::Matrix<double, 6, 6>* H, Eigen::Matrix<double, 6, 1>* b) const;
  52. public:
  53. double resolution;
  54. double kernel_width;
  55. double kernel_max_dist;
  56. std::unique_ptr<VoxelCoordinates> offsets;
  57. std::unique_ptr<Points> source_points;
  58. std::unique_ptr<Points> target_points;
  59. std::unique_ptr<Indices> source_neighbors;
  60. std::unique_ptr<Indices> target_neighbors;
  61. std::unique_ptr<Matrices> source_covariances;
  62. std::unique_ptr<Matrices> target_covariances;
  63. std::unique_ptr<GaussianVoxelMap> voxelmap;
  64. Eigen::Isometry3f linearized_x;
  65. std::unique_ptr<Correspondences> voxel_correspondences;
  66. };
  67. } // namespace cuda
  68. } // namespace fast_gicp
  69. #endif