$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_KDOP_H 00038 #define COLLISION_CHECKING_KDOP_H 00039 00040 #include <cstdlib> 00041 #include <limits> 00042 #include <iostream> 00043 #include "collision_checking/BVH_defs.h" 00044 #include "collision_checking/vec_3f.h" 00045 00047 namespace collision_checking 00048 { 00049 00051 inline void minmax(BVH_REAL a, BVH_REAL b, BVH_REAL& minv, BVH_REAL& maxv) 00052 { 00053 if(a > b) 00054 { 00055 minv = b; 00056 maxv = a; 00057 } 00058 else 00059 { 00060 minv = a; 00061 maxv = b; 00062 } 00063 } 00065 inline void minmax(BVH_REAL p, BVH_REAL& minv, BVH_REAL& maxv) 00066 { 00067 if(p > maxv) maxv = p; 00068 if(p < minv) minv = p; 00069 } 00070 00071 00073 template<size_t N> 00074 void getDistances(const Vec3f& p, BVH_REAL d[]) {} 00075 00077 template<> 00078 inline void getDistances<5>(const Vec3f& p, BVH_REAL d[]) 00079 { 00080 d[0] = p[0] + p[1]; 00081 d[1] = p[0] + p[2]; 00082 d[2] = p[1] + p[2]; 00083 d[3] = p[0] - p[1]; 00084 d[4] = p[0] - p[2]; 00085 } 00086 00087 template<> 00088 inline void getDistances<6>(const Vec3f& p, BVH_REAL d[]) 00089 { 00090 d[0] = p[0] + p[1]; 00091 d[1] = p[0] + p[2]; 00092 d[2] = p[1] + p[2]; 00093 d[3] = p[0] - p[1]; 00094 d[4] = p[0] - p[2]; 00095 d[5] = p[1] - p[2]; 00096 } 00097 00098 template<> 00099 inline void getDistances<9>(const Vec3f& p, BVH_REAL d[]) 00100 { 00101 d[0] = p[0] + p[1]; 00102 d[1] = p[0] + p[2]; 00103 d[2] = p[1] + p[2]; 00104 d[3] = p[0] - p[1]; 00105 d[4] = p[0] - p[2]; 00106 d[5] = p[1] - p[2]; 00107 d[6] = p[0] + p[1] - p[2]; 00108 d[7] = p[0] + p[2] - p[1]; 00109 d[8] = p[1] + p[2] - p[0]; 00110 } 00111 00112 00126 template<size_t N> 00127 class KDOP 00128 { 00129 public: 00130 KDOP() 00131 { 00132 BVH_REAL real_max = std::numeric_limits<BVH_REAL>::max(); 00133 for(size_t i = 0; i < N / 2; ++i) 00134 { 00135 dist_[i] = real_max; 00136 dist_[i + N / 2] = -real_max; 00137 } 00138 } 00139 00140 00141 KDOP(const Vec3f& v) 00142 { 00143 for(size_t i = 0; i < 3; ++i) 00144 { 00145 dist_[i] = dist_[N / 2 + i] = v[i]; 00146 } 00147 00148 BVH_REAL d[(N - 6) / 2]; 00149 getDistances<(N - 6) / 2>(v, d); 00150 for(size_t i = 0; i < (N - 6) / 2; ++i) 00151 { 00152 dist_[3 + i] = dist_[3 + i + N / 2] = d[i]; 00153 } 00154 } 00155 00156 KDOP(const Vec3f& a, const Vec3f& b) 00157 { 00158 for(size_t i = 0; i < 3; ++i) 00159 { 00160 minmax(a[i], b[i], dist_[i], dist_[i + N / 2]); 00161 } 00162 00163 BVH_REAL ad[(N - 6) / 2], bd[(N - 6) / 2]; 00164 getDistances<(N - 6) / 2>(a, ad); 00165 getDistances<(N - 6) / 2>(b, bd); 00166 for(size_t i = 0; i < (N - 6) / 2; ++i) 00167 { 00168 minmax(ad[i], bd[i], dist_[3 + i], dist_[3 + i + N / 2]); 00169 } 00170 } 00171 00173 inline bool overlap(const KDOP<N>& other) const 00174 { 00175 for(size_t i = 0; i < N / 2; ++i) 00176 { 00177 if(dist_[i] > other.dist_[i + N / 2]) return false; 00178 if(dist_[i + N / 2] < other.dist_[i]) return false; 00179 } 00180 00181 return true; 00182 } 00183 00185 inline bool inside(const Vec3f& p) const 00186 { 00187 for(size_t i = 0; i < 3; ++i) 00188 { 00189 if(p[i] < dist_[i] || p[i] > dist_[i + N / 2]) 00190 return false; 00191 } 00192 00193 BVH_REAL d[(N - 6) / 2]; 00194 getDistances(p, d); 00195 for(size_t i = 0; i < (N - 6) / 2; ++i) 00196 { 00197 if(d[i] < dist_[3 + i] || d[i] > dist_[i + 3 + N / 2]) 00198 return false; 00199 } 00200 00201 return true; 00202 } 00203 00205 inline KDOP<N>& operator += (const Vec3f& p) 00206 { 00207 for(size_t i = 0; i < 3; ++i) 00208 { 00209 minmax(p[i], dist_[i], dist_[N / 2 + i]); 00210 } 00211 00212 BVH_REAL pd[(N - 6) / 2]; 00213 getDistances<(N - 6) / 2>(p, pd); 00214 for(size_t i = 0; i < (N - 6) / 2; ++i) 00215 { 00216 minmax(pd[i], dist_[3 + i], dist_[3 + N / 2 + i]); 00217 } 00218 00219 return *this; 00220 } 00221 00223 inline KDOP<N>& operator += (const KDOP<N>& other) 00224 { 00225 for(size_t i = 0; i < N / 2; ++i) 00226 { 00227 dist_[i] = std::min(other.dist_[i], dist_[i]); 00228 dist_[i + N / 2] = std::max(other.dist_[i + N / 2], dist_[i + N / 2]); 00229 } 00230 return *this; 00231 } 00232 00234 inline KDOP<N> operator + (const KDOP<N>& other) const 00235 { 00236 KDOP<N> res(*this); 00237 return res += other; 00238 } 00239 00241 inline BVH_REAL width() const 00242 { 00243 return dist_[N / 2] - dist_[0]; 00244 } 00245 00247 inline BVH_REAL height() const 00248 { 00249 return dist_[N / 2 + 1] - dist_[1]; 00250 } 00251 00253 inline BVH_REAL depth() const 00254 { 00255 return dist_[N / 2 + 2] - dist_[2]; 00256 } 00257 00259 inline BVH_REAL volume() const 00260 { 00261 return width() * height() * depth(); 00262 } 00263 00264 inline BVH_REAL size() const 00265 { 00266 return width() * width() + height() * height() + depth() * depth(); 00267 } 00268 00270 inline Vec3f center() const 00271 { 00272 return Vec3f(dist_[0] + dist_[N / 2], dist_[1] + dist_[N / 2 + 1], dist_[2] + dist_[N / 2 + 2]) * 0.5; 00273 } 00274 00278 BVH_REAL distance(const KDOP<N>& other) const 00279 { 00280 std::cerr << "KDOP distance not implemented!" << std::endl; 00281 return 0.0; 00282 } 00283 00284 private: 00286 BVH_REAL dist_[N]; 00287 00288 00289 }; 00290 00291 } 00292 00293 #endif