AABB.hpp
Go to the documentation of this file.
00001 // ========================================================================================
00002 //  ApproxMVBB
00003 //  Copyright (C) 2014 by Gabriel Nützi <nuetzig (at) imes (d0t) mavt (d0t) ethz (døt) ch>
00004 //
00005 //  This Source Code Form is subject to the terms of the Mozilla Public
00006 //  License, v. 2.0. If a copy of the MPL was not distributed with this
00007 //  file, You can obtain one at http://mozilla.org/MPL/2.0/.
00008 // ========================================================================================
00009 
00010 #ifndef ApproxMVBB_AABB_hpp
00011 #define ApproxMVBB_AABB_hpp
00012 
00013 #include <algorithm>
00014 
00015 #include "ApproxMVBB/Config/Config.hpp"
00016 #include ApproxMVBB_TypeDefs_INCLUDE_FILE
00017 #include ApproxMVBB_StaticAssert_INCLUDE_FILE
00018 #include ApproxMVBB_AssertionDebug_INCLUDE_FILE
00019 
00020 namespace ApproxMVBB{
00021 
00022 template<unsigned int Dim>
00023 class  AABB {
00024 public:
00025     ApproxMVBB_DEFINE_MATRIX_TYPES
00026     EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00027 private:
00028 
00029     template<unsigned int D = Dim,  bool = true>
00030     struct unite_impl{
00031         template<typename T, typename P>
00032         inline static void apply(T * t, const P & p){
00033             t->m_maxPoint(D-1) = std::max(t->m_maxPoint(D-1),p(D-1));
00034             t->m_minPoint(D-1) = std::min(t->m_minPoint(D-1),p(D-1));
00035             unite_impl<D-1>::apply(t,p);
00036         }
00037     };
00038     template<bool dummy>
00039     struct unite_impl<0,dummy>{
00040         template<typename T, typename P>
00041         inline static void apply(T *, const P &){}
00042     };
00043 
00044     template<unsigned int D = Dim,  bool = true>
00045     struct uniteBox_impl{
00046         template<typename T, typename B>
00047         inline static void apply(T * t, const B & b){
00048             t->m_maxPoint(D-1) = std::max(t->m_maxPoint(D-1),b.m_maxPoint(D-1));
00049             t->m_minPoint(D-1) = std::min(t->m_minPoint(D-1),b.m_minPoint(D-1));
00050             uniteBox_impl<D-1>::apply(t,b);
00051         }
00052     };
00053     template<bool dummy>
00054     struct uniteBox_impl<0,dummy>{
00055         template<typename T, typename B>
00056         inline static void apply(T *, const B &){}
00057     };
00058 
00059 
00060     template<unsigned int D = Dim, bool = true>
00061     struct reset_impl{
00062         template<typename T>
00063         inline static void apply(T * t){
00064             t->m_minPoint(D-1) = std::numeric_limits<PREC>::max();
00065             t->m_maxPoint(D-1) = std::numeric_limits<PREC>::lowest();
00066             reset_impl<D-1>::apply(t);
00067         }
00068     };
00069 
00070     template<bool dummy>
00071     struct reset_impl<0,dummy>{
00072         template<typename T>
00073         inline static void apply(T *){}
00074     };
00075 
00076 public:
00077 
00078     AABB() {
00079         reset();
00080     }
00081     void reset(){
00082         reset_impl<>::apply(this);
00083     }
00084 
00085     AABB( const VectorStat<Dim> &p): m_minPoint(p), m_maxPoint(p) {}
00086 
00087     AABB( const VectorStat<Dim> &l, const VectorStat<Dim> &u): m_minPoint(l), m_maxPoint(u) {
00088         ApproxMVBB_ASSERTMSG( (m_maxPoint.array() >= m_minPoint.array()).all(),
00089         "AABB initialized wrongly! min/max: " << m_minPoint.transpose() <<"/" << m_maxPoint.transpose());
00090     }
00091 
00092 
00093     template<typename Derived>
00094     AABB& unite(const MatrixBase<Derived> &p) {
00095       EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Derived,Dim);
00096       unite_impl<>::apply(this,p);
00097       return *this;
00098     }
00099 
00100     template<typename Derived>
00101     AABB& operator+=(const MatrixBase<Derived> &p){
00102         EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Derived,Dim);
00103         unite_impl<>::apply(this,p);
00104         return *this;
00105     }
00106 
00107 
00108     void unite(const AABB & box) {
00109         uniteBox_impl<>::apply(this,box);
00110     }
00111 
00112     AABB& operator+=(const AABB & box){
00113         uniteBox_impl<>::apply(this,box);
00114         return *this;
00115     }
00116 
00117     AABB operator+ (const AABB & box){
00118         AABB r = this;
00119         uniteBox_impl<>::apply(&r,box);
00120         return r;
00121     }
00122 
00123     AABB& transform(const AffineTrafo & M) {
00124         ApproxMVBB_STATIC_ASSERTM(Dim==3,"So far AABB transform is only implemented in 3d")
00125         AABB ret( M*(Vector3( m_minPoint(0), m_minPoint(1), m_minPoint(2))));
00126         ret.unite(M*(Vector3( m_maxPoint(0), m_minPoint(1), m_minPoint(2))));
00127         ret.unite(M*(Vector3( m_minPoint(0), m_maxPoint(1), m_minPoint(2))));
00128         ret.unite(M*(Vector3( m_minPoint(0), m_minPoint(1), m_maxPoint(2))));
00129         ret.unite(M*(Vector3( m_minPoint(0), m_maxPoint(1), m_maxPoint(2))));
00130         ret.unite(M*(Vector3( m_maxPoint(0), m_maxPoint(1), m_minPoint(2))));
00131         ret.unite(M*(Vector3( m_maxPoint(0), m_minPoint(1), m_maxPoint(2))));
00132         ret.unite(M*(Vector3( m_maxPoint(0), m_maxPoint(1), m_maxPoint(2))));
00133         *this = ret;
00134         return *this;
00135     }
00136 
00137 
00138     inline VectorStat<Dim> center(){ return 0.5*(m_maxPoint + m_minPoint);}
00139 
00140     inline bool overlaps(const AABB & box) const {
00141         return ((m_maxPoint.array() >= box.m_minPoint.array()) && (m_minPoint.array() <= box.m_maxPoint.array())).all();
00142     }
00143 
00144     template<typename Derived>
00145     inline bool overlaps(const MatrixBase<Derived> &p) const {
00146         return ((p.array() >= m_minPoint.array()) && (p.array() <= m_maxPoint.array())).all();
00147     }
00148 
00149     inline bool overlapsSubSpace(const AABB & box, unsigned int fixedAxis) const {
00150         MyMatrix::ArrayStat<bool,Dim> t = ((m_maxPoint.array() >= box.m_minPoint.array()) && (m_minPoint.array() <= box.m_maxPoint.array()));
00151         t(fixedAxis) = true;
00152         return t.all();
00153     }
00154 
00155     inline ArrayStat<Dim> extent() const{
00156         // since min <= max, extent can not be smaller than zero
00157         // , except if AABB contains no points/uninitialized (reset())
00158         return (m_maxPoint - m_minPoint).array();
00159     }
00160 
00161     inline PREC maxExtent() const{
00162         return (m_maxPoint - m_minPoint).maxCoeff();
00163     }
00164 
00165     inline bool isEmpty() const {
00166         return (m_maxPoint.array() <= m_minPoint.array()).any();
00167     }
00168 
00169     inline void expand(PREC d) {
00170         ApproxMVBB_ASSERTMSG(d>=0,"d>=0")
00171         m_minPoint.array() -= d;
00172         m_maxPoint.array() += d;
00173     }
00174 
00175     inline void expand(VectorStat<Dim> d) {
00176         ApproxMVBB_ASSERTMSG((d.array()>=0).all(), "d<0")
00177         m_minPoint -= d;
00178         m_maxPoint += d;
00179     }
00180 
00182     void expandToMinExtentRelative(PREC p, PREC defaultExtent, PREC eps){
00183         ArrayStat<Dim> e = extent();
00184         VectorStat<Dim> c = center();
00185         typename ArrayStat<Dim>::Index idx;
00186         PREC ext = std::abs(e.maxCoeff(&idx)) * p;
00187 
00188         if( ext < eps ){ // extent of max axis almost zero, set all axis to defaultExtent --> cube
00189             ext = defaultExtent;
00190             m_minPoint = c - 0.5*ext;
00191             m_maxPoint = c + 0.5*ext;
00192         }else{
00193             for(int i=0;i<Dim;++i){
00194                 if(i!=idx && std::abs(e(i)) < ext){
00195                     m_minPoint(i) = c(i) - 0.5*ext;
00196                     m_maxPoint(i) = c(i) + 0.5*ext;
00197                 }
00198             }
00199         }
00200     }
00201 
00203     void expandToMinExtentAbsolute(PREC minExtent){
00204         Array3 e = extent();
00205         Vector3 c = center();
00206 
00207         PREC l = 0.5*minExtent;
00208         for(int i=0;i<Dim;++i){
00209             if(std::abs(e(i)) < minExtent){
00210                 m_minPoint(i) = c(i) - l;
00211                 m_maxPoint(i) = c(i) + l;
00212             }
00213         }
00214     }
00215 
00217     void expandToMinExtentAbsolute(ArrayStat<Dim> minExtent){
00218         Array3 e = extent();
00219         Vector3 c = center();
00220 
00221         for(unsigned int i=0;i<Dim;++i){
00222             PREC l = minExtent(i);
00223             if(std::abs(e(i)) < l){
00224                 m_minPoint(i) = c(i) - 0.5*l;
00225                 m_maxPoint(i) = c(i) + 0.5*l;
00226             }
00227         }
00228     }
00229 
00234     template<bool MoveMax>
00235     void expandToMaxExtent(const unsigned int & axis){
00236         ApproxMVBB_ASSERTMSG(axis < Dim,"axis >= Dim !");
00237         if(!MoveMax){
00238             m_minPoint(axis) = std::numeric_limits<PREC>::lowest();
00239         }else{
00240             m_maxPoint(axis) = std::numeric_limits<PREC>::max();
00241         }
00242     }
00243 
00244     void expandToMaxExtent(){
00245         m_minPoint.setConstant(std::numeric_limits<PREC>::lowest());
00246         m_maxPoint.setConstant(std::numeric_limits<PREC>::max());
00247     }
00248 
00249     inline PREC volume() const {
00250         return (m_maxPoint - m_minPoint).prod();
00251     }
00252 
00253     //info about axis aligned bounding box
00254     VectorStat<Dim> m_minPoint;
00255     VectorStat<Dim> m_maxPoint;
00256 };
00257 
00258 using AABB3d = AABB<3>;
00259 using AABB2d = AABB<2>;
00260 
00261 }
00262 
00263  #endif


asr_approx_mvbb
Author(s): Gassner Nikolai
autogenerated on Sat Jun 8 2019 20:21:49