00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00033 #ifndef _projection_mesh_CPP_
00034 #define _projection_mesh_CPP_
00035
00036 #include "projection_mesh.h"
00037
00038
00039
00040 int class_projection_mesh::clear_constraints(void)
00041 {
00042 for (PT::Vertex_iterator it=mesh.vertices_begin(); it!=mesh.vertices_end(); ++it)
00043 {
00044 mesh.remove_incident_constraints(it);
00045 }
00046 return 1;
00047 }
00048
00049 int class_projection_mesh::clear_vertices(void)
00050 {
00051 mesh.clear();
00052 return 1;
00053 }
00054
00055 int class_projection_mesh::set_constraint_polygon(std::vector<pcl::PointXY>* p)
00056 {
00057 PT::Locate_type lt;
00058 int li;
00059 std::vector<PT::Vertex_handle> vv;
00060
00061 for (size_t i=0; i<p->size();i++)
00062 {
00063 pcl::PointXY pt = p->at(i);
00064 PT::Face_handle fh = mesh.locate(PT::Point(pt.x,pt.y), lt, li);
00065
00066 if (lt==PT::VERTEX)
00067 {
00068 vv.push_back(fh->vertex(li));
00069 }
00070 else
00071 {
00072 PT::Vertex_handle vh;
00073 vh = mesh.insert(PT::Point(pt.x,pt.y));
00074 vh->info().z = 0;
00075 vh->info().rgb = -1;
00076 vh->info().weight = 0;
00077 vv.push_back(vh);
00078 }
00079 }
00080
00081
00082 for (size_t i=1; i<vv.size();i++)
00083 {
00084 mesh.insert_constraint(vv[i-1], vv[i]);
00085 }
00086 mesh.insert_constraint(vv[vv.size()-1], vv[0]);
00087
00088 return 1;
00089 }
00090
00091 int class_projection_mesh::add_vertex_to_mesh(double x, double y, double z, float rgb, float weight)
00092 {
00093 PT::Vertex_handle vh;
00094 vh = mesh.insert(PT::Point(x,y));
00095 vh->info().z = z;
00096 vh->info().rgb = rgb;
00097 vh->info().weight = weight;
00098 return 1;
00099 }
00100
00101 int class_projection_mesh::initialize_all_faces_status(void)
00102 {
00103 for(PT::All_faces_iterator it = mesh.all_faces_begin(); it != mesh.all_faces_end(); ++it)
00104 {
00105 it->counter=-1;
00106 it->status=-1;
00107 }
00108 return 1;
00109 }
00110
00111
00112 void class_projection_mesh::discoverComponent(const PT& ct,
00113 PT::Face_handle start,
00114 int index,
00115 std::list<PT::Edge>& border )
00116 {
00117 if(start->counter != -1)
00118 {
00119 return;
00120 }
00121 std::list<PT::Face_handle> queue;
00122 queue.push_back(start);
00123
00124 while(! queue.empty())
00125 {
00126 PT::Face_handle fh = queue.front();
00127 queue.pop_front();
00128 if(fh->counter == -1)
00129 {
00130 fh->counter = index;
00131 fh->set_in_domain(index%2 == 1);
00132 for(int i = 0; i < 3; i++)
00133 {
00134 PT::Edge e(fh,i);
00135 PT::Face_handle n = fh->neighbor(i);
00136 if(n->counter == -1)
00137 {
00138 if(ct.is_constrained(e))
00139 {
00140 border.push_back(e);
00141 }
00142 else
00143 {
00144 queue.push_back(n);
00145 }
00146 }
00147
00148 }
00149 }
00150 }
00151 }
00152
00153 void class_projection_mesh::discoverComponents(const PT& ct)
00154 {
00155 int index = 0;
00156 std::list<PT::Edge> border;
00157 discoverComponent(ct, ct.infinite_face(), index++, border);
00158 while(! border.empty())
00159 {
00160 PT::Edge e = border.front();
00161 border.pop_front();
00162 PT::Face_handle n = e.first->neighbor(e.second);
00163 if(n->counter == -1)
00164 {
00165 discoverComponent(ct, n, e.first->counter+1, border);
00166 }
00167 }
00168 }
00169
00170
00171 int class_projection_mesh::draw_mesh_triangles(cv::Mat* image, cv::Scalar color, int thickness)
00172 {
00173 for(PT::Finite_faces_iterator fc1 = mesh.finite_faces_begin(); fc1 != mesh.finite_faces_end(); ++fc1)
00174 {
00175 if (!fc1->is_in_domain())
00176 {
00177
00178 }
00179
00180 cv::line(*image, cv::Point2d( CGAL::to_double(fc1->vertex(0)->point().x()), CGAL::to_double(fc1->vertex(0)->point().y())), cv::Point2d( CGAL::to_double(fc1->vertex(1)->point().x()), CGAL::to_double(fc1->vertex(1)->point().y())), color, thickness);
00181 cv::line(*image, cv::Point2d( CGAL::to_double(fc1->vertex(1)->point().x()), CGAL::to_double(fc1->vertex(1)->point().y())), cv::Point2d( CGAL::to_double(fc1->vertex(2)->point().x()), CGAL::to_double(fc1->vertex(2)->point().y())), color, thickness);
00182 cv::line(*image, cv::Point2d( CGAL::to_double(fc1->vertex(0)->point().x()), CGAL::to_double(fc1->vertex(0)->point().y())), cv::Point2d( CGAL::to_double(fc1->vertex(2)->point().x()), CGAL::to_double(fc1->vertex(2)->point().y())), color, thickness);
00183 }
00184
00185 return 1;
00186 }
00187
00188
00189 int class_projection_mesh::compute_face_weights(void)
00190 {
00191 for(PT::Finite_faces_iterator fi = mesh.finite_faces_begin(); fi != mesh.finite_faces_end(); ++fi)
00192 {
00193 if (!fi->is_in_domain())
00194 {
00195
00196 }
00197
00198 fi->weight = (fi->vertex(0)->info().weight + fi->vertex(1)->info().weight + fi->vertex(2)->info().weight)/3.0;
00199 }
00200
00201
00202 return 1;
00203 }
00204
00205 int class_projection_mesh::export_triangles_in_order(pcl::PointCloud<pcl::PointXYZRGB>* vertex_list, std::vector<float>* face_weights)
00206 {
00207
00208 vertex_list->points.erase(vertex_list->points.begin(), vertex_list->points.end());
00209 vertex_list->erase(vertex_list->begin(), vertex_list->end());
00210
00211 pcl::PointXYZRGB pt;
00212
00213 initialize_visited();
00214
00215 std::vector<PT::Face_handle> queue;
00216 PT::Finite_faces_iterator fi= mesh.finite_faces_begin();
00217 queue.push_back(fi);
00218
00219
00220 for (size_t i=0; i<queue.size(); i++)
00221 {
00222 if (queue[i]->visited==false)
00223 {
00224
00225 PT::Face_handle nfh;
00226
00227 nfh = queue[i]->neighbor(0);
00228 if (nfh->visited==false && !mesh.is_infinite(nfh))
00229 {
00230 queue.push_back(nfh);
00231 }
00232
00233 nfh = queue[i]->neighbor(1);
00234 if (nfh->visited==false && !mesh.is_infinite(nfh))
00235 {
00236 queue.push_back(nfh);
00237 }
00238
00239 nfh = queue[i]->neighbor(2);
00240 if (nfh->visited==false && !mesh.is_infinite(nfh))
00241 {
00242 queue.push_back(nfh);
00243 }
00244
00245 queue[i]->visited=true;
00246
00247 if (queue[i]->is_in_domain())
00248 {
00249 for (int u=0; u<3;u++)
00250 {
00251 pt.x = CGAL::to_double(queue[i]->vertex(u)->point().x());
00252 pt.y = CGAL::to_double(queue[i]->vertex(u)->point().y());
00253 pt.z = CGAL::to_double(queue[i]->vertex(u)->info().z);
00254 pt.rgb = queue[i]->vertex(u)->info().rgb;
00255 vertex_list->points.push_back(pt);
00256 }
00257 face_weights->push_back(queue[i]->weight);
00258 }
00259 queue.erase(queue.begin()+i);
00260 i=-1;
00261 }
00262 }
00263
00264 return 1;
00265 }
00266
00267
00268 int class_projection_mesh::export_triangles(pcl::PointCloud<pcl::PointXYZRGB>* vertex_list, std::vector<float>* face_weights)
00269 {
00270
00271 vertex_list->points.erase(vertex_list->points.begin(), vertex_list->points.end());
00272 vertex_list->erase(vertex_list->begin(), vertex_list->end());
00273
00274 pcl::PointXYZRGB pt;
00275
00276 for(PT::Finite_faces_iterator fi = mesh.finite_faces_begin(); fi != mesh.finite_faces_end(); ++fi)
00277 {
00278 if (!fi->is_in_domain())
00279 {
00280 continue;
00281 }
00282
00283 for (int u=0; u<3;u++)
00284 {
00285 pt.x = CGAL::to_double(fi->vertex(u)->point().x());
00286 pt.y = CGAL::to_double(fi->vertex(u)->point().y());
00287 pt.z = CGAL::to_double(fi->vertex(u)->info().z);
00288 pt.rgb = fi->vertex(u)->info().rgb;
00289 vertex_list->points.push_back(pt);
00290 }
00291
00292 face_weights->push_back(fi->weight);
00293 }
00294
00295 return 1;
00296 }
00297 #endif
00298