megatree.h
Go to the documentation of this file.
00001 #ifndef MEGATREE_H
00002 #define MEGATREE_H
00003 
00004 #include <cstdio>
00005 #include <assert.h>
00006 #include <vector>
00007 #include <list>
00008 #include <map>
00009 
00010 #include <boost/cstdint.hpp>
00011 #include <boost/filesystem.hpp>
00012 #include <boost/shared_ptr.hpp>
00013 #include <boost/function.hpp>
00014 
00015 #include "megatree/allocator.h"
00016 #include "megatree/node_handle.h"
00017 #include "megatree/node_file.h"
00018 #include "megatree/list.h"
00019 #include "megatree/function_caller.h"
00020 #include <megatree/storage.h>
00021 #include <fstream>
00022 #include <tr1/unordered_set>
00023 #include <megatree/blocking_queue.h>
00024 #include <megatree/std_singleton_allocator.h>
00025 
00026 namespace megatree
00027 {
00028   const unsigned version = 11;
00029   const unsigned int CACHE_SIZE = 1000000;
00030   const float MIN_CELL_SIZE = 0.001; // 1 mm default accuray
00031 
00032   // Tree
00033   class MegaTree
00034   {
00035   public:
00036     // Loads the tree from disk, grabbing parameters from the metadata
00037     MegaTree(boost::shared_ptr<Storage> storage, unsigned cache_size, bool read_only);
00038 
00039     MegaTree(boost::shared_ptr<Storage> storage, const std::vector<double>& cell_center, const double& cell_size,
00040              unsigned subtree_width, unsigned subfolder_depth,
00041              unsigned cache_size=CACHE_SIZE, double _min_cell_size=MIN_CELL_SIZE);
00042 
00043     ~MegaTree();
00044 
00045     bool operator==(MegaTree& tree);
00046 
00047     // Use releaseNode() to deallocate nodes.
00048     void releaseNode(NodeHandle& node);
00049 
00050     // create nodes always blocking
00051     void createChildNode(NodeHandle& parent_node, uint8_t child, NodeHandle& child_node);
00052     NodeHandle* createChildNode(NodeHandle& parent_node, uint8_t child);
00053 
00054     // Methods for getting nodes.  The caller must release the returned node.
00055     void getRoot(NodeHandle &root_node);
00056     NodeHandle* getRoot();
00057     void getChildNode(const NodeHandle& parent_node, uint8_t child, NodeHandle &child_node);
00058     NodeHandle* getChildNode(const NodeHandle& parent_node, uint8_t child);
00059 
00060     // cache functions
00061     void flushCache();
00062 
00063     // Slow.  For careful debugging only.  Prints out which files still have nodes in use.
00064     void dumpNodesInUse();
00065 
00066     // Reset read/write/... counts that are used for debugging
00067     void resetCount()
00068     {
00069       count_hit = count_miss = count_file_write = count_nodes_read = 0;
00070     }
00071 
00072     // Get the total number of points in this tree
00073     unsigned long getNumPoints()
00074     {
00075       NodeHandle root;
00076       getRoot(root);
00077       unsigned long c = root.getCount();
00078       releaseNode(root);
00079       return c;
00080     }
00081   
00082     // Create a string with some statistics about this tree (read/write/cache_miss/...)
00083     std::string toString()
00084       {
00085         std::stringstream s;
00086         s << "Num nodes " << getNumPoints() << ", hit count " << count_hit << ", miss count " << count_miss  
00087           << ", write count " << count_file_write << ", total nodes read " << count_nodes_read 
00088           << ", nodes being written " << current_write_size
00089           << ", nodes per file " << (int)((float)current_cache_size / (float)file_cache.size())
00090           << ", total cache usage " << (int)((float)current_cache_size / (float)max_cache_size * 100.0) << "%"
00091           << ", open files " << file_cache.size();
00092         return s.str();
00093       }
00094 
00095     // Get the geometry object of the root node
00096     const NodeGeometry& getRootGeometry() const
00097     {
00098       return root_geometry;
00099     }
00100 
00101     // Get the size of the smallest cell this tree supports
00102     double getMinCellSize() const { return min_cell_size; }
00103 
00104 
00105     // This function is pretty gross.  There should be a safer way to do this.
00106     void recenter(double x, double y, double z)
00107     {
00108       assert(getNumPoints() == 0);
00109       double new_center[] = {x, y, z};
00110       NodeGeometry new_root_geometry(new_center, root_geometry.getSize());
00111       root_geometry = new_root_geometry;
00112       writeMetaData();
00113     }
00114 
00115     // Only public for regression tests
00116     // Returns the ID of the file containing the given node.
00117     IdType getFileId(const IdType& node_id);
00118     ShortId getShortId(const IdType& node_id);
00119 
00120 
00121   private:
00122     unsigned cacheSize() const { return current_cache_size; }
00123 
00124     // callback after getAsync on storage finishes
00125     void readNodeFileCb(NodeFile* node_file, const ByteVec& buffer);
00126 
00127     // callback after putAsync on storage finishes when evicting node files
00128     void evictNodeFileCb(CacheIterator<IdType, NodeFile> it);
00129 
00130     // callback after putAsync on storage finishes when flushing node files to disk
00131     void flushNodeFileCb(CacheIterator<IdType, NodeFile> it, boost::mutex& mutex, boost::condition& condition, unsigned& remaining);
00132 
00133     void createRoot(NodeHandle &root);
00134 
00135     void initTree(boost::shared_ptr<Storage> storage, const std::vector<double>& _cell_center, const double& _cell_size,
00136                   unsigned _subtree_width, unsigned _subfolder_depth,
00137                   unsigned _cache_size, double _min_cell_size);
00138 
00139 
00140     // NodeFile methods
00141     // Returns the node file with id "file_id".  Should call releaseNodeFile on the returned pointer.
00142     NodeFile* createNodeFile(const IdType& file_id);
00143     NodeFile* getNodeFile(const IdType& file_id);
00144     void releaseNodeFile(NodeFile*& node_file);
00145 
00146     void cacheMaintenance();
00147     void writeMetaData();
00148 
00149     bool checkEqualRecursive(MegaTree& tree1, MegaTree& tree2, NodeHandle& node1, NodeHandle& node2);
00150 
00151 
00152     // storage backend
00153     boost::shared_ptr<Storage> storage;
00154     
00155     // cache properties
00156     boost::mutex file_cache_mutex;
00157     Cache<IdType, NodeFile> file_cache;  // front is most recenty used
00158     unsigned current_cache_size;  // Number of nodes currently in the cache.
00159     unsigned current_write_size;  // Number of nodes currently being written.
00160 
00161     // tree properties
00162     double min_cell_size;  // Minimum edge length of a cell in this tree
00163     NodeGeometry root_geometry;
00164     unsigned max_cache_size, subtree_width, subfolder_depth;
00165     boost::shared_ptr<Allocator<Node> > node_allocator;
00166     StdSingletonAllocatorInstance<std::_Rb_tree_node<std::pair<const ShortId, Node*> > >* singleton_allocator;
00167     // Counters that track tree statistics.
00168     unsigned count_hit, count_miss, count_file_write, count_nodes_read;
00169 
00170     bool read_only;
00171 
00172 
00173   public:
00174     class ChildIterator
00175     {
00176     public:
00177       ChildIterator(MegaTree& _tree, NodeHandle& parent, NodeFile* _children_file = NULL)
00178         : child_counter(-1), tree(_tree), children_file(_children_file)
00179       {
00180         if (!_children_file)
00181         {
00182           // get file for all children
00183           IdType child_id = parent.getId().getChild(0);
00184           IdType children_file_id = tree.getFileId(child_id);
00185           children_file = tree.getNodeFile(children_file_id);  
00186           children_file->waitUntilLoaded();
00187         }
00188       
00189         // get all children
00190         for (unsigned int i=0; i<8; i++)
00191         {
00192           if (parent.hasChild(i))
00193           {
00194             IdType child_id = parent.getId().getChild(i);
00195             NodeGeometry child_geometry = parent.getNodeGeometry().getChild(i);
00196             Node* child_node = children_file->readNode(tree.getShortId(child_id));
00197             children[i].initialize(child_node, child_id, children_file, child_geometry);
00198           }
00199         }
00200         if (!_children_file)
00201           children_file->removeUser();
00202       
00203         // get first child
00204         next();
00205       }
00206       
00207       
00208       ~ChildIterator()
00209       {
00210         for (unsigned int i=0; i<8; i++)
00211         {
00212           if (children[i].isValid())
00213             tree.releaseNode(children[i]);
00214         }
00215       }
00216 
00217       void next()
00218       {
00219         child_counter++;
00220         while (child_counter < 8 && !children[child_counter].isValid())
00221           child_counter++;
00222       }
00223       
00224       
00225       bool finished()
00226       {
00227         return (child_counter > 7);
00228       }
00229       
00230       uint8_t getChildNr()
00231       {
00232         return child_counter;
00233       }
00234 
00235       NodeHandle& getChildNode()
00236       {
00237         return children[child_counter];
00238       }
00239 
00240       NodeHandle* getAllChildren()
00241       {
00242         return  children;
00243       }
00244 
00245     private:
00246       NodeHandle children[8];
00247       int child_counter;
00248       MegaTree& tree;
00249       NodeFile* children_file;
00250     };
00251 
00252   };
00253 
00254 
00255 
00256 }
00257 
00258 
00259 #endif


megatree_cpp
Author(s): Stuart Glaser
autogenerated on Mon Dec 2 2013 13:01:28