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>
52template <
typename Po
intT>
65template <
typename Po
intT>
71template <
typename Po
intT>
void
78template <
typename Po
intT>
void
85template <
typename Po
intT>
void
92template <
typename Po
intT>
void
101template <
typename Po
intT>
void
112template <
typename Po
intT>
void
114 float sr,
float sg,
float sb,
127template <
typename Po
intT>
void
129 float snx,
float sny,
float snz,
143template <
typename Po
intT>
void
192template <
typename Po
intT>
void
249 std::vector< pcl::PCLPointField >
fields;
251 bool color_data =
false;
254 if (rgba_index == -1)
281 Eigen::Vector3i c =
voxel_grid_.getGridCoordinates (p.x (), p.y (), p.y ());
286 std::uint32_t rgb = *
reinterpret_cast<int*
>(&(*filtered_cloud_)[i].rgba);
287 std::uint8_t r = (rgb >> 16) & 0x0000ff;
288 std::uint8_t g = (rgb >> 8) & 0x0000ff;
289 std::uint8_t b = (rgb) & 0x0000ff;
290 color_[i] = Eigen::Vector3i (r, g, b);
307 float n_x = (*filtered_normal_)[i].normal_x;
308 float n_y = (*filtered_normal_)[i].normal_y;
309 float n_z = (*filtered_normal_)[i].normal_z;
310 normal_[i] = Eigen::Vector3f (n_x, n_y, n_z);
317template <
typename Po
intT>
void
319 std::vector<int> &labels,
320 unsigned int n_labels)
323 srand (
static_cast<unsigned int> (time (
nullptr)) );
327 const float GT_PROB = 0.9f;
328 const float u_energy = -std::log ( 1.0f /
static_cast<float> (n_labels) );
329 const float n_energy = -std::log ( (1.0f - GT_PROB) /
static_cast<float>(n_labels - 1) );
330 const float p_energy = -std::log ( GT_PROB );
334 int label = (*filtered_anno_)[k].label;
336 if (labels.empty () && label > 0)
337 labels.push_back (label);
340 for (
int c_idx = 0; c_idx < static_cast<int> (labels.size ()) ; c_idx++)
342 if (labels[c_idx] == label)
345 if (c_idx ==
static_cast<int>(labels.size () -1) && label > 0)
347 if (labels.size () < n_labels)
348 labels.push_back (label);
355 std::size_t u_idx = k * n_labels;
358 for (std::size_t i = 0; i < n_labels; i++)
359 unary[u_idx + i] = n_energy;
360 unary[u_idx + labels.size ()] = p_energy;
364 const float PROB = 0.2f;
365 const float n_energy2 = -std::log ( (1.0f - PROB) /
static_cast<float>(n_labels - 1) );
366 const float p_energy2 = -std::log ( PROB );
368 for (std::size_t i = 0; i < n_labels; i++)
369 unary[u_idx + i] = n_energy2;
370 unary[u_idx + labels.size ()] = p_energy2;
376 for (std::size_t i = 0; i < n_labels; i++)
377 unary[u_idx + i] = u_energy;
383template <
typename Po
intT>
void
388 std::cout <<
"create Voxel Grid - DONE" << std::endl;
392 std::cout <<
"create Data Vector from Voxel Grid - DONE" << std::endl;
395 const int n_labels = 10;
397 int N =
static_cast<int> (
data_.size ());
400 std::vector<int> labels;
401 std::vector<float> unary;
404 unary.resize (N * n_labels);
408 std::cout <<
"labels size: " << labels.size () << std::endl;
409 for (
const int &label : labels)
411 std::cout << label << std::endl;
415 std::cout <<
"create unary potentials - DONE" << std::endl;
495 std::cout <<
"create dense CRF - DONE" << std::endl;
503 std::cout <<
"add smoothness kernel - DONE" << std::endl;
513 std::cout <<
"add appearance kernel - DONE" << std::endl;
523 std::cout <<
"add surface kernel - DONE" << std::endl;
526 std::vector<int> r (N);
537 std::cout <<
"Map inference - DONE" << std::endl;
542 for (
int i = 0; i < N; i++)
544 output[i].label = labels[r[i]];
600#define PCL_INSTANTIATE_CrfSegmentation(T) template class 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.
Eigen::Vector4f voxel_grid_leaf_size_
indices of the filtered cloud.
pcl::PointCloud< pcl::PointNormal >::Ptr filtered_normal_
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...
std::vector< Eigen::Vector3i, Eigen::aligned_allocator< Eigen::Vector3i > > data_
voxel grid data points packing order [x0y0z0, x1y0z0,x2y0z0,...,x0y1z0,x1y1z0,...,...
unsigned int n_iterations_
void setAnnotatedCloud(typename pcl::PointCloud< pcl::PointXYZRGBL >::Ptr anno_cloud)
pcl::VoxelGrid< PointT > voxel_grid_
Voxel grid to discretize the scene.
std::vector< Eigen::Vector3i, Eigen::aligned_allocator< Eigen::Vector3i > > color_
float surface_kernel_param_[7]
pcl::PointCloud< PointT >::Ptr filtered_cloud_
voxel grid filtered cloud.
void setSmoothnessKernelParameters(const float sx, const float sy, const float sz, const float w)
Set the smoothness kernel parameters.
pcl::PointCloud< PointT >::Ptr input_cloud_
input cloud that will be segmented.
std::vector< Eigen::Vector3f, Eigen::aligned_allocator< Eigen::Vector3f > > normal_
float appearance_kernel_param_[7]
appearance kernel parameters [0] = standard deviation x [1] = standard deviation y [2] = standard dev...
void setNormalCloud(typename pcl::PointCloud< pcl::PointNormal >::Ptr normal_cloud)
CrfSegmentation()
Constructor that sets default values for member variables.
float smoothness_kernel_param_[4]
smoothness kernel parameters [0] = standard deviation x [1] = standard deviation y [2] = standard dev...
pcl::PointCloud< pcl::PointNormal >::Ptr normal_cloud_
void setSurfaceKernelParameters(float sx, float sy, float sz, float snx, float sny, float snz, float w)
pcl::PointCloud< pcl::PointXYZRGBL >::Ptr filtered_anno_
void setInputCloud(typename pcl::PointCloud< PointT >::Ptr input_cloud)
This method sets the input cloud.
pcl::PointCloud< pcl::PointXYZRGBL >::Ptr anno_cloud_
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 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 mapInference(int n_iterations, std::vector< int > &result, float relax=1.0f)
void setColorVector(const std::vector< Eigen::Vector3i, Eigen::aligned_allocator< Eigen::Vector3i > > color)
The associated color of the data.
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.
int getFieldIndex(const pcl::PointCloud< PointT > &, const std::string &field_name, std::vector< pcl::PCLPointField > &fields)
A point structure representing Euclidean xyz coordinates, together with normal coordinates and the su...