$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_AABB_H 00038 #define COLLISION_CHECKING_AABB_H 00039 00040 00041 #include "collision_checking/BVH_defs.h" 00042 #include "collision_checking/vec_3f.h" 00043 #include <limits> 00044 #include <iostream> 00045 00047 namespace collision_checking 00048 { 00049 00051 class AABB 00052 { 00053 public: 00055 Vec3f min_; 00057 Vec3f max_; 00058 00059 AABB() 00060 { 00061 BVH_REAL real_max = std::numeric_limits<BVH_REAL>::max(); 00062 min_ = Vec3f(real_max, real_max, real_max); 00063 max_ = Vec3f(-real_max, -real_max, -real_max); 00064 } 00065 00066 AABB(const Vec3f& v) : min_(v), max_(v) 00067 { 00068 } 00069 00070 AABB(const Vec3f& a, const Vec3f&b) 00071 { 00072 min_ = min(a, b); 00073 max_ = max(a, b); 00074 } 00075 00077 inline bool overlap(const AABB& other) const 00078 { 00079 if(min_[0] > other.max_[0]) return false; 00080 if(min_[1] > other.max_[1]) return false; 00081 if(min_[2] > other.max_[2]) return false; 00082 00083 if(max_[0] < other.min_[0]) return false; 00084 if(max_[1] < other.min_[1]) return false; 00085 if(max_[2] < other.min_[2]) return false; 00086 00087 return true; 00088 } 00089 00091 inline bool axisOverlap(const AABB& other, int axis_id) const 00092 { 00093 if(min_[axis_id] > other.max_[axis_id]) return false; 00094 00095 if(max_[axis_id] < other.min_[axis_id]) return false; 00096 00097 return true; 00098 } 00099 00101 inline bool overlap(const AABB& other, AABB& overlap_part) const 00102 { 00103 if(!overlap(other)) 00104 return false; 00105 00106 overlap_part.min_ = max(min_, other.min_); 00107 overlap_part.max_ = min(max_, other.max_); 00108 return true; 00109 } 00110 00111 00113 inline bool contain(const Vec3f& p) const 00114 { 00115 if(p[0] < min_[0] || p[0] > max_[0]) return false; 00116 if(p[1] < min_[1] || p[1] > max_[1]) return false; 00117 if(p[2] < min_[2] || p[2] > max_[2]) return false; 00118 00119 return true; 00120 } 00121 00123 inline AABB& operator += (const Vec3f& p) 00124 { 00125 min_ = min(min_, p); 00126 max_ = max(max_, p); 00127 return *this; 00128 } 00129 00131 inline AABB& operator += (const AABB& other) 00132 { 00133 min_ = min(min_, other.min_); 00134 max_ = max(max_, other.max_); 00135 return *this; 00136 } 00137 00139 inline AABB operator + (const AABB& other) const 00140 { 00141 AABB res(*this); 00142 return res += other; 00143 } 00144 00146 inline BVH_REAL width() const 00147 { 00148 return max_[0] - min_[0]; 00149 } 00150 00152 inline BVH_REAL height() const 00153 { 00154 return max_[1] - min_[1]; 00155 } 00156 00158 inline BVH_REAL depth() const 00159 { 00160 return max_[2] - min_[2]; 00161 } 00162 00164 inline BVH_REAL volume() const 00165 { 00166 return width() * height() * depth(); 00167 } 00168 00170 inline BVH_REAL size() const 00171 { 00172 return (max_ - min_).sqrLength(); 00173 } 00174 00176 inline Vec3f center() const 00177 { 00178 return (min_ + max_) * 0.5; 00179 } 00180 00184 BVH_REAL distance(const AABB& other) const 00185 { 00186 std::cerr << "AABB distance not implemented!" << std::endl; 00187 return 0.0; 00188 } 00189 }; 00190 00191 } 00192 00193 #endif