$search
00001 /* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Copyright (c) 2011, Willow Garage, Inc. 00005 * All rights reserved. 00006 * 00007 * Redistribution and use in source and binary forms, with or without 00008 * modification, are permitted provided that the following conditions 00009 * are met: 00010 * 00011 * * Redistributions of source code must retain the above copyright 00012 * notice, this list of conditions and the following disclaimer. 00013 * * Redistributions in binary form must reproduce the above 00014 * copyright notice, this list of conditions and the following 00015 * disclaimer in the documentation and/or other materials provided 00016 * with the distribution. 00017 * * Neither the name of Willow Garage, Inc. nor the names of its 00018 * contributors may be used to endorse or promote products derived 00019 * from this software without specific prior written permission. 00020 * 00021 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00022 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00023 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00024 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00025 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00026 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00027 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00028 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00029 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00030 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00031 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00032 * POSSIBILITY OF SUCH DAMAGE. 00033 */ 00034 00037 #ifndef COLLISION_CHECKING_BVH_SPLIT_RULE_H 00038 #define COLLISION_CHECKING_BVH_SPLIT_RULE_H 00039 00040 00041 #include "collision_checking/BVH_defs.h" 00042 #include "collision_checking/primitive.h" 00043 #include "collision_checking/vec_3f.h" 00044 #include "collision_checking/obb.h" 00045 #include <ros/console.h> 00046 #include <vector> 00047 00049 namespace collision_checking 00050 { 00051 00052 enum SplitMethodType {SPLIT_METHOD_MEAN, SPLIT_METHOD_MEDIAN, SPLIT_METHOD_BV_CENTER}; 00053 00054 00056 template<typename BV> 00057 class BVSplitRule 00058 { 00059 public: 00060 00061 BVSplitRule() 00062 { 00063 split_method = SPLIT_METHOD_MEAN; 00064 } 00065 00066 void setSplitType(SplitMethodType method) 00067 { 00068 split_method = method; 00069 } 00070 00072 void set(Vec3f* vertices_, Triangle* tri_indices_, BVHModelType type_) 00073 { 00074 vertices = vertices_; 00075 tri_indices = tri_indices_; 00076 type = type_; 00077 } 00078 00080 void computeRule(const BV& bv, unsigned int* primitive_indices, int num_primitives) 00081 { 00082 switch(split_method) 00083 { 00084 case SPLIT_METHOD_MEAN: 00085 computeRule_mean(bv, primitive_indices, num_primitives); 00086 break; 00087 case SPLIT_METHOD_MEDIAN: 00088 computeRule_median(bv, primitive_indices, num_primitives); 00089 break; 00090 case SPLIT_METHOD_BV_CENTER: 00091 computeRule_bvcenter(bv, primitive_indices, num_primitives); 00092 break; 00093 default: 00094 ROS_WARN_STREAM("Split method not supported"); 00095 } 00096 } 00097 00099 bool operator()(const Vec3f& q) const 00100 { 00101 return q[split_axis] > split_value; 00102 } 00103 00105 void clear() 00106 { 00107 vertices = NULL; 00108 tri_indices = NULL; 00109 type = BVH_MODEL_UNKNOWN; 00110 } 00111 00112 private: 00113 00115 int split_axis; 00116 00118 BVH_REAL split_value; 00119 00120 Vec3f* vertices; 00121 Triangle* tri_indices; 00122 BVHModelType type; 00123 SplitMethodType split_method; 00124 00126 void computeRule_bvcenter(const BV& bv, unsigned int* primitive_indices, int num_primitives) 00127 { 00128 Vec3f center = bv.center(); 00129 int axis = 2; 00130 00131 if(bv.width() >= bv.height() && bv.width() >= bv.depth()) 00132 axis = 0; 00133 else if(bv.height() >= bv.width() && bv.height() >= bv.depth()) 00134 axis = 1; 00135 00136 split_axis = axis; 00137 split_value = center[axis]; 00138 } 00139 00141 void computeRule_mean(const BV& bv, unsigned int* primitive_indices, int num_primitives) 00142 { 00143 int axis = 2; 00144 00145 if(bv.width() >= bv.height() && bv.width() >= bv.depth()) 00146 axis = 0; 00147 else if(bv.height() >= bv.width() && bv.height() >= bv.depth()) 00148 axis = 1; 00149 00150 split_axis = axis; 00151 BVH_REAL sum = 0; 00152 00153 if(type == BVH_MODEL_TRIANGLES) 00154 { 00155 for(int i = 0; i < num_primitives; ++i) 00156 { 00157 const Triangle& t = tri_indices[primitive_indices[i]]; 00158 sum += ((vertices[t[0]][split_axis] + vertices[t[1]][split_axis] + vertices[t[2]][split_axis]) / 3); 00159 } 00160 } 00161 else if(type == BVH_MODEL_POINTCLOUD) 00162 { 00163 for(int i = 0; i < num_primitives; ++i) 00164 { 00165 sum += vertices[primitive_indices[i]][split_axis]; 00166 } 00167 } 00168 00169 split_value = sum / num_primitives; 00170 } 00171 00173 void computeRule_median(const BV& bv, unsigned int* primitive_indices, int num_primitives) 00174 { 00175 int axis = 2; 00176 00177 if(bv.width() >= bv.height() && bv.width() >= bv.depth()) 00178 axis = 0; 00179 else if(bv.height() >= bv.width() && bv.height() >= bv.depth()) 00180 axis = 1; 00181 00182 split_axis = axis; 00183 std::vector<BVH_REAL> proj(num_primitives); 00184 00185 if(type == BVH_MODEL_TRIANGLES) 00186 { 00187 for(int i = 0; i < num_primitives; ++i) 00188 { 00189 const Triangle& t = tri_indices[primitive_indices[i]]; 00190 proj[i] = (vertices[t[0]][split_axis] + vertices[t[1]][split_axis] + vertices[t[2]][split_axis]) / 3; 00191 } 00192 } 00193 else if(type == BVH_MODEL_POINTCLOUD) 00194 { 00195 for(int i = 0; i < num_primitives; ++i) 00196 proj[i] = vertices[primitive_indices[i]][split_axis]; 00197 } 00198 00199 std::sort(proj.begin(), proj.end()); 00200 00201 if(num_primitives % 2 == 1) 00202 { 00203 split_value = proj[(num_primitives - 1) / 2]; 00204 } 00205 else 00206 { 00207 split_value = (proj[num_primitives / 2] + proj[num_primitives / 2 - 1]) / 2; 00208 } 00209 } 00210 }; 00211 00212 00213 00215 template<> 00216 class BVSplitRule<OBB> 00217 { 00218 public: 00219 00220 BVSplitRule() 00221 { 00222 split_method = SPLIT_METHOD_MEAN; 00223 } 00224 00225 void setSplitType(SplitMethodType method) 00226 { 00227 split_method = method; 00228 } 00229 00231 void set(Vec3f* vertices_, Triangle* tri_indices_, BVHModelType type_) 00232 { 00233 vertices = vertices_; 00234 tri_indices = tri_indices_; 00235 type = type_; 00236 } 00237 00239 void computeRule(const OBB& bv, unsigned int* primitive_indices, int num_primitives) 00240 { 00241 Vec3f center = bv.center(); 00242 split_vector = bv.axis[0]; 00243 split_value = center[0]; 00244 } 00245 00247 bool operator()(const Vec3f& q) const 00248 { 00249 return split_vector.dot(Vec3f(q[0], q[1], q[2])) > split_value; 00250 } 00251 00253 void clear() 00254 { 00255 vertices = NULL; 00256 tri_indices = NULL; 00257 type = BVH_MODEL_UNKNOWN; 00258 } 00259 00260 private: 00261 00263 void computeRule_bvcenter(const OBB& bv, unsigned int* primitive_indices, int num_primitives); 00264 00266 void computeRule_mean(const OBB& bv, unsigned int* primitive_indices, int num_primitives); 00267 00269 void computeRule_median(const OBB& bv, unsigned int* primitive_indices, int num_primitives); 00270 00271 BVH_REAL split_value; 00272 Vec3f split_vector; 00273 00274 Vec3f* vertices; 00275 Triangle* tri_indices; 00276 BVHModelType type; 00277 SplitMethodType split_method; 00278 }; 00279 00280 } 00281 00282 #endif