$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_PQP_H 00038 #define COLLISION_CHECKING_PQP_H 00039 00040 #include "collision_checking/BVH_defs.h" 00041 #include "collision_checking/vec_3f.h" 00042 #include <iostream> 00043 #include <limits> 00044 #include <iostream> 00045 00047 namespace collision_checking 00048 { 00049 00051 class OBB 00052 { 00054 struct SimpleQuaternion 00055 { 00056 SimpleQuaternion(); 00057 00058 SimpleQuaternion(BVH_REAL a, BVH_REAL b, BVH_REAL c, BVH_REAL d); 00059 00061 void fromRotation(const Vec3f axis[3]); 00062 00064 void toRotation(Vec3f axis[3]) const; 00065 00067 BVH_REAL dot(const SimpleQuaternion& other) const; 00068 00070 SimpleQuaternion operator + (const SimpleQuaternion& other) const; 00071 00073 SimpleQuaternion operator - () const; 00074 00076 SimpleQuaternion operator * (BVH_REAL t) const; 00077 00078 private: 00079 BVH_REAL data[4]; 00080 }; 00081 00082 00083 public: 00085 Vec3f axis[3]; // R[i] is the ith column of the orientation matrix, or the axis of the OBB 00086 00088 Vec3f To; 00089 00091 Vec3f extent; 00092 00093 OBB() {} 00094 00096 bool overlap(const OBB& other) const; 00097 00101 bool overlap(const OBB& other, OBB& overlap_part) const 00102 { 00103 return overlap(other); 00104 } 00105 00107 inline bool contain(const Vec3f& p) const; 00108 00110 OBB& operator += (const Vec3f& p); 00111 00113 OBB& operator += (const OBB& other) 00114 { 00115 *this = *this + other; 00116 return *this; 00117 } 00118 00120 OBB operator + (const OBB& other) const; 00121 00123 inline BVH_REAL width() const 00124 { 00125 return 2 * extent[0]; 00126 } 00127 00129 inline BVH_REAL height() const 00130 { 00131 return 2 * extent[1]; 00132 } 00133 00135 inline BVH_REAL depth() const 00136 { 00137 return 2 * extent[2]; 00138 } 00139 00141 inline BVH_REAL volume() const 00142 { 00143 return width() * height() * depth(); 00144 } 00145 00147 inline BVH_REAL size() const 00148 { 00149 return extent.sqrLength(); 00150 } 00151 00153 inline Vec3f center() const 00154 { 00155 return To; 00156 } 00157 00161 BVH_REAL distance(const OBB& other) const 00162 { 00163 std::cerr << "OBB distance not implemented!" << std::endl; 00164 return 0.0; 00165 } 00166 00167 00168 private: 00169 00171 void computeVertices(Vec3f vertex[8]) const; 00172 00174 static void getCovariance(Vec3f* ps, int n, Vec3f M[3]); 00175 00177 static void Meigen(Vec3f a[3], BVH_REAL dout[3], Vec3f vout[3]); 00178 00180 static void getExtentAndCenter(Vec3f* ps, int n, Vec3f axis[3], Vec3f& center, Vec3f& extent); 00181 00183 static OBB merge_largedist(const OBB& b1, const OBB& b2); 00184 00186 static OBB merge_smalldist(const OBB& b1, const OBB& b2); 00187 00188 public: 00190 static bool obbDisjoint(const Vec3f B[3], const Vec3f& T, const Vec3f& a, const Vec3f& b); 00191 00192 }; 00193 00194 00195 bool overlap(const Vec3f R0[3], const Vec3f& T0, const OBB& b1, const OBB& b2); 00196 00197 } 00198 00199 #endif