10 #ifndef ApproxMVBB_AABB_hpp 11 #define ApproxMVBB_AABB_hpp 16 #include ApproxMVBB_TypeDefs_INCLUDE_FILE 17 #include ApproxMVBB_StaticAssert_INCLUDE_FILE 18 #include ApproxMVBB_AssertionDebug_INCLUDE_FILE 22 template<
unsigned int Dim>
26 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
29 template<
unsigned int D = Dim,
bool = true>
31 template<
typename T,
typename P>
32 inline static void apply(T * t,
const P & p){
33 t->m_maxPoint(D-1) = std::max(t->m_maxPoint(D-1),p(D-1));
34 t->m_minPoint(D-1) = std::min(t->m_minPoint(D-1),p(D-1));
40 template<
typename T,
typename P>
41 inline static void apply(T *,
const P &){}
44 template<
unsigned int D = Dim,
bool = true>
46 template<
typename T,
typename B>
47 inline static void apply(T * t,
const B & b){
48 t->m_maxPoint(D-1) = std::max(t->m_maxPoint(D-1),b.m_maxPoint(D-1));
49 t->m_minPoint(D-1) = std::min(t->m_minPoint(D-1),b.m_minPoint(D-1));
55 template<
typename T,
typename B>
56 inline static void apply(T *,
const B &){}
60 template<
unsigned int D = Dim,
bool = true>
63 inline static void apply(T * t){
64 t->m_minPoint(D-1) = std::numeric_limits<PREC>::max();
65 t->m_maxPoint(D-1) = std::numeric_limits<PREC>::lowest();
89 "AABB initialized wrongly! min/max: " <<
m_minPoint.transpose() <<
"/" <<
m_maxPoint.transpose());
93 template<
typename Derived>
95 EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Derived,Dim);
100 template<
typename Derived>
102 EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Derived,Dim);
144 template<
typename Derived>
145 inline bool overlaps(
const MatrixBase<Derived> &p)
const {
183 ArrayStat<Dim> e =
extent();
184 VectorStat<Dim> c =
center();
185 typename ArrayStat<Dim>::Index idx;
186 PREC ext = std::abs(e.maxCoeff(&idx)) * p;
193 for(
int i=0;i<Dim;++i){
194 if(i!=idx && std::abs(e(i)) < ext){
207 PREC l = 0.5*minExtent;
208 for(
int i=0;i<Dim;++i){
209 if(std::abs(e(i)) < minExtent){
221 for(
unsigned int i=0;i<Dim;++i){
222 PREC l = minExtent(i);
223 if(std::abs(e(i)) < l){
234 template<
bool MoveMax>
238 m_minPoint(axis) = std::numeric_limits<PREC>::lowest(); 240 m_maxPoint(axis) = std::numeric_limits<PREC>::max(); 244 void expandToMaxExtent(){ 245 m_minPoint.setConstant(std::numeric_limits<PREC>::lowest()); 246 m_maxPoint.setConstant(std::numeric_limits<PREC>::max()); 249 inline PREC volume() const { 250 return (m_maxPoint - m_minPoint).prod(); 253 //info about axis aligned bounding box 254 VectorStat<Dim> m_minPoint; 255 VectorStat<Dim> m_maxPoint; 258 using AABB3d = AABB<3>; 259 using AABB2d = AABB<2>; #define ApproxMVBB_ASSERTMSG(condition, message)
An Assert Macro to use within C++ code.
void expand(VectorStat< Dim > d)
void expandToMinExtentAbsolute(ArrayStat< Dim > minExtent)
void unite(const AABB &box)
AABB & unite(const MatrixBase< Derived > &p)
VectorStat< Dim > m_minPoint
VectorStat< Dim > center()
These are some container definitions.
Eigen::Array< Scalar, M, 1 > ArrayStat
AABB & operator+=(const MatrixBase< Derived > &p)
static void apply(T *t, const P &p)
bool overlaps(const MatrixBase< Derived > &p) const
void expandToMaxExtent(const unsigned int &axis)
bool overlaps(const AABB &box) const
VectorStat< Dim > m_maxPoint
static void apply(T *, const P &)
AABB & operator+=(const AABB &box)
static void apply(T *t, const B &b)
static void apply(T *, const B &)
AABB & transform(const AffineTrafo &M)
void expandToMinExtentAbsolute(PREC minExtent)
Eigen::Array< Scalar, 3, 1 > Array3
AABB(const VectorStat< Dim > &p)
AABB operator+(const AABB &box)
void expandToMinExtentRelative(PREC p, PREC defaultExtent, PREC eps)
Eigen::Matrix< Scalar, 3, 1 > Vector3
bool overlapsSubSpace(const AABB &box, unsigned int fixedAxis) const
#define ApproxMVBB_STATIC_ASSERTM(B, COMMENT)
Eigen::Transform< Scalar, 3, Eigen::TransformTraits::Affine > AffineTrafo
#define ApproxMVBB_DEFINE_MATRIX_TYPES
ArrayStat< Dim > extent() const
AABB(const VectorStat< Dim > &l, const VectorStat< Dim > &u)