00001 /************************************************************************************************** 00002 Software License Agreement (BSD License) 00003 00004 Copyright (c) 2011-2013, LAR toolkit developers - University of Aveiro - http://lars.mec.ua.pt 00005 All rights reserved. 00006 00007 Redistribution and use in source and binary forms, with or without modification, are permitted 00008 provided that the following conditions are met: 00009 00010 *Redistributions of source code must retain the above copyright notice, this list of 00011 conditions and the following disclaimer. 00012 *Redistributions in binary form must reproduce the above copyright notice, this list of 00013 conditions and the following disclaimer in the documentation and/or other materials provided 00014 with the distribution. 00015 *Neither the name of the University of Aveiro nor the names of its contributors may be used to 00016 endorse or promote products derived from this software without specific prior written permission. 00017 00018 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR 00019 IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND 00020 FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR 00021 CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL 00022 DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, 00023 DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER 00024 IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT 00025 OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 00026 ***************************************************************************************************/ 00033 #ifndef _TEXTURED_TRIANGLE_CPP_ 00034 #define _TEXTURED_TRIANGLE_CPP_ 00035 00036 #include "textured_triangle.h" 00037 00038 00039 //TEXTURED VERTEX methods 00040 00041 class_textured_vertex::class_textured_vertex(float vx, float vy, float vz, float vrgb) 00042 { 00043 x=vx; y=vy; z=vz; rgb=vrgb; 00044 } 00045 00046 //TEXTURED TRIANGLE methods 00047 class_textured_triangle::class_textured_triangle(class_textured_vertex v0, class_textured_vertex v1,class_textured_vertex v2, float w, int p) 00048 { 00049 v[0].x = v0.x; v[0].y = v0.y; v[0].z = v0.z; v[0].rgb = v0.rgb; 00050 v[1].x = v1.x; v[1].y = v1.y; v[1].z = v1.z; v[1].rgb = v1.rgb; 00051 v[2].x = v2.x; v[2].y = v2.y; v[2].z = v2.z; v[2].rgb = v2.rgb; 00052 weight = w; 00053 provenience = p; 00054 } 00055 00056 00057 bool class_textured_triangle::overlaps(class_textured_triangle* t) 00058 { 00059 00060 CGAL::Triangle_2<K1> t1(CGAL::Point_2<K1>(v[0].x, v[0].y), CGAL::Point_2<K1>(v[1].x, v[1].y), CGAL::Point_2<K1>(v[2].x, v[2].y)); 00061 CGAL::Triangle_2<K1> t2(CGAL::Point_2<K1>(t->v[0].x, t->v[0].y), CGAL::Point_2<K1>(t->v[1].x, t->v[1].y), CGAL::Point_2<K1>(t->v[2].x, t->v[2].y)); 00062 00063 CGAL::Object result = CGAL::intersection(t1, t2); 00064 if (const CGAL::Triangle_2<K1> *itriangle = CGAL::object_cast<CGAL::Triangle_2<K1> >(&result)) 00065 { 00066 //if intersection is a triangle then the triangles overlap 00067 //ROS_WARN("intersection was a triangle"); 00068 return 1; 00069 } 00070 else if (const std::vector<CGAL::Point_2<K1> > *iptvector = CGAL::object_cast<std::vector<CGAL::Point_2<K1> > >(&result)) 00071 { 00072 //if intersection is vector of points, i.e., a polygon, then the triangles overlap 00073 //ROS_WARN("intersection was a pt vector"); 00074 return 1; 00075 } 00076 else 00077 { 00078 //if intersection is any of the other cases, i.e., segment or point, then there is only overlap in the boundaries 00079 return 0; 00080 } 00081 //} 00082 00083 //Segment_2 00084 //Triangle_2 00085 //std::vector<Point_2> 00086 //CDT2 triang; 00087 //for (int i=0; i<3; i++) 00088 //triang.insert(CDT2::Point(v[i].x, v[i].y)); 00089 00090 //CDT2::Locate_type lt[3]; 00091 //int li; 00092 //CDT2::Face_handle fh = triang.locate(CDT2::Point(t->v[0].x, t->v[0].y), lt[0], li); //locate the point where we want to insert a new vertex 00093 00094 00095 //fh = triang.locate(CDT2::Point(t->v[1].x, t->v[1].y), lt[1], li); //locate the point where we want to insert a new vertex 00096 //fh = triang.locate(CDT2::Point(t->v[2].x, t->v[2].y), lt[2], li); //locate the point where we want to insert a new vertex 00097 00098 00099 //if (lt[0]) 00100 00101 //First see if any of the t vertices is inside the class triangle 00102 //for (int i=0; i<3; i++) 00103 //{ 00106 //if (point_inside_triangle(v[0].x, v[0].y, v[1].x, v[1].y,v[2].x, v[2].y, t->v[i].x, t->v[i].y)) 00107 //return true; 00108 //} 00109 00111 //for (int i=0; i<3; i++) 00112 //{ 00113 //if (point_inside_triangle(t->v[0].x, t->v[0].y, t->v[1].x, t->v[1].y,t->v[2].x, t->v[2].y, v[i].x, v[i].y)) 00114 //return true; 00115 //} 00116 00117 //double X,Y; 00118 //if (lineSegmentIntersection( t->v[0].x, t->v[0].y, t->v[1].x, t->v[1].y, 00119 //v[0].x, v[0].y, v[1].x, v[1].y, 00120 //&X, &Y)==DO_INTERSECT) 00121 //return true; 00122 00123 //if (lineSegmentIntersection( t->v[1].x, t->v[1].y, t->v[2].x, t->v[2].y, 00124 //v[0].x, v[0].y, v[1].x, v[1].y, 00125 //&X, &Y)==DO_INTERSECT) 00126 //return true; 00127 00128 //if (lineSegmentIntersection( t->v[2].x, t->v[2].y, t->v[0].x, t->v[0].y, 00129 //v[0].x, v[0].y, v[1].x, v[1].y, 00130 //&X, &Y)==DO_INTERSECT) 00131 //return true; 00132 00133 //if (lineSegmentIntersection( t->v[0].x, t->v[0].y, t->v[1].x, t->v[1].y, 00134 //v[2].x, v[2].y, v[0].x, v[0].y, 00135 //&X, &Y)==DO_INTERSECT) 00136 //return true; 00137 00138 //if (lineSegmentIntersection( t->v[1].x, t->v[1].y, t->v[2].x, t->v[2].y, 00139 //v[2].x, v[2].y, v[0].x, v[0].y, 00140 //&X, &Y)==DO_INTERSECT) 00141 //return true; 00142 00143 //if (lineSegmentIntersection( t->v[2].x, t->v[2].y, t->v[0].x, t->v[0].y, 00144 //v[2].x, v[2].y, v[0].x, v[0].y, 00145 //&X, &Y)==DO_INTERSECT) 00146 //return true; 00147 00148 //if (lineSegmentIntersection( t->v[0].x, t->v[0].y, t->v[1].x, t->v[1].y, 00149 //v[1].x, v[1].y, v[2].x, v[2].y, 00150 //&X, &Y)==DO_INTERSECT) 00151 //return true; 00152 00153 //if (lineSegmentIntersection( t->v[1].x, t->v[1].y, t->v[2].x, t->v[2].y, 00154 //v[1].x, v[1].y, v[2].x, v[2].y, 00155 //&X, &Y)==DO_INTERSECT) 00156 //return true; 00157 00158 //if (lineSegmentIntersection( t->v[2].x, t->v[2].y, t->v[0].x, t->v[0].y, 00159 //v[1].x, v[1].y, v[2].x, v[2].y, 00160 //&X, &Y)==DO_INTERSECT) 00161 //return true; 00162 00163 //return false; 00164 } 00165 00166 00167 //TEXTURE SET methods 00168 00169 int class_texture_set::add_triangle(class_textured_vertex v0, class_textured_vertex v1, class_textured_vertex v2, int provenience, float weight, t_add_method method) 00170 { 00171 00172 if (method==FORCE) 00173 { 00174 boost::shared_ptr<class_textured_triangle> t(new class_textured_triangle(v0,v1,v2, weight, provenience)); 00175 set.push_back(t); 00176 } 00177 else if (method==CHECK) 00178 { 00179 boost::shared_ptr<class_textured_triangle> t(new class_textured_triangle(v0,v1,v2, weight, provenience)); 00180 00181 std::priority_queue<size_t> index_to_remove; //a list of triangles to remove on account of the insertion of the new one 00182 00183 //ROS_INFO("ADDING new triangle, list size %d", (int)set.size()); 00184 00185 //check i the triangle to be inserted intersects any of the ones on the list 00186 for (size_t i=0; i<set.size(); ++i) 00187 { 00188 if (t->provenience != set[i]->provenience) 00189 if (set[i]->overlaps(&(*t))) 00190 { 00191 00192 //ROS_DEBUG("new triangle overlaps with %i from list",(int)i); 00193 //printf("new:\n"); 00194 //t.print_info(); 00195 //printf("triangle %d:\n",(int)i); 00196 //it->print_info(); 00197 //if they overlap must compare weight 00198 if (t->weight > set[i]->weight) //if new triangle has larger weight 00199 { 00200 //ROS_INFO("LARGER: new triangle W (%f); old triangle %d (W=%f)", t->weight,(int)i, set[i]->weight); 00201 index_to_remove.push(i); 00202 } 00203 else //if new triangle has less weight, dont add it and return 00204 { 00205 //ROS_INFO("SMALLER: new triangle W (%f); old triangle %d (W=%f)", t->weight,(int)i, set[i]->weight); 00206 t.reset(); 00207 return DID_NOT_ADD_TRIANGLE; 00208 } 00209 } 00210 } 00211 00212 //if the cycle ended and reached here, no return occurred which means the new triangle must be inserted and the ones in index_to_remove must be deleted 00213 00214 //ROS_INFO("must remove %d triangles before adding new",(int) key_to_remove.size()); 00215 //first lets delete. Must be carefull not to loose the indexes propper position, to delete from the end to the begining 00216 00217 //ROS_INFO("List size before removing=%d", (int)set.size()); 00218 while (!index_to_remove.empty()) 00219 { 00220 ROS_INFO("Removing triangle %d", (int)index_to_remove.top()); 00221 set.erase(set.begin() + index_to_remove.top()); 00222 index_to_remove.pop(); 00223 } 00224 00225 00226 //for (size_t i=0; i<index_to_remove.size(); ++i) 00227 00228 //ROS_INFO("AAA List size after removing=%d", (int)set.size()); 00229 //finnaly we add the new triangle 00230 set.push_back(t); 00231 //ROS_INFO("AAA List size after adding=%d", (int)set.size()); 00232 return ADDED_TRIANGLE; 00233 } 00234 00235 return -1; 00236 } 00237 00238 int class_texture_set::set_transform(tf::Transform* st) 00239 { 00240 transform.setRotation(st->getRotation()); 00241 transform.setOrigin(st->getOrigin()); 00242 return 1; 00243 } 00244 00245 int class_texture_set::export_to_pc(void) 00246 { 00247 pc.points.erase(pc.points.begin(), pc.points.end()); 00248 pc_proveniences.erase(pc_proveniences.begin(), pc_proveniences.end()); 00249 00250 for(size_t k=0; k<set.size(); k++) 00251 //std::map<size_t, boost::shared_ptr<class_textured_triangle> >::iterator it; 00252 //for (it=set.begin(); it!=set.end();++it) 00253 { 00254 00255 //printf("INSIDE TRI%d\n v0 x=%f y=%f z=%f\n v1 x=%f y=%f z=%f\n v2 x=%f y=%f z=%f\n",(int)k, set[k].v[0].x, set[k].v[0].y,set[k].v[0].z,set[k].v[1].x,set[k].v[1].y,set[k].v[1].z,set[k].v[2].x,set[k].v[2].y,set[k].v[2].z); 00256 for (int u=0; u<3;u++) 00257 { 00258 pcl::PointCloud<pcl::PointXYZ> pc_local; 00259 pcl::PointXYZ pt; 00260 00261 pt.x = set[k]->v[u].x; 00262 pt.y = set[k]->v[u].y; 00263 pt.z = set[k]->v[u].z; 00264 pc_local.points.push_back(pt); 00265 00266 pcl::PointCloud<pcl::PointXYZ> pc_global; 00267 pcl_ros::transformPointCloud(pc_local, pc_global, transform.inverse()); 00268 pcl::PointXYZRGB ptcolor; 00269 ptcolor.x = pc_global.points[0].x; 00270 ptcolor.y = pc_global.points[0].y; 00271 ptcolor.z = pc_global.points[0].z; 00272 ptcolor.rgb = set[k]->v[u].rgb; 00273 00274 pc.points.push_back(ptcolor); 00275 pc_proveniences.push_back(set[k]->provenience); 00276 00277 pc.height = 1; 00278 pc.width = pc.points.size(); 00279 pc.is_dense = 0; 00280 00281 } 00282 } 00283 00284 ROS_INFO("Exported triangle set %d triangles from a list with set.size()=%d", (int)pc.points.size(), (int)set.size()); 00285 00286 00287 return 1; 00288 00289 00290 } 00291 00292 #endif 00293