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>
69template <
typename Po
intT>
void
76template <
typename Po
intT>
void
83template <
typename Po
intT>
void
90template <
typename Po
intT>
void
99template <
typename Po
intT>
void
110template <
typename Po
intT>
void
112 float sr,
float sg,
float sb,
125template <
typename Po
intT>
void
127 float snx,
float sny,
float snz,
141template <
typename Po
intT>
void
190template <
typename Po
intT>
void
247 std::vector< pcl::PCLPointField >
fields;
249 bool color_data =
false;
252 if (rgba_index == -1)
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);
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);
315template <
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 );
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;
381template <
typename Po
intT>
void
386 std::cout <<
"create Voxel Grid - DONE" << std::endl;
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;
402 unary.resize (N * 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;
501 std::cout <<
"add smoothness kernel - DONE" << std::endl;
511 std::cout <<
"add appearance kernel - DONE" << std::endl;
521 std::cout <<
"add surface kernel - DONE" << std::endl;
524 std::vector<int> r (N);
535 std::cout <<
"Map inference - DONE" << std::endl;
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.
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...