8 #ifndef CORELIB_INCLUDE_RTABMAP_CORE_IMPL_UTIL3D_SURFACE_HPP_ 9 #define CORELIB_INCLUDE_RTABMAP_CORE_IMPL_UTIL3D_SURFACE_HPP_ 11 #include <pcl/search/kdtree.h> 12 #include <pcl/conversions.h> 19 template<
typename po
intT>
21 const typename pcl::PointCloud<pointT> & cloud,
22 const std::vector<pcl::Vertices> & polygons,
23 const pcl::PointXYZ & viewPoint)
25 std::vector<pcl::Vertices> output(polygons.size());
26 for(
unsigned int i=0; i<polygons.size(); ++i)
28 pcl::Vertices polygon = polygons[i];
29 Eigen::Vector3f v1 = cloud.at(polygon.vertices[1]).getVector3fMap() - cloud.at(polygon.vertices[0]).getVector3fMap();
30 Eigen::Vector3f v2 = cloud.at(polygon.vertices[2]).getVector3fMap() - cloud.at(polygon.vertices[0]).getVector3fMap();
31 Eigen::Vector3f n = (v1.cross(v2)).normalized();
33 Eigen::Vector3f p = Eigen::Vector3f(viewPoint.x, viewPoint.y, viewPoint.z) - cloud.at(polygon.vertices[1]).getVector3fMap();
35 float result = n.dot(p);
39 int tmp = polygon.vertices[0];
40 polygon.vertices[0] = polygon.vertices[2];
41 polygon.vertices[2] = tmp;
49 template<
typename po
intRGBT>
51 pcl::PolygonMeshPtr & mesh,
52 float meshDecimationFactor,
54 const typename pcl::PointCloud<pointRGBT>::Ptr & cloud,
55 float transferColorRadius,
62 bool hasNormals =
false;
63 bool hasColors =
false;
64 for(
unsigned int i=0; i<mesh->cloud.fields.size(); ++i)
66 if(mesh->cloud.fields[i].name.compare(
"normal_x") == 0)
70 else if(mesh->cloud.fields[i].name.compare(
"rgb") == 0)
76 if(maximumPolygons > 0)
78 double factor = 1.0-double(maximumPolygons)/double(mesh->polygons.size());
79 if(factor > meshDecimationFactor)
81 meshDecimationFactor = factor;
84 if(meshDecimationFactor > 0.0)
86 unsigned int count = mesh->polygons.size();
87 if(progressState) progressState->
callback(
uFormat(
"Mesh decimation (factor=%f) from %d polygons...",meshDecimationFactor, (
int)count));
90 if(progressState) progressState->
callback(
uFormat(
"Mesh decimated (factor=%f) from %d to %d polygons", meshDecimationFactor, (
int)count, (
int)mesh->polygons.size()));
91 if(count < mesh->polygons.size())
93 if(progressState) progressState->
callback(
uFormat(
"Decimated mesh has more polygons than before!"));
101 transferColorRadius >= 0.0)
103 if(progressState) progressState->
callback(
uFormat(
"Transferring color from point cloud to mesh..."));
106 typename pcl::search::KdTree<pointRGBT>::Ptr
tree (
new pcl::search::KdTree<pointRGBT>(
true));
107 tree->setInputCloud(cloud);
108 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr coloredCloud(
new pcl::PointCloud<pcl::PointXYZRGBNormal>);
109 pcl::fromPCLPointCloud2(mesh->cloud, *coloredCloud);
110 std::vector<bool> coloredPts(coloredCloud->size());
111 for(
unsigned int i=0; i<coloredCloud->size(); ++i)
114 std::vector<float> kDistances;
116 pt.x = coloredCloud->at(i).x;
117 pt.y = coloredCloud->at(i).y;
118 pt.z = coloredCloud->at(i).z;
119 if(transferColorRadius > 0.0)
121 tree->radiusSearch(pt, transferColorRadius, kIndices, kDistances);
125 tree->nearestKSearch(pt, 1, kIndices, kDistances);
134 for(
unsigned int j=0; j<kIndices.size(); ++j)
136 r+=(int)cloud->at(kIndices[j]).r;
137 g+=(int)cloud->at(kIndices[j]).g;
138 b+=(int)cloud->at(kIndices[j]).b;
139 a+=(int)cloud->at(kIndices[j]).a;
141 coloredCloud->at(i).r = r/kIndices.size();
142 coloredCloud->at(i).g = g/kIndices.size();
143 coloredCloud->at(i).b = b/kIndices.size();
144 coloredCloud->at(i).a = a/kIndices.size();
145 coloredPts.at(i) =
true;
150 coloredCloud->at(i).r = coloredCloud->at(i).g = coloredCloud->at(i).b = 255;
151 coloredPts.at(i) =
false;
154 pcl::toPCLPointCloud2(*coloredCloud, mesh->cloud);
159 std::vector<pcl::Vertices> filteredPolygons(mesh->polygons.size());
161 for(
unsigned int i=0; i<mesh->polygons.size(); ++i)
163 bool coloredPolygon =
true;
164 for(
unsigned int j=0; j<mesh->polygons[i].vertices.size(); ++j)
166 if(!coloredPts.at(mesh->polygons[i].vertices[j]))
168 coloredPolygon =
false;
174 filteredPolygons[oi++] = mesh->polygons[i];
177 filteredPolygons.resize(oi);
178 mesh->polygons = filteredPolygons;
185 if(progressState) progressState->
callback(
uFormat(
"Filter small polygon clusters..."));
188 std::vector<std::set<int> > neighbors;
189 std::vector<std::set<int> > vertexToPolygons;
191 mesh->cloud.height*mesh->cloud.width,
196 minClusterSize<0?0:minClusterSize);
198 std::vector<pcl::Vertices> filteredPolygons(mesh->polygons.size());
199 if(minClusterSize < 0)
202 std::list<std::list<int> >::iterator biggestClusterIndex = clusters.end();
203 unsigned int biggestClusterSize = 0;
204 for(std::list<std::list<int> >::iterator iter=clusters.begin(); iter!=clusters.end(); ++iter)
206 if(iter->size() > biggestClusterSize)
208 biggestClusterIndex = iter;
209 biggestClusterSize = iter->size();
212 if(biggestClusterIndex != clusters.end())
215 for(std::list<int>::iterator jter=biggestClusterIndex->begin(); jter!=biggestClusterIndex->end(); ++jter)
217 filteredPolygons[oi++] = mesh->polygons.at(*jter);
219 filteredPolygons.resize(oi);
225 for(std::list<std::list<int> >::iterator iter=clusters.begin(); iter!=clusters.end(); ++iter)
227 for(std::list<int>::iterator jter=iter->begin(); jter!=iter->end(); ++jter)
229 filteredPolygons[oi++] = mesh->polygons.at(*jter);
232 filteredPolygons.resize(oi);
235 int before = (int)mesh->polygons.size();
236 mesh->polygons = filteredPolygons;
238 if(progressState) progressState->
callback(
uFormat(
"Filtered %d polygons.", before-(
int)mesh->polygons.size()));
242 if(!hasNormals || (!hasColors && coloredOutput))
245 if(hasColors || coloredOutput)
247 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr cloud (
new pcl::PointCloud<pcl::PointXYZRGBNormal>);
248 pcl::fromPCLPointCloud2(mesh->cloud, *cloud);
250 Eigen::Vector3f normal(1,0,0);
251 for(
unsigned int i=0; i<mesh->polygons.size(); ++i)
253 pcl::Vertices & v = mesh->polygons[i];
258 cloud->at(v.vertices[1]).x - cloud->at(v.vertices[0]).x,
259 cloud->at(v.vertices[1]).y - cloud->at(v.vertices[0]).y,
260 cloud->at(v.vertices[1]).z - cloud->at(v.vertices[0]).z);
261 int last = v.vertices.size()-1;
263 cloud->at(v.vertices[last]).x - cloud->at(v.vertices[0]).x,
264 cloud->at(v.vertices[last]).y - cloud->at(v.vertices[0]).y,
265 cloud->at(v.vertices[last]).z - cloud->at(v.vertices[0]).z);
266 normal = v0.cross(v1);
270 for(
unsigned int j=0; j<v.vertices.size(); ++j)
274 cloud->at(v.vertices[j]).normal_x = normal[0];
275 cloud->at(v.vertices[j]).normal_y = normal[1];
276 cloud->at(v.vertices[j]).normal_z = normal[2];
280 cloud->at(v.vertices[j]).r = 255;
281 cloud->at(v.vertices[j]).g = 255;
282 cloud->at(v.vertices[j]).b = 255;
286 pcl::toPCLPointCloud2 (*cloud, mesh->cloud);
290 pcl::PointCloud<pcl::PointNormal>::Ptr cloud (
new pcl::PointCloud<pcl::PointNormal>);
291 pcl::fromPCLPointCloud2(mesh->cloud, *cloud);
293 for(
unsigned int i=0; i<mesh->polygons.size(); ++i)
295 pcl::Vertices & v = mesh->polygons[i];
298 cloud->at(v.vertices[1]).x - cloud->at(v.vertices[0]).x,
299 cloud->at(v.vertices[1]).y - cloud->at(v.vertices[0]).y,
300 cloud->at(v.vertices[1]).z - cloud->at(v.vertices[0]).z);
301 int last = v.vertices.size()-1;
303 cloud->at(v.vertices[last]).x - cloud->at(v.vertices[0]).x,
304 cloud->at(v.vertices[last]).y - cloud->at(v.vertices[0]).y,
305 cloud->at(v.vertices[last]).z - cloud->at(v.vertices[0]).z);
306 Eigen::Vector3f normal = v0.cross(v1);
309 for(
unsigned int j=0; j<v.vertices.size(); ++j)
311 cloud->at(v.vertices[j]).normal_x = normal[0];
312 cloud->at(v.vertices[j]).normal_y = normal[1];
313 cloud->at(v.vertices[j]).normal_z = normal[2];
316 pcl::toPCLPointCloud2 (*cloud, mesh->cloud);
321 template<
typename Po
intT>
323 const Eigen::Vector3f & origin,
324 const Eigen::Vector3f & dir,
325 const typename pcl::PointCloud<PointT> & cloud,
326 const std::vector<pcl::Vertices> & polygons,
327 bool ignoreBackFaces,
329 Eigen::Vector3f & normal,
332 bool intersect =
false;
334 for (
size_t i = 0; i < polygons.size(); ++i)
336 const pcl::Vertices & vert = polygons.at(i);
337 UASSERT(vert.vertices.size()==3);
341 cloud.at(vert.vertices.at(0)).getVector3fMap(),
342 cloud.at(vert.vertices.at(1)).getVector3fMap(),
343 cloud.at(vert.vertices.at(2)).getVector3fMap(), d, n) &&
345 (!ignoreBackFaces || n.dot(dir)<0))
void denseMeshPostProcessing(pcl::PolygonMeshPtr &mesh, float meshDecimationFactor, int maximumPolygons, const typename pcl::PointCloud< pointRGBT >::Ptr &cloud, float transferColorRadius, bool coloredOutput, bool cleanMesh, int minClusterSize, ProgressState *progressState)
bool RTABMAP_EXP intersectRayTriangle(const Eigen::Vector3f &p, const Eigen::Vector3f &dir, const Eigen::Vector3f &v0, const Eigen::Vector3f &v1, const Eigen::Vector3f &v2, float &distance, Eigen::Vector3f &normal)
GLM_FUNC_DECL genType::value_type distance(genType const &p0, genType const &p1)
Some conversion functions.
bool intersectRayMesh(const Eigen::Vector3f &origin, const Eigen::Vector3f &dir, const typename pcl::PointCloud< PointT > &cloud, const std::vector< pcl::Vertices > &polygons, bool ignoreBackFaces, float &distance, Eigen::Vector3f &normal, int &index)
#define UASSERT(condition)
virtual bool callback(const std::string &msg) const
std::list< std::list< int > > RTABMAP_EXP clusterPolygons(const std::vector< std::set< int > > &neighborPolygons, int minClusterSize=0)
pcl::PolygonMesh::Ptr RTABMAP_EXP meshDecimation(const pcl::PolygonMesh::Ptr &mesh, float factor)
std::vector< pcl::Vertices > normalizePolygonsSide(const typename pcl::PointCloud< pointT > &cloud, const std::vector< pcl::Vertices > &polygons, const pcl::PointXYZ &viewPoint)
GLM_FUNC_DECL genType max(genType const &x, genType const &y)
void RTABMAP_EXP createPolygonIndexes(const std::vector< pcl::Vertices > &polygons, int cloudSize, std::vector< std::set< int > > &neighborPolygons, std::vector< std::set< int > > &vertexPolygons)
Given a set of polygons, create two indexes: polygons to neighbor polygons and vertices to polygons...
static const GLushort kIndices[]
std::string UTILITE_EXP uFormat(const char *fmt,...)