Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00037 #ifndef FCL_MORTON_H
00038 #define FCL_MORTON_H
00039
00040 #include <boost/dynamic_bitset.hpp>
00041 #include "fcl/data_types.h"
00042 #include "fcl/BV/AABB.h"
00043
00044 namespace fcl
00045 {
00046
00048 namespace details
00049 {
00050
00051 static inline FCL_UINT32 quantize(FCL_REAL x, FCL_UINT32 n)
00052 {
00053 return std::max(std::min((FCL_UINT32)(x * (FCL_REAL)n), FCL_UINT32(n-1)), FCL_UINT32(0));
00054 }
00055
00057 static inline FCL_UINT32 morton_code(FCL_UINT32 x, FCL_UINT32 y, FCL_UINT32 z)
00058 {
00059 x = (x | (x << 16)) & 0x030000FF;
00060 x = (x | (x << 8)) & 0x0300F00F;
00061 x = (x | (x << 4)) & 0x030C30C3;
00062 x = (x | (x << 2)) & 0x09249249;
00063
00064 y = (y | (y << 16)) & 0x030000FF;
00065 y = (y | (y << 8)) & 0x0300F00F;
00066 y = (y | (y << 4)) & 0x030C30C3;
00067 y = (y | (y << 2)) & 0x09249249;
00068
00069 z = (z | (z << 16)) & 0x030000FF;
00070 z = (z | (z << 8)) & 0x0300F00F;
00071 z = (z | (z << 4)) & 0x030C30C3;
00072 z = (z | (z << 2)) & 0x09249249;
00073
00074 return x | (y << 1) | (z << 2);
00075 }
00076
00078 static inline FCL_UINT64 morton_code60(FCL_UINT32 x, FCL_UINT32 y, FCL_UINT32 z)
00079 {
00080 FCL_UINT32 lo_x = x & 1023u;
00081 FCL_UINT32 lo_y = y & 1023u;
00082 FCL_UINT32 lo_z = z & 1023u;
00083 FCL_UINT32 hi_x = x >> 10u;
00084 FCL_UINT32 hi_y = y >> 10u;
00085 FCL_UINT32 hi_z = z >> 10u;
00086
00087 return (FCL_UINT64(morton_code(hi_x, hi_y, hi_z)) << 30) | FCL_UINT64(morton_code(lo_x, lo_y, lo_z));
00088 }
00089
00090 }
00092
00093
00095 template<typename T>
00096 struct morton_functor {};
00097
00098
00100 template<>
00101 struct morton_functor<FCL_UINT32>
00102 {
00103 morton_functor(const AABB& bbox) : base(bbox.min_),
00104 inv(1.0 / (bbox.max_[0] - bbox.min_[0]),
00105 1.0 / (bbox.max_[1] - bbox.min_[1]),
00106 1.0 / (bbox.max_[2] - bbox.min_[2]))
00107 {}
00108
00109 FCL_UINT32 operator() (const Vec3f& point) const
00110 {
00111 FCL_UINT32 x = details::quantize((point[0] - base[0]) * inv[0], 1024u);
00112 FCL_UINT32 y = details::quantize((point[1] - base[1]) * inv[1], 1024u);
00113 FCL_UINT32 z = details::quantize((point[2] - base[2]) * inv[2], 1024u);
00114
00115 return details::morton_code(x, y, z);
00116 }
00117
00118 const Vec3f base;
00119 const Vec3f inv;
00120
00121 size_t bits() const { return 30; }
00122 };
00123
00124
00126 template<>
00127 struct morton_functor<FCL_UINT64>
00128 {
00129 morton_functor(const AABB& bbox) : base(bbox.min_),
00130 inv(1.0 / (bbox.max_[0] - bbox.min_[0]),
00131 1.0 / (bbox.max_[1] - bbox.min_[1]),
00132 1.0 / (bbox.max_[2] - bbox.min_[2]))
00133 {}
00134
00135 FCL_UINT64 operator() (const Vec3f& point) const
00136 {
00137 FCL_UINT32 x = details::quantize((point[0] - base[0]) * inv[0], 1u << 20);
00138 FCL_UINT32 y = details::quantize((point[1] - base[1]) * inv[1], 1u << 20);
00139 FCL_UINT32 z = details::quantize((point[2] - base[2]) * inv[2], 1u << 20);
00140
00141 return details::morton_code60(x, y, z);
00142 }
00143
00144 const Vec3f base;
00145 const Vec3f inv;
00146
00147 size_t bits() const { return 60; }
00148 };
00149
00151 template<>
00152 struct morton_functor<boost::dynamic_bitset<> >
00153 {
00154 morton_functor(const AABB& bbox, size_t bit_num_) : base(bbox.min_),
00155 inv(1.0 / (bbox.max_[0] - bbox.min_[0]),
00156 1.0 / (bbox.max_[1] - bbox.min_[1]),
00157 1.0 / (bbox.max_[2] - bbox.min_[2])),
00158 bit_num(bit_num_)
00159 {}
00160
00161 boost::dynamic_bitset<> operator() (const Vec3f& point) const
00162 {
00163 FCL_REAL x = (point[0] - base[0]) * inv[0];
00164 FCL_REAL y = (point[1] - base[1]) * inv[1];
00165 FCL_REAL z = (point[2] - base[2]) * inv[2];
00166 int start_bit = bit_num * 3 - 1;
00167 boost::dynamic_bitset<> bits(bit_num * 3);
00168
00169 x *= 2;
00170 y *= 2;
00171 z *= 2;
00172
00173 for(size_t i = 0; i < bit_num; ++i)
00174 {
00175 bits[start_bit--] = ((z < 1) ? 0 : 1);
00176 bits[start_bit--] = ((y < 1) ? 0 : 1);
00177 bits[start_bit--] = ((x < 1) ? 0 : 1);
00178 x = ((x >= 1) ? 2*(x-1) : 2*x);
00179 y = ((y >= 1) ? 2*(y-1) : 2*y);
00180 z = ((z >= 1) ? 2*(z-1) : 2*z);
00181 }
00182
00183 return bits;
00184 }
00185
00186 const Vec3f base;
00187 const Vec3f inv;
00188 const size_t bit_num;
00189
00190 size_t bits() const { return bit_num * 3; }
00191 };
00192
00193 }
00194
00195 #endif