$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_MODEL_H 00038 #define COLLISION_CHECKING_BVH_MODEL_H 00039 00040 00041 #include "collision_checking/BVH_defs.h" 00042 #include "collision_checking/BV.h" 00043 #include "collision_checking/primitive.h" 00044 #include "collision_checking/vec_3f.h" 00045 #include "collision_checking/BVH_split_rule.h" 00046 #include "collision_checking/BV_fitter.h" 00047 #include <vector> 00048 #include <iostream> 00049 #include <string.h> 00050 00052 namespace collision_checking 00053 { 00054 00056 template<typename BV> 00057 struct BVNode 00058 { 00060 BV bv; 00061 00067 int first_child; 00068 00072 int first_primitive; 00073 00075 int num_primitives; 00076 00078 bool isLeaf() { return first_child < 0; } 00079 00081 int primitiveId() { return -(first_child + 1); } 00082 00084 int leftChild() { return first_child; } 00085 00087 int rightChild() { return first_child + 1; } 00088 00090 bool overlap(const BVNode& other) const 00091 { 00092 return bv.overlap(other.bv); 00093 } 00094 00095 BVH_REAL distance(const BVNode& other) const 00096 { 00097 return bv.distance(other.bv); 00098 } 00099 00100 }; 00101 00103 template<typename BV> 00104 class BVHModel 00105 { 00106 private: 00107 int num_tris_allocated; 00108 int num_vertices_allocated; 00109 int num_bvs_allocated; 00110 int num_vertex_updated; // for ccd vertex update 00111 unsigned int* primitive_indices; 00112 00113 public: 00115 Vec3f* vertices; 00116 00118 Triangle* tri_indices; 00119 00121 Vec3f* prev_vertices; 00122 00124 BVNode<BV>* bvs; 00125 00127 int num_tris; 00128 00130 int num_vertices; 00131 00133 int num_bvs; 00134 00136 BVHBuildState build_state; 00137 00139 BVSplitRule<BV> bv_splitter; 00140 00142 BVFitter<BV> bv_fitter; 00143 00145 BVHModelType getModelType() const 00146 { 00147 if(tri_indices && vertices) 00148 return BVH_MODEL_TRIANGLES; 00149 else if(vertices) 00150 return BVH_MODEL_POINTCLOUD; 00151 else 00152 return BVH_MODEL_UNKNOWN; 00153 } 00154 00155 BVHModel() 00156 { 00157 vertices = NULL; 00158 tri_indices = NULL; 00159 bvs = NULL; 00160 00161 num_tris = 0; 00162 num_tris_allocated = 0; 00163 num_vertices = 0; 00164 num_vertices_allocated = 0; 00165 num_bvs = 0; 00166 num_bvs_allocated = 0; 00167 00168 prev_vertices = NULL; 00169 00170 primitive_indices = NULL; 00171 00172 build_state = BVH_BUILD_STATE_EMPTY; 00173 } 00174 00175 00176 ~BVHModel() 00177 { 00178 delete [] vertices; 00179 delete [] tri_indices; 00180 delete [] bvs; 00181 00182 delete [] prev_vertices; 00183 00184 delete [] primitive_indices; 00185 } 00186 00188 int beginModel(int num_tris = 0, int num_vertices = 0); 00189 00191 int addVertex(const Vec3f& p); 00192 00194 int addTriangle(const Vec3f& p1, const Vec3f& p2, const Vec3f& p3); 00195 00197 int addSubModel(const std::vector<Vec3f>& ps, const std::vector<Triangle>& ts); 00198 00200 int addSubModel(const std::vector<Vec3f>& ps); 00201 00203 int endModel(); 00204 00205 00207 int beginReplaceModel(); 00208 00210 int replaceVertex(const Vec3f& p); 00211 00213 int replaceTriangle(const Vec3f& p1, const Vec3f& p2, const Vec3f& p3); 00214 00216 int replaceSubModel(const std::vector<Vec3f>& ps); 00217 00219 int endReplaceModel(bool refit = true, bool bottomup = true); 00220 00221 00225 int beginUpdateModel(); 00226 00228 int updateVertex(const Vec3f& p); 00229 00231 int updateTriangle(const Vec3f& p1, const Vec3f& p2, const Vec3f& p3); 00232 00234 int updateSubModel(const std::vector<Vec3f>& ps); 00235 00237 int endUpdateModel(bool refit = true, bool bottomup = true); 00238 00240 int memUsage(int msg) const; 00241 00242 private: 00243 00245 int buildTree(); 00246 00248 int refitTree(bool bottomup); 00249 00251 int refitTree_topdown(); 00252 00254 int refitTree_bottomup(); 00255 00257 int recursiveBuildTree(int bv_id, int first_primitive, int num_primitives); 00258 00260 int recursiveRefitTree_bottomup(int bv_id); 00261 00262 }; 00263 00264 } 00265 00266 #endif