$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 00038 #include "collision_checking/collision.h" 00039 00040 namespace collision_checking 00041 { 00042 00043 int collide(const BVHModel<OBB>& model1, const Vec3f R1[3], const Vec3f& T1, 00044 const BVHModel<OBB>& model2, const Vec3f R2[3], const Vec3f& T2, BVH_CollideResult* res, BVHFrontList* front_list) 00045 { 00046 if(model1.build_state != BVH_BUILD_STATE_PROCESSED && model1.build_state != BVH_BUILD_STATE_UPDATED) 00047 { 00048 std::cerr << "BVH Error: Must finish BVH model construction before call collide()!" << std::endl; 00049 return BVH_ERR_BUILD_OUT_OF_SEQUENCE; 00050 } 00051 00052 if(model2.build_state != BVH_BUILD_STATE_PROCESSED && model2.build_state != BVH_BUILD_STATE_UPDATED) 00053 { 00054 std::cerr << "BVH Error: Must finish BVH model construction before call collide()!" << std::endl; 00055 return BVH_ERR_BUILD_OUT_OF_SEQUENCE; 00056 } 00057 00058 // currently only support the mesh-mesh collision 00059 if(model1.getModelType() != BVH_MODEL_TRIANGLES || model2.getModelType()!= BVH_MODEL_TRIANGLES) 00060 { 00061 std::cerr << "BVH Error: Collision only supported between two triangle models." << std::endl; 00062 return BVH_ERR_UNSUPPORTED_FUNCTION; 00063 } 00064 00065 00066 res->resetRecord(); 00067 00068 // compute the transform from 1 to 2 00069 Vec3f R1_col[3]; 00070 R1_col[0] = Vec3f(R1[0][0], R1[1][0], R1[2][0]); 00071 R1_col[1] = Vec3f(R1[0][1], R1[1][1], R1[2][1]); 00072 R1_col[2] = Vec3f(R1[0][2], R1[1][2], R1[2][2]); 00073 00074 Vec3f R2_col[3]; 00075 R2_col[0] = Vec3f(R2[0][0], R2[1][0], R2[2][0]); 00076 R2_col[1] = Vec3f(R2[0][1], R2[1][1], R2[2][1]); 00077 R2_col[2] = Vec3f(R2[0][2], R2[1][2], R2[2][2]); 00078 00079 Vec3f R[3]; 00080 R[0] = Vec3f(R1_col[0].dot(R2_col[0]), R1_col[0].dot(R2_col[1]), R1_col[0].dot(R2_col[2])); 00081 R[1] = Vec3f(R1_col[1].dot(R2_col[0]), R1_col[1].dot(R2_col[1]), R1_col[1].dot(R2_col[2])); 00082 R[2] = Vec3f(R1_col[2].dot(R2_col[0]), R1_col[2].dot(R2_col[1]), R1_col[2].dot(R2_col[2])); 00083 00084 Vec3f Ttemp = T2 - T1; 00085 Vec3f T(R1_col[0].dot(Ttemp), R1_col[1].dot(Ttemp), R1_col[2].dot(Ttemp)); 00086 00087 if(front_list && front_list->size() > 0) 00088 propagateBVHFrontList(model1.bvs, model2.bvs, R, T, model1.vertices, model2.vertices, model1.tri_indices, model2.tri_indices, res, front_list); 00089 else 00090 collideRecurse(model1.bvs, model2.bvs, R, T, 0, 0, model1.vertices, model2.vertices, model1.tri_indices, model2.tri_indices, res, front_list); 00091 00092 00093 // update the contact position and normal 00094 // contact R1 * c + T1 00095 // normal R1^{-T} * n = R1 * n 00096 for(int i = 0; i < res->numPairs(); ++i) 00097 { 00098 BVHCollisionPair* pairs = res->collidePairs(); 00099 Vec3f normal = pairs[i].normal; 00100 pairs[i].normal = Vec3f(R1[0].dot(normal), R1[1].dot(normal), R1[2].dot(normal)); 00101 Vec3f pos = pairs[i].contact_point; 00102 pairs[i].contact_point = Vec3f(R1[0].dot(pos), R1[1].dot(pos), R1[2].dot(pos)) + T1; 00103 } 00104 00105 return BVH_OK; 00106 } 00107 00108 00109 int collide(const BVHModel<RSS>& model1, const Vec3f R1[3], const Vec3f& T1, 00110 const BVHModel<RSS>& model2, const Vec3f R2[3], const Vec3f& T2, BVH_CollideResult* res, BVHFrontList* front_list) 00111 { 00112 if(model1.build_state != BVH_BUILD_STATE_PROCESSED && model1.build_state != BVH_BUILD_STATE_UPDATED) 00113 { 00114 std::cerr << "BVH Error: Must finish BVH model construction before call collide()!" << std::endl; 00115 return BVH_ERR_BUILD_OUT_OF_SEQUENCE; 00116 } 00117 00118 if(model2.build_state != BVH_BUILD_STATE_PROCESSED && model2.build_state != BVH_BUILD_STATE_UPDATED) 00119 { 00120 std::cerr << "BVH Error: Must finish BVH model construction before call collide()!" << std::endl; 00121 return BVH_ERR_BUILD_OUT_OF_SEQUENCE; 00122 } 00123 00124 // currently only support the mesh-mesh collision 00125 if(model1.getModelType() != BVH_MODEL_TRIANGLES || model2.getModelType()!= BVH_MODEL_TRIANGLES) 00126 { 00127 std::cerr << "BVH Error: Collision only supported between two triangle models." << std::endl; 00128 return BVH_ERR_UNSUPPORTED_FUNCTION; 00129 } 00130 00131 00132 res->resetRecord(); 00133 00134 // compute the transform from 1 to 2 00135 Vec3f R1_col[3]; 00136 R1_col[0] = Vec3f(R1[0][0], R1[1][0], R1[2][0]); 00137 R1_col[1] = Vec3f(R1[0][1], R1[1][1], R1[2][1]); 00138 R1_col[2] = Vec3f(R1[0][2], R1[1][2], R1[2][2]); 00139 00140 Vec3f R2_col[3]; 00141 R2_col[0] = Vec3f(R2[0][0], R2[1][0], R2[2][0]); 00142 R2_col[1] = Vec3f(R2[0][1], R2[1][1], R2[2][1]); 00143 R2_col[2] = Vec3f(R2[0][2], R2[1][2], R2[2][2]); 00144 00145 Vec3f R[3]; 00146 R[0] = Vec3f(R1_col[0].dot(R2_col[0]), R1_col[0].dot(R2_col[1]), R1_col[0].dot(R2_col[2])); 00147 R[1] = Vec3f(R1_col[1].dot(R2_col[0]), R1_col[1].dot(R2_col[1]), R1_col[1].dot(R2_col[2])); 00148 R[2] = Vec3f(R1_col[2].dot(R2_col[0]), R1_col[2].dot(R2_col[1]), R1_col[2].dot(R2_col[2])); 00149 00150 Vec3f Ttemp = T2 - T1; 00151 Vec3f T(R1_col[0].dot(Ttemp), R1_col[1].dot(Ttemp), R1_col[2].dot(Ttemp)); 00152 00153 if(front_list && front_list->size() > 0) 00154 propagateBVHFrontList(model1.bvs, model2.bvs, R, T, model1.vertices, model2.vertices, model1.tri_indices, model2.tri_indices, res, front_list); 00155 else 00156 collideRecurse(model1.bvs, model2.bvs, R, T, 0, 0, model1.vertices, model2.vertices, model1.tri_indices, model2.tri_indices, res, front_list); 00157 00158 00159 // update the contact position and normal 00160 // contact R1 * c + T1 00161 // normal R1^{-T} * n = R1 * n 00162 for(int i = 0; i < res->numPairs(); ++i) 00163 { 00164 BVHCollisionPair* pairs = res->collidePairs(); 00165 Vec3f normal = pairs[i].normal; 00166 pairs[i].normal = Vec3f(R1[0].dot(normal), R1[1].dot(normal), R1[2].dot(normal)); 00167 Vec3f pos = pairs[i].contact_point; 00168 pairs[i].contact_point = Vec3f(R1[0].dot(pos), R1[1].dot(pos), R1[2].dot(pos)) + T1; 00169 } 00170 00171 return BVH_OK; 00172 } 00173 00174 00175 } 00176