30 #ifndef MCL_3DL_POINT_CLOUD_RANDOM_SAMPLERS_POINT_CLOUD_SAMPLER_WITH_NORMAL_H
31 #define MCL_3DL_POINT_CLOUD_RANDOM_SAMPLERS_POINT_CLOUD_SAMPLER_WITH_NORMAL_H
35 #include <unordered_set>
39 #include <Eigen/Eigenvalues>
41 #include <pcl/features/normal_3d.h>
42 #include <pcl/kdtree/kdtree_flann.h>
43 #include <pcl/point_cloud.h>
44 #include <pcl/point_types.h>
52 template <
class POINT_TYPE>
56 using Matrix = Eigen::Matrix<double, Eigen::Dynamic, Eigen::Dynamic>;
57 using Vector = Eigen::Matrix<double, Eigen::Dynamic, 1>;
59 std::shared_ptr<std::default_random_engine>
engine_;
70 :
engine_(
std::make_shared<
std::default_random_engine>(random_seed))
87 void setParameters(
const double perform_weighting_ratio,
const double max_weight_ratio,
88 const double max_weight,
const double normal_search_range)
100 for (
size_t i = 0; i < 3; ++i)
102 for (
size_t j = 0; j < 3; ++j)
104 pos_cov(i, j) = std::abs(covariances[i][j]);
107 const Eigen::SelfAdjointEigenSolver<Matrix> eigen_solver(pos_cov);
112 typename pcl::PointCloud<POINT_TYPE>::Ptr
sample(
113 const typename pcl::PointCloud<POINT_TYPE>::ConstPtr& pc,
114 const size_t num)
const final
118 typename pcl::PointCloud<POINT_TYPE>::Ptr output(
new pcl::PointCloud<POINT_TYPE>);
119 output->header = pc->header;
121 if ((pc->points.size() == 0) || (num == 0))
125 if (pc->size() <= num)
133 double max_weight = 1.0;
144 const double weight_ratio =
146 max_weight = 1.0 + (
max_weight_ - 1.0) * weight_ratio;
150 pcl::NormalEstimation<POINT_TYPE, pcl::Normal> ne;
151 pcl::PointCloud<pcl::Normal>::Ptr cloud_normals(
new pcl::PointCloud<pcl::Normal>);
152 typename pcl::search::KdTree<POINT_TYPE>::Ptr tree(
new pcl::search::KdTree<POINT_TYPE>());
153 ne.setInputCloud(pc);
154 ne.setSearchMethod(tree);
156 ne.compute(*cloud_normals);
159 std::vector<double> cumulative_weight(cloud_normals->points.size(), 0.0);
160 for (
size_t i = 0; i < cloud_normals->points.size(); i++)
163 const auto& normal = cloud_normals->points[i];
164 if (!std::isnan(normal.normal_x) && !std::isnan(normal.normal_y) && !std::isnan(normal.normal_z))
166 double acos_angle = std::abs(normal.normal_x * fpc_local.
x_ +
167 normal.normal_y * fpc_local.
y_ +
168 normal.normal_z * fpc_local.
z_);
170 if (acos_angle > 1.0)
174 const double angle = std::acos(acos_angle);
175 weight = 1.0 + (max_weight - 1.0) * ((M_PI / 2 -
angle) / (M_PI / 2));
177 cumulative_weight[i] = weight + ((i == 0) ? 0.0 : cumulative_weight[i - 1]);
179 std::uniform_real_distribution<double> ud(0, cumulative_weight.back());
181 std::unordered_set<size_t> selected_ids;
184 const double random_value = ud(*
engine_);
185 auto it = std::lower_bound(cumulative_weight.begin(), cumulative_weight.end(), random_value);
186 const size_t n = it - cumulative_weight.begin();
187 selected_ids.insert(n);
188 if (selected_ids.size() >= num)
193 output->points.reserve(num);
194 for (
const auto& index : selected_ids)
196 output->push_back(pc->points[index]);
200 ROS_DEBUG(
"PointCloudSamplerWithNormal::sample() computation time: %f[s] (Normal calculation: %f[s])",
201 (final_timestamp - start_timestamp).toSec(), (compute_normal_timestamp - start_timestamp).toSec());
202 ROS_DEBUG(
"Chosen eigen vector: (%f, %f, %f), max weight: %f",
210 #endif // MCL_3DL_POINT_CLOUD_RANDOM_SAMPLERS_POINT_CLOUD_SAMPLER_WITH_NORMAL_H