24 #include <pcl/features/integral_image_normal.h> 25 #include <pcl/features/normal_3d.h> 26 #include <pcl/ModelCoefficients.h> 27 #include <pcl/segmentation/organized_multi_plane_segmentation.h> 28 #include <pcl/segmentation/organized_connected_component_segmentation.h> 29 #include <pcl/filters/extract_indices.h> 30 #include <pcl/filters/voxel_grid.h> 31 #include <pcl/common/transforms.h> 32 #include <pcl/common/time.h> 42 using namespace Eigen;
50 assert(hist1.size() == hist2.size());
52 double BhattachDist_aux = 0.0;
53 for (
unsigned i = 0; i < hist1.size(); i++)
54 BhattachDist_aux += sqrt(hist1[i] * hist2[i]);
56 BhattachDist = sqrt(1 - BhattachDist_aux);
121 "plane_segmentation",
"dist_threshold", 0.04,
true);
123 "plane_segmentation",
"angle_threshold", 0.069812,
true);
125 "plane_segmentation",
"minInliersRate", 0.01,
true);
129 config_file.
read_bool(
"map_construction",
"use_color",
false);
131 config_file.
read_float(
"map_construction",
"color_threshold", 0.09);
133 "map_construction",
"intensity_threshold", 255.0);
135 config_file.
read_float(
"unary",
"hue_threshold", 0.25);
137 "map_construction",
"proximity_neighbor_planes", 1.0);
139 config_file.
read_int(
"map_construction",
"graph_mode", 1);
141 "map_construction",
"max_cos_normal", 0.9848,
true);
143 "map_construction",
"max_dist_center_plane", 0.1,
true);
145 config_file.
read_float(
"map_construction",
"proximity_threshold", 0.15);
149 config_file.
read_bool(
"semantics",
"inferStructure",
true);
151 config_file.
read_bool(
"semantics",
"makeCovisibilityClusters",
false);
157 config_file.
read_bool(
"localisation",
"detect_loopClosure",
true);
160 "localisation",
"config_localiser",
"",
true);
164 config_file.
read_string(
"serialize",
"path_save_pbmap",
"map");
166 config_file.
read_bool(
"serialize",
"save_registered_cloud",
true);
168 "serialize",
"path_save_registered_cloud",
169 "/home/edu/Projects/PbMaps/PbMaps.txt");
174 cout <<
"readConfigFile configPbMap.ini dist_threshold " 179 PbMapMaker::PbMapMaker(
const string& config_file)
180 : cloudViewer(
"Cloud Viewer"),
181 mpPbMapLocaliser(nullptr),
182 m_pbmaker_must_stop(false),
183 m_pbmaker_finished(false)
201 Plane& plane1,
Plane& plane2,
const float distThreshold)
203 float distThres2 = distThreshold * distThreshold;
213 .squaredNorm() < distThres2)
219 .squaredNorm() < distThres2)
227 .squaredNorm() < distThres2)
292 pcl::PointCloud<PointT>::Ptr& pointCloudPtr_arg, Eigen::Matrix4f& poseKF,
293 double distThreshold,
double angleThreshold,
double minInliersF)
297 unsigned minInliers = minInliersF * pointCloudPtr_arg->size();
300 cout <<
"detectPlanes in a cloud with " << pointCloudPtr_arg->size()
301 <<
" points " << minInliers <<
" minInliers\n";
304 pcl::PointCloud<PointT>::Ptr pointCloudPtr_arg2(
305 new pcl::PointCloud<PointT>);
306 pcl::copyPointCloud(*pointCloudPtr_arg, *pointCloudPtr_arg2);
308 pcl::PointCloud<pcl::PointXYZRGBA>::Ptr alignedCloudPtr(
309 new pcl::PointCloud<pcl::PointXYZRGBA>);
310 pcl::transformPointCloud(*pointCloudPtr_arg, *alignedCloudPtr, poseKF);
316 static pcl::VoxelGrid<pcl::PointXYZRGBA> grid;
317 grid.setLeafSize(0.02, 0.02, 0.02);
318 pcl::PointCloud<pcl::PointXYZRGBA> globalMap;
320 grid.filter(globalMap);
325 pcl::IntegralImageNormalEstimation<PointT, pcl::Normal> ne;
326 ne.setNormalEstimationMethod(ne.COVARIANCE_MATRIX);
327 ne.setMaxDepthChangeFactor(0.02f);
328 ne.setNormalSmoothingSize(10.0f);
329 ne.setDepthDependentSmoothing(
true);
331 pcl::OrganizedMultiPlaneSegmentation<PointT, pcl::Normal, pcl::Label> mps;
332 mps.setMinInliers(minInliers);
333 cout <<
"Params " << minInliers <<
" " << angleThreshold <<
" " 334 << distThreshold << endl;
335 mps.setAngularThreshold(angleThreshold);
336 mps.setDistanceThreshold(distThreshold);
338 pcl::PointCloud<pcl::Normal>::Ptr normal_cloud(
339 new pcl::PointCloud<pcl::Normal>);
340 ne.setInputCloud(pointCloudPtr_arg2);
341 ne.compute(*normal_cloud);
344 double plane_extract_start = pcl::getTime();
346 mps.setInputNormals(normal_cloud);
347 mps.setInputCloud(pointCloudPtr_arg2);
349 std::vector<pcl::PlanarRegion<PointT>,
350 aligned_allocator<pcl::PlanarRegion<PointT>>>
352 std::vector<pcl::ModelCoefficients> model_coefficients;
353 std::vector<pcl::PointIndices> inlier_indices;
354 pcl::PointCloud<pcl::Label>::Ptr labels(
new pcl::PointCloud<pcl::Label>);
355 std::vector<pcl::PointIndices> label_indices;
356 std::vector<pcl::PointIndices> boundary_indices;
357 mps.segmentAndRefine(
358 regions, model_coefficients, inlier_indices, labels, label_indices,
362 double plane_extract_end = pcl::getTime();
363 std::cout <<
"Plane extraction took " 364 << double(plane_extract_end - plane_extract_start) << std::endl;
367 cout << regions.size() <<
" planes detected\n";
373 vector<Plane> detectedPlanes;
374 for (
size_t i = 0; i < regions.size(); i++)
378 Vector3f centroid = regions[i].getCentroid();
381 poseKF.block(0, 0, 3, 3) * Vector3f(
382 model_coefficients[i].
values[0],
383 model_coefficients[i].
values[1],
384 model_coefficients[i].
values[2]);
391 pcl::ExtractIndices<pcl::PointXYZRGBA> extract;
392 extract.setInputCloud(pointCloudPtr_arg2);
394 boost::make_shared<const pcl::PointIndices>(inlier_indices[i]));
395 extract.setNegative(
false);
399 static pcl::VoxelGrid<pcl::PointXYZRGBA> plane_grid;
400 plane_grid.setLeafSize(0.05, 0.05, 0.05);
401 pcl::PointCloud<pcl::PointXYZRGBA> planeCloud;
403 plane_grid.filter(planeCloud);
407 pcl::PointCloud<pcl::PointXYZRGBA>::Ptr contourPtr(
408 new pcl::PointCloud<pcl::PointXYZRGBA>);
409 contourPtr->points = regions[i].getContour();
410 plane_grid.setLeafSize(0.1, 0.1, 0.1);
411 plane_grid.setInputCloud(contourPtr);
421 cout <<
"Area plane region " << plane.
areaVoxels <<
" of Chull " 429 bool isSamePlane =
false;
430 for (
size_t j = 0; j < detectedPlanes.size(); j++)
442 cout <<
"\tTwo regions support the same plane in the same " 448 if (!isSamePlane) detectedPlanes.push_back(plane);
452 cout << detectedPlanes.size() <<
" Planes detected\n";
461 for (
size_t i = 0; i < detectedPlanes.size(); i++)
464 bool isSamePlane =
false;
467 for (
size_t j = 0; j < numPrevPlanes;
523 cout <<
"Same plane\n";
527 for (
size_t k = j + 1; k < numPrevPlanes; k++, itPlane++)
555 for (
size_t h = k + 1; h < numPrevPlanes; h++)
558 for (
size_t h = 0; h < numPrevPlanes; h++)
560 if (k == h)
continue;
576 .neighborPlanes.begin();
583 .neighborPlanes[it->first - 1] =
594 cout <<
"MERGE TWO PREVIOUS PLANES WHEREBY THE " 595 "INCORPORATION OF A NEW REGION \n";
605 detectedPlanes[i].numObservations = 1;
606 detectedPlanes[i].bFullExtent =
false;
607 detectedPlanes[i].nFramesAreaIsStable = 0;
611 detectedPlanes[i].semanticGroup =
614 .push_back(detectedPlanes[i].
id);
618 cout <<
"New plane " << detectedPlanes[i].id <<
" area " 619 << detectedPlanes[i].areaVoxels <<
" of polygon " 620 << detectedPlanes[i].areaHull << endl;
635 detectedPlanes[i].neighborPlanes[*it] = 1;
648 cout <<
"\n\tobservedPlanes: ";
670 cout <<
"Plane " << observedPlane.
id <<
" color\n" 685 cout <<
"Verify that the observed planes centers are above the floor\n";
688 for (set<unsigned>::reverse_iterator it =
observedPlanes.rbegin();
725 cout <<
"DetectedPlanesCloud finished\n";
733 const pcl::visualization::KeyboardEvent& event,
void* viewer_void)
735 if ((event.getKeySym() ==
"r" ||
event.getKeySym() ==
"R") &&
747 Plane& plane1,
Plane& plane2,
const float& cosAngleThreshold,
748 const float& distThreshold,
const float& proxThreshold)
759 float thres_max_dist =
762 if (fabs(dist_normal) >
787 static pcl::VoxelGrid<pcl::PointXYZRGBA> merge_grid;
788 merge_grid.setLeafSize(0.05, 0.05, 0.05);
789 pcl::PointCloud<pcl::PointXYZRGBA> mergeCloud;
791 merge_grid.filter(mergeCloud);
814 unsigned char red[10] = {255, 0, 0, 255, 255, 0, 255, 204, 0, 255};
815 unsigned char grn[10] = {0, 255, 0, 255, 0, 255, 160, 51, 128, 222};
816 unsigned char blu[10] = {0, 0, 255, 0, 255, 255, 0, 204, 0, 173};
818 double ared[10] = {1.0, 0, 0, 1.0, 1.0, 0, 1.0, 0.8, 0, 1.0};
819 double agrn[10] = {0, 1.0, 0, 1.0, 0, 1.0, 0.6, 0.2, 0.5, 0.9};
820 double ablu[10] = {0, 0, 1.0, 0, 1.0, 1.0, 0, 0.8, 0, 0.7};
826 std::this_thread::sleep_for(10ms);
835 viz.removeAllShapes();
836 viz.removeAllPointClouds();
928 if (!viz.updatePointCloud(
935 name,
"PointCloud size %u",
937 viz.addText(
name, 10, 20);
950 sprintf(
name,
"normal_%u", static_cast<unsigned>(i));
951 pcl::PointXYZ pt1, pt2;
1006 sprintf(
name,
"plane_%02u", static_cast<unsigned>(i));
1042 pcl::visualization::PointCloudColorHandlerCustom<PointT>
1063 viz.setPointCloudRenderingProperties(
1064 pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 10,
1138 it->first, it->second, 0.3, 0.9, 0.9, 0.9,
1151 size_t numPrevKFs = 0;
1152 size_t minGrowPlanes = 5;
1157 std::this_thread::sleep_for(10ms);
1172 int size_partition =
1174 cout <<
"PARTITION SIZE " << size_partition << endl;
1175 assert(size_partition < 2);
1196 updateLock.unlock();
1203 cout <<
"Waiting for PbMapMaker thread to die.." << endl;
1217 cout <<
" .. PbMapMaker has died." << endl;
Eigen::Vector3f diffPoints(const POINT &P1, const POINT &P2)
PlaneInferredInfo * mpPlaneInferInfo
std::string read_string(const std::string §ion, const std::string &name, const std::string &defaultValue, bool failIfNotFound=false) const
std::map< std::string, pcl::PointXYZ > foundPlaces
pcl::PointCloud< pcl::PointXYZRGBA >::Ptr polygonContourPtr
std::set< unsigned > observedPlanes
GLboolean GLenum GLenum GLvoid * values
A class used to store a planar feature (Plane for short).
PbMapLocaliser * mpPbMapLocaliser
bool areSamePlane(Plane &plane1, Plane &plane2, const float &cosAngleThreshold, const float &distThreshold, const float &proxThreshold)
void checkProximity(Plane &plane, float proximity)
void serializePbMap(std::string path)
This class allows loading and storing values and vectors of different types from ".ini" files easily.
void keyboardEventOccurred(const pcl::visualization::KeyboardEvent &event, void *viewer_void)
boost::mutex mtx_pbmap_busy
float read_float(const std::string §ion, const std::string &name, float defaultValue, bool failIfNotFound=false) const
void viz_cb(pcl::visualization::PCLVisualizer &viz)
Eigen::Vector3f v3colorNrgb
! Radiometric description
float intensity_threshold
struct config_pbmap configPbMap
int read_int(const std::string §ion, const std::string &name, int defaultValue, bool failIfNotFound=false) const
void calcElongationAndPpalDir()
A class used to infer some semantic meaning to the planes of a PbMap.
std::string path_save_registered_cloud
std::map< unsigned, std::vector< unsigned > > groups
pcl::PointCloud< pcl::PointXYZRGBA >::Ptr alignedModelPtr
void mergePlanes(Plane &updatePlane, Plane &discardPlane)
void isFullExtent(Plane &plane, double newArea)
! Check if the area of input plane is stable and bounded (e.g < 1 m2) along the last keyframes that o...
std::string path_save_pbmap
std::set< unsigned > nearbyPlanes
pcl::PointCloud< pcl::PointXYZRGBA >::Ptr planePointCloudPtr
bool searchTheFloor(Eigen::Matrix4f &poseSensor, Plane &plane)
! Check if the input plane correpond to the floor.
void forcePtsLayOnPlane()
SemanticClustering * clusterize
float proximity_threshold
GLsizei const GLchar ** string
std::vector< unsigned > vQueueObservedPlanes
pcl::PointCloud< PointT >::Ptr globalMapPtr
bool arePlanesNearby(Plane &plane1, Plane &plane2, const float distThreshold)
float proximity_neighbor_planes
bool save_registered_cloud
float compute2DPolygonalArea()
Compute the area of a 2D planar polygon patch - using a given normal.
float dist3D_Segment_to_Segment2(Segment S1, Segment S2)
void detectPlanesCloud(pcl::PointCloud< PointT >::Ptr &pointCloudPtr_arg, Eigen::Matrix4f &poseKF, double distThreshold, double angleThreshold, double minInliersF)
int evalPartition(std::set< unsigned > &observedPlanes)
bool read_bool(const std::string §ion, const std::string &name, bool defaultValue, bool failIfNotFound=false) const
unsigned id
! Parameters to allow the plane-based representation of the map by a graph
bool isInHull(PointT &point3D, pcl::PointCloud< PointT >::Ptr hull3D)
void computeMassCenterAndArea()
Compute the patch's convex-hull area and mass center.
GLuint const GLchar * name
std::vector< frameRGBDandPose > frameQueue
Eigen::Vector3f v3center
! Geometric description
void readConfigFile(const string &config_file_name)
void savePbMap(std::string filePath)
std::vector< Plane > vPlanes
float max_dist_center_plane
#define ASSERT_FILE_EXISTS_(FIL)
unsigned currentSemanticGroup
int sprintf(char *buf, size_t bufSize, const char *format,...) noexcept MRPT_printf_format_check(3
An OS-independent version of sprintf (Notice the bufSize param, which may be ignored in some compiler...
void calcConvexHull(pcl::PointCloud< pcl::PointXYZRGBA >::Ptr &pointCloud, std::vector< size_t > &indices=DEFAULT_VECTOR)
! Calculate the plane's convex hull with the monotone chain algorithm.
CONTAINER::Scalar norm(const CONTAINER &v)
pcl::visualization::CloudViewer cloudViewer
Eigen::Vector3f getVector3fromPointXYZ(pointPCL &pt)
Eigen::Matrix< dataType, 3, 1 > compose(Eigen::Matrix< dataType, 4, 4 > &pose, Eigen::Matrix< dataType, 3, 1 > &point)
double BhattacharyyaDist(std::vector< float > &hist1, std::vector< float > &hist2)