40 #ifndef PCL_CRF_SEGMENTATION_HPP_
41 #define PCL_CRF_SEGMENTATION_HPP_
43 #include <pcl/filters/voxel_grid_label.h>
44 #include <pcl/segmentation/crf_segmentation.h>
46 #include <pcl/common/io.h>
52 template <
typename Po
intT>
60 voxel_grid_leaf_size_ (
Eigen::Vector4f (0.001f, 0.001f, 0.001f, 0.0f))
65 template <
typename Po
intT>
69 template <
typename Po
intT>
void
72 input_cloud_ = input_cloud;
76 template <
typename Po
intT>
void
79 anno_cloud_ = anno_cloud;
83 template <
typename Po
intT>
void
86 normal_cloud_ = normal_cloud;
90 template <
typename Po
intT>
void
93 voxel_grid_leaf_size_.x () = x;
94 voxel_grid_leaf_size_.y () = y;
95 voxel_grid_leaf_size_.z () = z;
99 template <
typename Po
intT>
void
103 smoothness_kernel_param_[0] = sx;
104 smoothness_kernel_param_[1] = sy;
105 smoothness_kernel_param_[2] = sz;
106 smoothness_kernel_param_[3] = w;
110 template <
typename Po
intT>
void
112 float sr,
float sg,
float sb,
115 appearance_kernel_param_[0] = sx;
116 appearance_kernel_param_[1] = sy;
117 appearance_kernel_param_[2] = sz;
118 appearance_kernel_param_[3] = sr;
119 appearance_kernel_param_[4] = sg;
120 appearance_kernel_param_[5] = sb;
121 appearance_kernel_param_[6] = w;
125 template <
typename Po
intT>
void
127 float snx,
float sny,
float snz,
130 surface_kernel_param_[0] = sx;
131 surface_kernel_param_[1] = sy;
132 surface_kernel_param_[2] = sz;
133 surface_kernel_param_[3] = snx;
134 surface_kernel_param_[4] = sny;
135 surface_kernel_param_[5] = snz;
136 surface_kernel_param_[6] = w;
141 template <
typename Po
intT>
void
146 voxel_grid_.setInputCloud (input_cloud_);
148 voxel_grid_.setLeafSize (voxel_grid_leaf_size_.x (), voxel_grid_leaf_size_.y (), voxel_grid_leaf_size_.z () );
150 voxel_grid_.setDownsampleAllData (
true);
154 voxel_grid_.filter (*filtered_cloud_);
157 if (!anno_cloud_->points.empty ())
163 vg.
setLeafSize (voxel_grid_leaf_size_.x (), voxel_grid_leaf_size_.y (), voxel_grid_leaf_size_.z () );
169 vg.
filter (*filtered_anno_);
173 if (!normal_cloud_->points.empty ())
178 vg.
setLeafSize (voxel_grid_leaf_size_.x (), voxel_grid_leaf_size_.y (), voxel_grid_leaf_size_.z () );
184 vg.
filter (*filtered_normal_);
190 template <
typename Po
intT>
void
245 data_.resize (filtered_cloud_->size ());
247 std::vector< pcl::PCLPointField > fields;
249 bool color_data =
false;
251 rgba_index = pcl::getFieldIndex<PointT> (
"rgb", fields);
252 if (rgba_index == -1)
253 rgba_index = pcl::getFieldIndex<PointT> (
"rgba", fields);
257 color_.resize (filtered_cloud_->size ());
274 for (std::size_t i = 0; i < filtered_cloud_->size (); i++)
276 Eigen::Vector3f p ((*filtered_anno_)[i].x,
277 (*filtered_anno_)[i].y,
278 (*filtered_anno_)[i].z);
279 Eigen::Vector3i c = voxel_grid_.getGridCoordinates (p.x (), p.y (), p.y ());
284 std::uint32_t rgb = *
reinterpret_cast<int*
>(&(*filtered_cloud_)[i].rgba);
285 std::uint8_t r = (rgb >> 16) & 0x0000ff;
286 std::uint8_t g = (rgb >> 8) & 0x0000ff;
287 std::uint8_t b = (rgb) & 0x0000ff;
288 color_[i] = Eigen::Vector3i (r, g, b);
302 normal_.resize (filtered_normal_->size ());
303 for (std::size_t i = 0; i < filtered_normal_->size (); i++)
305 float n_x = (*filtered_normal_)[i].normal_x;
306 float n_y = (*filtered_normal_)[i].normal_y;
307 float n_z = (*filtered_normal_)[i].normal_z;
308 normal_[i] = Eigen::Vector3f (n_x, n_y, n_z);
315 template <
typename Po
intT>
void
317 std::vector<int> &labels,
318 unsigned int n_labels)
321 srand (
static_cast<unsigned int> (time (
nullptr)) );
325 const float GT_PROB = 0.9f;
326 const float u_energy = -std::log ( 1.0f /
static_cast<float> (n_labels) );
327 const float n_energy = -std::log ( (1.0f - GT_PROB) /
static_cast<float>(n_labels - 1) );
328 const float p_energy = -std::log ( GT_PROB );
330 for (std::size_t k = 0; k < filtered_anno_->size (); k++)
332 int label = (*filtered_anno_)[k].label;
334 if (labels.empty () && label > 0)
335 labels.push_back (label);
338 for (
int c_idx = 0; c_idx < static_cast<int> (labels.size ()) ; c_idx++)
340 if (labels[c_idx] == label)
343 if (c_idx ==
static_cast<int>(labels.size () -1) && label > 0)
345 if (labels.size () < n_labels)
346 labels.push_back (label);
353 std::size_t u_idx = k * n_labels;
356 for (std::size_t i = 0; i < n_labels; i++)
357 unary[u_idx + i] = n_energy;
358 unary[u_idx + labels.size ()] = p_energy;
362 const float PROB = 0.2f;
363 const float n_energy2 = -std::log ( (1.0f - PROB) /
static_cast<float>(n_labels - 1) );
364 const float p_energy2 = -std::log ( PROB );
366 for (std::size_t i = 0; i < n_labels; i++)
367 unary[u_idx + i] = n_energy2;
368 unary[u_idx + labels.size ()] = p_energy2;
374 for (std::size_t i = 0; i < n_labels; i++)
375 unary[u_idx + i] = u_energy;
381 template <
typename Po
intT>
void
386 std::cout <<
"create Voxel Grid - DONE" << std::endl;
389 createDataVectorFromVoxelGrid ();
390 std::cout <<
"create Data Vector from Voxel Grid - DONE" << std::endl;
393 const int n_labels = 10;
395 int N =
static_cast<int> (data_.size ());
398 std::vector<int> labels;
399 std::vector<float> unary;
400 if (!anno_cloud_->points.empty ())
402 unary.resize (N * n_labels);
403 createUnaryPotentials (unary, labels, n_labels);
406 std::cout <<
"labels size: " << labels.size () << std::endl;
407 for (
const int &label : labels)
409 std::cout << label << std::endl;
413 std::cout <<
"create unary potentials - DONE" << std::endl;
493 std::cout <<
"create dense CRF - DONE" << std::endl;
498 smoothness_kernel_param_[1],
499 smoothness_kernel_param_[2],
500 smoothness_kernel_param_[3]);
501 std::cout <<
"add smoothness kernel - DONE" << std::endl;
505 appearance_kernel_param_[1],
506 appearance_kernel_param_[2],
507 appearance_kernel_param_[3],
508 appearance_kernel_param_[4],
509 appearance_kernel_param_[5],
510 appearance_kernel_param_[6]);
511 std::cout <<
"add appearance kernel - DONE" << std::endl;
514 surface_kernel_param_[0],
515 surface_kernel_param_[1],
516 surface_kernel_param_[2],
517 surface_kernel_param_[3],
518 surface_kernel_param_[4],
519 surface_kernel_param_[5],
520 surface_kernel_param_[6]);
521 std::cout <<
"add surface kernel - DONE" << std::endl;
524 std::vector<int> r (N);
535 std::cout <<
"Map inference - DONE" << std::endl;
538 output = *filtered_anno_;
540 for (
int i = 0; i < N; i++)
542 output[i].label = labels[r[i]];
598 #define PCL_INSTANTIATE_CrfSegmentation(T) template class PCL_EXPORTS pcl::CrfSegmentation<T>;
void createUnaryPotentials(std::vector< float > &unary, std::vector< int > &colors, unsigned int n_labels)
void createVoxelGrid()
Create a voxel grid to discretize the scene.
void setAppearanceKernelParameters(float sx, float sy, float sz, float sr, float sg, float sb, float w)
Set the appearanche kernel parameters.
void createDataVectorFromVoxelGrid()
Get the data from the voxel grid and convert it into a vector.
void segmentPoints(pcl::PointCloud< pcl::PointXYZRGBL > &output)
This method simply launches the segmentation algorithm.
void setVoxelGridLeafSize(const float x, const float y, const float z)
Set the leaf size for the voxel grid.
~CrfSegmentation()
This destructor destroys the cloud...
void setAnnotatedCloud(typename pcl::PointCloud< pcl::PointXYZRGBL >::Ptr anno_cloud)
void setSmoothnessKernelParameters(const float sx, const float sy, const float sz, const float w)
Set the smoothness kernel parameters.
void setNormalCloud(typename pcl::PointCloud< pcl::PointNormal >::Ptr normal_cloud)
CrfSegmentation()
Constructor that sets default values for member variables.
void setSurfaceKernelParameters(float sx, float sy, float sz, float snx, float sny, float snz, float w)
void setInputCloud(typename pcl::PointCloud< PointT >::Ptr input_cloud)
This method sets the input cloud.
void setColorVector(const std::vector< Eigen::Vector3i, Eigen::aligned_allocator< Eigen::Vector3i >> color)
The associated color of the data.
void setDataVector(const std::vector< Eigen::Vector3i, Eigen::aligned_allocator< Eigen::Vector3i >> data)
Set the input data vector.
void addPairwiseGaussian(float sx, float sy, float sz, float w)
Add a pairwise gaussian kernel.
void setUnaryEnergy(const std::vector< float > unary)
void addPairwiseBilateral(float sx, float sy, float sz, float sr, float sg, float sb, float w)
Add a bilateral gaussian kernel.
void mapInference(int n_iterations, std::vector< int > &result, float relax=1.0f)
void addPairwiseNormals(std::vector< Eigen::Vector3i, Eigen::aligned_allocator< Eigen::Vector3i >> &coord, std::vector< Eigen::Vector3f, Eigen::aligned_allocator< Eigen::Vector3f >> &normals, float sx, float sy, float sz, float snx, float sny, float snz, float w)
void filter(PointCloud &output)
Calls the filtering method and returns the filtered dataset in output.
virtual void setInputCloud(const PointCloudConstPtr &cloud)
Provide a pointer to the input dataset.
PointCloud represents the base class in PCL for storing collections of 3D points.
shared_ptr< PointCloud< PointT > > Ptr
VoxelGrid assembles a local 3D grid over a given PointCloud, and downsamples + filters the data.
void setDownsampleAllData(bool downsample)
Set to true if all fields need to be downsampled, or false if just XYZ.
void setLeafSize(const Eigen::Vector4f &leaf_size)
Set the voxel grid leaf size.
A point structure representing Euclidean xyz coordinates, together with normal coordinates and the su...
A point structure representing Euclidean xyz coordinates, and the RGB color.