22 #include <pcl/common/time.h> 23 #include <pcl/filters/voxel_grid.h> 146 out << v3normal(0) << v3normal(1) << v3normal(2);
147 out << v3center(0) << v3center(1) << v3center(2);
148 out << v3PpalDir(0) << v3PpalDir(1) << v3PpalDir(2);
149 out << v3colorNrgb(0) << v3colorNrgb(1) << v3colorNrgb(2);
152 out << dominantIntensity;
153 out << bDominantColor;
164 out << label_context;
166 out << (
uint32_t)polygonContourPtr->size();
167 for (
uint32_t i = 0; i < polygonContourPtr->size(); i++)
168 out << polygonContourPtr->points[i].x << polygonContourPtr->points[i].y
169 << polygonContourPtr->points[i].z;
186 in >> v3normal(0) >> v3normal(1) >> v3normal(2);
187 in >> v3center(0) >> v3center(1) >> v3center(2);
188 in >> v3PpalDir(0) >> v3PpalDir(1) >> v3PpalDir(2);
189 d = -v3normal.dot(v3center);
190 in >> v3colorNrgb(0) >> v3colorNrgb(1) >> v3colorNrgb(2);
193 in >> dominantIntensity;
194 in >> bDominantColor;
205 polygonContourPtr->resize(
n);
206 for (
unsigned i = 0; i <
n; i++)
207 in >> polygonContourPtr->points[i].x >>
208 polygonContourPtr->points[i].y >>
209 polygonContourPtr->points[i].z;
225 const double D = -(v3normal.dot(v3center));
226 for (
unsigned i = 0; i < planePointCloudPtr->size(); i++)
228 double dist = v3normal[0] * planePointCloudPtr->points[i].x +
229 v3normal[1] * planePointCloudPtr->points[i].y +
230 v3normal[2] * planePointCloudPtr->points[i].z + D;
231 planePointCloudPtr->points[i].x -= v3normal[0] * dist;
232 planePointCloudPtr->points[i].y -= v3normal[1] * dist;
233 planePointCloudPtr->points[i].z -= v3normal[2] * dist;
236 for (
unsigned i = 0; i < polygonContourPtr->size(); i++)
238 double dist = v3normal[0] * polygonContourPtr->points[i].x +
239 v3normal[1] * polygonContourPtr->points[i].y +
240 v3normal[2] * polygonContourPtr->points[i].z + D;
241 polygonContourPtr->points[i].x -= v3normal[0] * dist;
242 polygonContourPtr->points[i].y -= v3normal[1] * dist;
243 polygonContourPtr->points[i].z -= v3normal[2] * dist;
255 k0 = (fabs(v3normal[0]) > fabs(v3normal[1])) ? 0 : 1;
256 k0 = (fabs(v3normal[k0]) > fabs(v3normal[2])) ? k0 : 2;
262 float ct = fabs(v3normal[k0]);
264 float p_i[3], p_j[3];
266 for (
unsigned int i = 0; i < polygonContourPtr->points.size(); i++)
268 p_i[0] = polygonContourPtr->points[i].x;
269 p_i[1] = polygonContourPtr->points[i].y;
270 p_i[2] = polygonContourPtr->points[i].z;
271 int j = (i + 1) % polygonContourPtr->points.size();
272 p_j[0] = polygonContourPtr->points[j].x;
273 p_j[1] = polygonContourPtr->points[j].y;
274 p_j[2] = polygonContourPtr->points[j].z;
276 AreaX2 += p_i[k1] * p_j[k2] - p_i[k2] * p_j[k1];
278 AreaX2 = fabs(AreaX2) / (2 * ct);
291 k0 = (fabs(v3normal[0]) > fabs(v3normal[1])) ? 0 : 1;
292 k0 = (fabs(v3normal[k0]) > fabs(v3normal[2])) ? k0 : 2;
298 float ct = fabs(v3normal[k0]);
300 Eigen::Vector3f massCenter = Eigen::Vector3f::Zero();
301 float p_i[3], p_j[3];
303 for (
unsigned int i = 0; i < polygonContourPtr->points.size(); i++)
305 p_i[0] = polygonContourPtr->points[i].x;
306 p_i[1] = polygonContourPtr->points[i].y;
307 p_i[2] = polygonContourPtr->points[i].z;
308 int j = (i + 1) % polygonContourPtr->points.size();
309 p_j[0] = polygonContourPtr->points[j].x;
310 p_j[1] = polygonContourPtr->points[j].y;
311 p_j[2] = polygonContourPtr->points[j].z;
312 double cross_segment = p_i[k1] * p_j[k2] - p_i[k2] * p_j[k1];
314 AreaX2 += cross_segment;
315 massCenter[k1] += (p_i[k1] + p_j[k1]) * cross_segment;
316 massCenter[k2] += (p_i[k2] + p_j[k2]) * cross_segment;
318 areaHull = fabs(AreaX2) / (2 * ct);
320 massCenter[k1] /= (3 * AreaX2);
321 massCenter[k2] /= (3 * AreaX2);
322 massCenter[k0] = (v3normal.dot(v3center) - v3normal[k1] * massCenter[k1] -
323 v3normal[k2] * massCenter[k2]) /
326 v3center = massCenter;
328 d = -(v3normal.dot(v3center));
333 pcl::PCA<PointT> pca;
334 pca.setInputCloud(planePointCloudPtr);
335 Eigen::VectorXf eigenVal = pca.getEigenValues();
338 elongation = sqrt(eigenVal[0] / eigenVal[1]);
339 Eigen::MatrixXf eigenVect = pca.getEigenVectors();
342 v3PpalDir[0] = eigenVect(0, 0);
343 v3PpalDir[1] = eigenVect(1, 0);
344 v3PpalDir[2] = eigenVect(2, 0);
352 assert(planePointCloudPtr->size() > 0);
354 r.resize(planePointCloudPtr->size());
355 g.resize(planePointCloudPtr->size());
356 b.resize(planePointCloudPtr->size());
357 intensity.resize(planePointCloudPtr->size());
360 for (
size_t i = 0; i < planePointCloudPtr->size(); i++)
362 float sumRGB = (float)planePointCloudPtr->points[i].r +
363 planePointCloudPtr->points[i].g +
364 planePointCloudPtr->points[i].b;
365 intensity[i] = sumRGB;
368 r[countPix] = planePointCloudPtr->points[i].r / sumRGB;
369 g[countPix] = planePointCloudPtr->points[i].g / sumRGB;
370 b[countPix] = planePointCloudPtr->points[i].b / sumRGB;
377 intensity.resize(countPix);
382 c1.resize(planePointCloudPtr->size());
383 c2.resize(planePointCloudPtr->size());
384 c3.resize(planePointCloudPtr->size());
386 for (
unsigned i = 0; i < planePointCloudPtr->size(); i++)
389 (
double)planePointCloudPtr->points[i].r,
391 planePointCloudPtr->points[i].g,
392 planePointCloudPtr->points[i].b));
394 (
double)planePointCloudPtr->points[i].g,
396 planePointCloudPtr->points[i].r,
397 planePointCloudPtr->points[i].b));
399 (
double)planePointCloudPtr->points[i].b,
401 planePointCloudPtr->points[i].r,
402 planePointCloudPtr->points[i].g));
411 const float FLOAT_TO_BYTE = 255.0f;
412 const float BYTE_TO_FLOAT = 1.0f / FLOAT_TO_BYTE;
414 vector<int> H(74, 0);
416 for (
unsigned i = 0; i < planePointCloudPtr->size(); i++)
419 fR = planePointCloudPtr->points[i].r * BYTE_TO_FLOAT;
420 fG = planePointCloudPtr->points[i].g * BYTE_TO_FLOAT;
421 fB = planePointCloudPtr->points[i].b * BYTE_TO_FLOAT;
427 if (planePointCloudPtr->points[i].b < planePointCloudPtr->points[i].g)
429 if (planePointCloudPtr->points[i].b <
430 planePointCloudPtr->points[i].r)
433 if (planePointCloudPtr->points[i].r >
434 planePointCloudPtr->points[i].g)
436 iMax = planePointCloudPtr->points[i].r;
441 iMax = planePointCloudPtr->points[i].g;
449 iMax = planePointCloudPtr->points[i].g;
454 if (planePointCloudPtr->points[i].g <
455 planePointCloudPtr->points[i].r)
458 if (planePointCloudPtr->points[i].b >
459 planePointCloudPtr->points[i].r)
462 iMax = planePointCloudPtr->points[i].b;
467 iMax = planePointCloudPtr->points[i].r;
474 iMax = planePointCloudPtr->points[i].b;
477 fDelta = fMax - fMin;
500 float ANGLE_TO_UNIT = 12.0f / fDelta;
501 if (iMax == planePointCloudPtr->points[i].r)
503 fH = (fG - fB) * ANGLE_TO_UNIT;
505 else if (iMax == planePointCloudPtr->points[i].g)
507 fH = (2.0f / 6.0f) + (fB - fR) * ANGLE_TO_UNIT;
511 fH = (4.0f / 6.0f) + (fR - fG) * ANGLE_TO_UNIT;
514 if (fH < 0.0f) fH += 72.0f;
515 if (fH >= 72.0f) fH -= 72.0f;
523 for (
unsigned i = 0; i < H.size(); i++) numPixels += H[i];
525 for (
unsigned i = 0; i < H.size(); i++) hist_H[i] = H[i] / numPixels;
534 assert(planePointCloudPtr->size() > 0);
538 std::vector<Eigen::Vector4f>
color(planePointCloudPtr->size());
541 size_t stepColor = std::max(
542 planePointCloudPtr->size() / 2000,
545 for (
size_t i = 0; i < planePointCloudPtr->size(); i += stepColor)
547 float sumRGB = (float)planePointCloudPtr->points[i].r +
548 planePointCloudPtr->points[i].g +
549 planePointCloudPtr->points[i].b;
552 color[countPix][0] = planePointCloudPtr->points[i].r / sumRGB;
553 color[countPix][1] = planePointCloudPtr->points[i].g / sumRGB;
554 color[countPix][2] = planePointCloudPtr->points[i].b / sumRGB;
555 color[countPix][3] = sumRGB;
563 color.resize(countPix);
564 intensity.resize(countPix);
566 float concentration, histStdDev;
568 Eigen::Vector4f dominantColor =
570 v3colorNrgb = dominantColor.head(3);
571 dominantIntensity = dominantColor(3);
574 bDominantColor =
true;
576 bDominantColor =
false;
619 dominantIntensity = 0;
620 int countFringe05 = 0;
621 for (
unsigned i = 0; i <
r.size(); i++)
622 if (fabs(
r[i] - v3colorNrgb(0)) < 0.05 &&
623 fabs(
g[i] - v3colorNrgb(1)) < 0.05 &&
624 fabs(
b[i] - v3colorNrgb(2)) < 0.05)
626 dominantIntensity += intensity[i];
629 assert(countFringe05 > 0);
630 dominantIntensity /= countFringe05;
631 float concentration05 =
static_cast<float>(countFringe05) /
r.size();
641 if (concentration05 > 0.5)
642 bDominantColor =
true;
644 bDominantColor =
false;
680 return x <
p.x || (
x ==
p.x &&
y <
p.y);
686 return (A.
x - O.
x) * (B.
y - O.
y) - (A.
y - O.
y) * (B.
x - O.
x);
762 pcl::PointCloud<pcl::PointXYZRGBA>::Ptr& pointCloud,
768 k0 = (fabs(v3normal(0)) > fabs(v3normal[1])) ? 0 : 1;
769 k0 = (fabs(v3normal(k0)) > fabs(v3normal(2))) ? k0 : 2;
771 std::vector<mPointHull> P;
772 P.resize(pointCloud->size());
774 for (
size_t i = 0; i < pointCloud->size(); i++)
776 P[i].x = pointCloud->points[i].y;
777 P[i].y = pointCloud->points[i].z;
781 for (
size_t i = 0; i < pointCloud->size(); i++)
783 P[i].x = pointCloud->points[i].x;
784 P[i].y = pointCloud->points[i].z;
788 for (
size_t i = 0; i < pointCloud->size(); i++)
790 P[i].x = pointCloud->points[i].x;
791 P[i].y = pointCloud->points[i].y;
795 int n = P.size(), k = 0;
796 std::vector<mPointHull> H(2 *
n);
799 std::sort(P.begin(), P.end());
802 for (
int i = 0; i <
n; i++)
804 while (k >= 2 &&
cross(H[k - 2], H[k - 1], P[i]) <= 0) k--;
806 if (k > 0) assert(H[k - 1].
id != H[k - 2].
id);
810 for (
int i =
n - 2,
t = k + 1; i >= 0; i--)
812 while (k >=
t &&
cross(H[k - 2], H[k - 1], P[i]) <= 0) k--;
817 size_t hull_noRep = k - 1;
819 polygonContourPtr->resize(hull_noRep);
822 for (
size_t i = 0; i < hull_noRep; i++)
824 polygonContourPtr->points[i] = pointCloud->points[H[i].id];
830 pcl::PointCloud<pcl::PointXYZRGBA>::Ptr& pointCloud,
836 k0 = (fabs(v3normal(0)) > fabs(v3normal[1])) ? 0 : 1;
837 k0 = (fabs(v3normal(k0)) > fabs(v3normal(2))) ? k0 : 2;
841 std::vector<mPointHull> P;
842 P.resize(pointCloud->size());
844 for (
size_t i = 0; i < pointCloud->size(); i++)
846 P[i].x = pointCloud->points[i].y;
847 P[i].y = pointCloud->points[i].z;
851 for (
size_t i = 0; i < pointCloud->size(); i++)
853 P[i].x = pointCloud->points[i].z;
854 P[i].y = pointCloud->points[i].x;
858 for (
size_t i = 0; i < pointCloud->size(); i++)
860 P[i].x = pointCloud->points[i].x;
861 P[i].y = pointCloud->points[i].y;
865 int n = P.size(), k = 0;
866 std::vector<mPointHull> H(2 *
n);
869 std::sort(P.begin(), P.end());
872 for (
int i = 0; i <
n; i++)
874 while (k >= 2 &&
cross(H[k - 2], H[k - 1], P[i]) <= 0) k--;
876 if (k > 0) assert(H[k - 1].
id != H[k - 2].
id);
880 for (
int i =
n - 2,
t = k + 1; i >= 0; i--)
882 while (k >=
t &&
cross(H[k - 2], H[k - 1], P[i]) <= 0) k--;
887 size_t hull_noRep = k - 1;
889 polygonContourPtr->resize(hull_noRep);
892 for (
size_t i = 0; i < hull_noRep; i++)
894 polygonContourPtr->points[i] = pointCloud->points[H[i].id];
899 float ct = fabs(v3normal[k0]);
901 Eigen::Vector3f massCenter = Eigen::Vector3f::Zero();
902 for (
size_t i = 0, j = 1; i < hull_noRep; i++, j++)
904 float cross_segment = H[i].x * H[j].y - H[i].y * H[j].x;
906 AreaX2 += cross_segment;
907 massCenter[k1] += (H[i].x + H[j].x) * cross_segment;
908 massCenter[k2] += (H[i].y + H[j].y) * cross_segment;
910 areaHull = fabs(AreaX2) / (2 * ct);
912 v3center[k1] /= (3 * AreaX2);
913 v3center[k2] /= (3 * AreaX2);
915 (-d - v3normal[k1] * massCenter[k1] - v3normal[k2] * massCenter[k2]) /
918 d = -v3normal.dot(v3center);
921 Eigen::Matrix2f covariances = Eigen::Matrix2f::Zero();
922 Eigen::Vector2f p1, p2;
923 p2[0] = H[0].x - massCenter[k1];
924 p2[1] = H[0].y - massCenter[k2];
926 for (
size_t i = 1; i < hull_noRep; i++)
929 p2[0] = H[i].x - massCenter[k1];
930 p2[1] = H[i].y - massCenter[k2];
931 float lenght_side = (p1 - p2).
norm();
934 lenght_side * (p1 * p1.transpose() + p2 * p2.transpose());
941 for (
int i = 0; i < 2; ++i)
943 std::cout <<
"Eig " << evd.eigenvalues()[i] <<
" v " 944 << evd.eigenvectors().col(i).transpose() <<
"\n";
946 if (evd.eigenvalues()[0] > 2 * evd.eigenvalues()[1])
948 elongation = sqrt(evd.eigenvalues()[0] / evd.eigenvalues()[1]);
949 v3PpalDir[k1] = evd.eigenvectors()(0, 0);
950 v3PpalDir[k2] = evd.eigenvectors()(1, 0);
952 (-d - v3normal[k1] * v3PpalDir[k1] - v3normal[k2] * v3PpalDir[k2]) /
954 v3PpalDir /= v3PpalDir.norm();
962 float distThres2 = distThreshold * distThreshold;
966 if ((v3center - plane_nearby.
v3center).squaredNorm() < distThres2)
969 for (
unsigned i = 1; i < polygonContourPtr->size(); i++)
972 .squaredNorm() < distThres2)
978 .squaredNorm() < distThres2)
981 for (
unsigned i = 1; i < polygonContourPtr->size(); i++)
984 polygonContourPtr->points[i],
986 .squaredNorm() < distThres2)
992 for (
unsigned i = 1; i < polygonContourPtr->size(); i++)
996 polygonContourPtr->points[i],
997 polygonContourPtr->points[i - 1]),
1012 Plane& plane_nearby,
const float& cosAngleThreshold,
1013 const float& parallelDistThres,
const float& proxThreshold)
1016 if (v3normal.dot(plane_nearby.
v3normal) < cosAngleThreshold)
return false;
1020 float dist_normal = v3normal.dot(plane_nearby.
v3center - v3center);
1021 if (fabs(dist_normal) > parallelDistThres)
1025 if (!isPlaneNearby(plane_nearby, proxThreshold))
return false;
1035 Eigen::Matrix4f& Rt,
Plane& plane_,
const float& cosAngleThreshold,
1036 const float& parallelDistThres,
const float& proxThreshold)
1038 Plane plane = plane_;
1041 Rt.block(0, 0, 3, 3) * plane_.
v3center + Rt.block(0, 3, 3, 1);
1042 pcl::transformPointCloud(
1045 if (fabs(d - plane.
d) > parallelDistThres)
return false;
1048 if (v3normal.dot(plane.
v3normal) < cosAngleThreshold)
return false;
1065 return isPlaneNearby(plane, proxThreshold);
1071 (fabs(v3colorNrgb[0] - plane.
v3colorNrgb[0]) > colorThreshold ||
1072 fabs(v3colorNrgb[1] - plane.
v3colorNrgb[1]) > colorThreshold))
1088 assert(inliers.size() > 0 && same_plane_patch.
inliers.size() > 0);
1090 (inliers.size() * v3normal +
1092 v3normal = v3normal / v3normal.norm();
1097 *planePointCloudPtr +=
1104 static pcl::VoxelGrid<pcl::PointXYZRGBA> merge_grid;
1105 merge_grid.setLeafSize(0.05, 0.05, 0.05);
1106 pcl::PointCloud<pcl::PointXYZRGBA> mergeCloud;
1107 merge_grid.setInputCloud(planePointCloudPtr);
1108 merge_grid.filter(mergeCloud);
1109 planePointCloudPtr->clear();
1110 *planePointCloudPtr = mergeCloud;
1116 inliers.end(), same_plane_patch.
inliers.begin(),
1117 same_plane_patch.
inliers.end());
1121 computeMassCenterAndArea();
1123 d = -v3normal.dot(v3center);
1126 forcePtsLayOnPlane();
1131 areaVoxels = planePointCloudPtr->size() * 0.0025;
1138 assert(inliers.size() > 0 && same_plane_patch.
inliers.size() > 0);
1140 (inliers.size() * v3normal +
1142 v3normal = v3normal / v3normal.norm();
1145 *planePointCloudPtr +=
1151 inliers.end(), same_plane_patch.
inliers.begin(),
1152 same_plane_patch.
inliers.end());
1160 computeMassCenterAndArea();
1162 calcElongationAndPpalDir();
1164 d = -v3normal.dot(v3center);
1172 for (
size_t i = 0; i < hist_H.size(); i++)
1174 hist_H[i] += same_plane_patch.
hist_H[i];
1182 v3normal = Rt.block(0, 0, 3, 3) * v3normal;
1183 v3PpalDir = Rt.block(0, 0, 3, 3) * v3PpalDir;
1186 v3center = Rt.block(0, 0, 3, 3) * v3center + Rt.block(0, 3, 3, 1);
1188 d = -(v3normal.dot(v3center));
1191 pcl::transformPointCloud(*polygonContourPtr, *polygonContourPtr, Rt);
1193 pcl::transformPointCloud(*planePointCloudPtr, *planePointCloudPtr, Rt);
Eigen::Vector4f getMultiDimMeanShift_color(std::vector< Eigen::Vector4f > &data, dataType &stdDevHist, dataType &concentration)
Eigen::Vector3f diffPoints(const POINT &P1, const POINT &P2)
pcl::PointCloud< pcl::PointXYZRGBA >::Ptr polygonContourPtr
void transform(Eigen::Matrix4f &Rt)
A class used to store a planar feature (Plane for short).
#define IMPLEMENTS_SERIALIZABLE(class_name, base, NameSpace)
This must be inserted in all CSerializable classes implementation files.
void mergePlane2(Plane &plane)
GLuint GLuint GLsizei GLenum const GLvoid * indices
void serializeFrom(mrpt::serialization::CArchive &in, uint8_t serial_version) override
Pure virtual method for reading (deserializing) from an abstract archive.
void mergePlane(Plane &plane)
Eigen::Vector3f v3colorNrgb
! Radiometric description
void calcConvexHullandParams(pcl::PointCloud< pcl::PointXYZRGBA >::Ptr &pointCloud, std::vector< size_t > &indices=DEFAULT_VECTOR)
bool operator<(const mPointHull &p) const
void calcElongationAndPpalDir()
#define MRPT_THROW_UNKNOWN_SERIALIZATION_VERSION(__V)
For use in CSerializable implementations.
! mPointHull serves to calculate the convex hull of a set of points in 2D, which are defined by its p...
pcl::PointCloud< pcl::PointXYZRGBA >::Ptr planePointCloudPtr
dataType getHistogramMeanShift(std::vector< dataType > &data, double range, dataType &stdDevHist_out)
void forcePtsLayOnPlane()
float cross(const mPointHull &O, const mPointHull &A, const mPointHull &B)
bool isSamePlane(Plane &plane, const float &cosAngleThreshold, const float &distThreshold, const float &proxThreshold)
bool isPlaneNearby(Plane &plane, const float distThreshold)
float compute2DPolygonalArea()
Compute the area of a 2D planar polygon patch - using a given normal.
void serializeTo(mrpt::serialization::CArchive &out) const override
Pure virtual method for writing (serializing) to an abstract archive.
Virtual base class for "archives": classes abstracting I/O streams.
float dist3D_Segment_to_Segment2(Segment S1, Segment S2)
GLdouble GLdouble GLdouble r
void computeMassCenterAndArea()
Compute the patch's convex-hull area and mass center.
std::vector< int32_t > inliers
! Convex Hull
std::vector< float > hist_H
Eigen::Vector3f v3center
! Geometric description
float concentrationThreshold
unsigned __int32 uint32_t
bool hasSimilarDominantColor(Plane &plane, const float colorThreshold)
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)
Eigen::Vector3f getVector3fromPointXYZ(pointPCL &pt)