|
| 1 | +#ifndef LA3DM_GP_BLOCK_H |
| 2 | +#define LA3DM_GP_BLOCK_H |
| 3 | + |
| 4 | +#include <unordered_map> |
| 5 | +#include <array> |
| 6 | +#include "point3f.h" |
| 7 | +#include "gpoctree_node.h" |
| 8 | +#include "gpoctree.h" |
| 9 | + |
| 10 | +namespace la3dm { |
| 11 | + |
| 12 | + /// Hask key to index Block given block's center. |
| 13 | + typedef int64_t BlockHashKey; |
| 14 | + |
| 15 | + /// Initialize Look-Up Table |
| 16 | + std::unordered_map<OcTreeHashKey, point3f> init_key_loc_map(float resolution, unsigned short max_depth); |
| 17 | + |
| 18 | + std::unordered_map<unsigned short, OcTreeHashKey> init_index_map(const std::unordered_map<OcTreeHashKey, point3f> &key_loc_map, |
| 19 | + unsigned short max_depth); |
| 20 | + |
| 21 | + /// Extended Block |
| 22 | +#ifdef PREDICT |
| 23 | + typedef std::array<BlockHashKey, 27> ExtendedBlock; |
| 24 | +#else |
| 25 | + typedef std::array<BlockHashKey, 7> ExtendedBlock; |
| 26 | +#endif |
| 27 | + |
| 28 | + /// Convert from block to hash key. |
| 29 | + BlockHashKey block_to_hash_key(point3f center); |
| 30 | + |
| 31 | + /// Convert from block to hash key. |
| 32 | + BlockHashKey block_to_hash_key(float x, float y, float z); |
| 33 | + |
| 34 | + /// Convert from hash key to block. |
| 35 | + point3f hash_key_to_block(BlockHashKey key); |
| 36 | + |
| 37 | + /// Get current block's extended block. |
| 38 | + ExtendedBlock get_extended_block(BlockHashKey key); |
| 39 | + |
| 40 | + /* |
| 41 | + * @brief Block is built on top of OcTree, providing the functions to locate nodes. |
| 42 | + * |
| 43 | + * Block stores the information needed to locate each OcTreeNode's position: |
| 44 | + * fixed resolution, fixed block_size, both of which must be initialized. |
| 45 | + * The localization is implemented using Loop-Up Table. |
| 46 | + */ |
| 47 | + class Block : public OcTree { |
| 48 | + friend BlockHashKey block_to_hash_key(point3f center); |
| 49 | + |
| 50 | + friend BlockHashKey block_to_hash_key(float x, float y, float z); |
| 51 | + |
| 52 | + friend point3f hash_key_to_block(BlockHashKey key); |
| 53 | + |
| 54 | + friend ExtendedBlock get_extended_block(BlockHashKey key); |
| 55 | + |
| 56 | + friend class GPOctoMap; |
| 57 | + |
| 58 | + public: |
| 59 | + Block(); |
| 60 | + |
| 61 | + Block(point3f center); |
| 62 | + |
| 63 | + /// @return location of the OcTreeNode given OcTree's LeafIterator. |
| 64 | + inline point3f get_loc(const LeafIterator &it) const { |
| 65 | + return Block::key_loc_map[it.get_hash_key()] + center; |
| 66 | + } |
| 67 | + |
| 68 | + /// @return size of the OcTreeNode given OcTree's LeafIterator. |
| 69 | + inline float get_size(const LeafIterator &it) const { |
| 70 | + unsigned short depth, index; |
| 71 | + hash_key_to_node(it.get_hash_key(), depth, index); |
| 72 | + return float(size / pow(2, depth)); |
| 73 | + } |
| 74 | + |
| 75 | + /// @return center of current Block. |
| 76 | + inline point3f get_center() const { return center; } |
| 77 | + |
| 78 | + /// @return min lim of current Block. |
| 79 | + inline point3f get_lim_min() const { return center - point3f(size / 2.0f, size / 2.0f, size / 2.0f); } |
| 80 | + |
| 81 | + /// @return max lim of current Block. |
| 82 | + inline point3f get_lim_max() const { return center + point3f(size / 2.0f, size / 2.0f, size / 2.0f); } |
| 83 | + |
| 84 | + /// @return ExtendedBlock of current Block. |
| 85 | + ExtendedBlock get_extended_block() const; |
| 86 | + |
| 87 | + OcTreeHashKey get_node(unsigned short x, unsigned short y, unsigned short z) const; |
| 88 | + |
| 89 | + point3f get_point(unsigned short x, unsigned short y, unsigned short z) const; |
| 90 | + |
| 91 | + void get_index(const point3f &p, unsigned short &x, unsigned short &y, unsigned short &z) const; |
| 92 | + |
| 93 | + OcTreeNode &search(float x, float y, float z) const; |
| 94 | + |
| 95 | + OcTreeNode &search(point3f p) const; |
| 96 | + |
| 97 | + private: |
| 98 | + // Loop-Up Table |
| 99 | + static std::unordered_map<OcTreeHashKey, point3f> key_loc_map; |
| 100 | + static std::unordered_map<unsigned short, OcTreeHashKey> index_map; |
| 101 | + static float resolution; |
| 102 | + static float size; |
| 103 | + static unsigned short cell_num; |
| 104 | + |
| 105 | + point3f center; |
| 106 | + }; |
| 107 | + |
| 108 | +} |
| 109 | + |
| 110 | +#endif // LA3DM_GP_BLOCK_H |
0 commit comments