node_file.h
Go to the documentation of this file.
00001 #ifndef MEGATREE_NODE_FILE_H_
00002 #define MEGATREE_NODE_FILE_H_
00003 
00004 #include <megatree/std_singleton_allocator.h>
00005 #include <megatree/allocator.h>
00006 #include <megatree/node.h>
00007 #include <megatree/cache.h>
00008 #include <megatree/storage.h>  // for ByteVec typedef
00009 #include <megatree/tree_common.h>
00010 #include <boost/thread/mutex.hpp>
00011 #include <boost/thread/condition.hpp>
00012 #include <boost/filesystem.hpp>
00013 #include <pthread.h>
00014 
00015 
00016 namespace megatree
00017 {
00018 
00019 class SpinLock
00020 {
00021   public:
00022     SpinLock()
00023     {
00024       int ret = pthread_spin_init(&spinlock, 0);
00025       assert(ret == 0);
00026     }
00027 
00028     void lock()
00029     {
00030       int ret = pthread_spin_lock(&spinlock);
00031       assert(ret == 0);
00032     }
00033 
00034     void unlock()
00035     {
00036       int ret = pthread_spin_unlock(&spinlock);
00037       assert(ret == 0);
00038     }
00039 
00040     ~SpinLock()
00041     {
00042       pthread_spin_destroy(&spinlock);
00043     }
00044 
00045   class ScopedLock
00046   {
00047     public:
00048       ScopedLock(SpinLock& _spinlock): spinlock(_spinlock)
00049       {
00050         spinlock.lock();
00051       }
00052 
00053       ~ScopedLock()
00054       {
00055         spinlock.unlock();
00056       }
00057 
00058     private:
00059       SpinLock& spinlock;
00060 
00061   };
00062 
00063   private:
00064     pthread_spinlock_t spinlock;
00065 };
00066 
00067 
00068 class Cond
00069 {
00070 public:
00071   Cond(): cond(false)
00072   {
00073   }
00074 
00075   void wait(SpinLock& spinlock)
00076   {
00077     cond = false;
00078     spinlock.unlock();
00079     //TODO: There has just got to be a better way than having to write a custom
00080     //while loop here. The pthread_cond stuff won't take a pthread_spinlock as
00081     //input though and I cannot for the life of me figure out how to get the
00082     //mutex that, I think, is contained within the pthread_spinlock... ugh
00083     //swap this out for something better... please
00084     while(!cond)
00085       usleep(10);
00086     spinlock.lock();
00087   }
00088 
00089   void notify_all()
00090   {
00091     cond = true;
00092   }
00093 
00094 private:
00095   bool cond;
00096 };
00097 
00098 
00099 
00100 enum NodeState
00101 {
00102   INVALID,
00103   LOADING,
00104   LOADED,
00105   EVICTING
00106 };
00107 
00108 
00109 
00110 class NodeFile
00111 {
00112   typedef Allocator<Node> NodeAllocator;
00113   typedef Allocator<std::pair<ShortId, Node*> > PairAllocator;
00114 
00115 public:
00116   NodeFile(const boost::filesystem::path& _path,
00117            boost::shared_ptr<NodeAllocator> _node_allocator = boost::shared_ptr<NodeAllocator>(),
00118            boost::shared_ptr<PairAllocator> _pair_allocator = boost::shared_ptr<PairAllocator>())
00119   : node_state(LOADING), path(_path),
00120     child_files(0),
00121     node_allocator(_node_allocator), pair_allocator(_pair_allocator),
00122     use_count(0) {}
00123 
00124   ~NodeFile();
00125 
00126   // empty deserialize
00127   void deserialize();
00128 
00129   // deserializes a ByteVec into the node file
00130   void deserialize(const ByteVec& buffer);
00131 
00132   // serialized the node file into a ByteVec
00133   void serialize(ByteVec& buffer);
00134 
00135   // Serializes the node file into a ByteVec using the very tiny
00136   // "bytesize" format.  3 bytes for position, 3 for color.
00137   void serializeBytesize(ByteVec& buffer);
00138 
00139   // Reads an existing node from the cache.  Must return this node with releaseNode()
00140   Node* readNode(const ShortId& short_id);
00141 
00142   // Creates a new node in this file.  Must return this node with releaseNode()
00143   Node* createNode(const ShortId& short_id);
00144 
00145   void initializeFromChildren(const boost::filesystem::path &_path,
00146       std::vector<boost::shared_ptr<NodeFile> >& children);
00147   void initializeRootNodeFile(const boost::filesystem::path &_path, NodeFile& child);
00148 
00149   // Returns a node.
00150   void releaseNode(Node* node, const ShortId& short_id, bool modified);
00151 
00152   void setWritten()
00153   {
00154     is_modified = false;
00155   }
00156 
00157   // get the number of nodes that are currently in use.  Protected by mutex.
00158   unsigned users() const
00159   {
00160     return use_count;
00161   }
00162 
00163   bool hasChildFile(uint8_t child) const
00164   {
00165     return (child_files >> child) & 1;
00166   }
00167 
00168   void setChildFile(uint8_t child)
00169   {
00170     is_modified = true;
00171     child_files |= (1 << child);
00172   }
00173 
00174   void clearChildFile(uint8_t child)
00175   {
00176     is_modified = true;
00177     child_files &= ~(1 << child);
00178   }
00179 
00180   // Protected by mutex.
00181   void addUser()
00182   {
00183     use_count++;
00184   }
00185 
00186   // Protected by mutex.
00187   void removeUser()
00188   {
00189     assert(use_count > 0);
00190     use_count--;
00191   }
00192 
00193   boost::filesystem::path getPath() const { return path; }
00194 
00195   unsigned cacheSize() const
00196   {
00197     return node_cache.size();
00198   }
00199 
00200   bool isModified()
00201   {
00202     return is_modified;
00203   }
00204 
00205   NodeState getNodeState()
00206   {
00207     SpinLock::ScopedLock lock(node_state_mutex);
00208     return node_state;
00209   }
00210 
00211   void setNodeState(NodeState state);
00212 
00213   void waitUntilLoaded();
00214 
00215   boost::mutex mutex;
00216 
00217 private:
00218 
00219   SpinLock node_state_mutex;
00220   //  boost::condition node_state_condition;
00221   Cond node_state_condition;
00222   NodeState node_state;
00223 
00224   boost::filesystem::path path;
00225 
00226   // Bitstring, indicating which child files exist.
00227   uint8_t child_files;
00228 
00229   // Lookup table, keyed on the node's short_id in the file.
00230   //
00231   // The node cache used to be an std::tr1::unordered_map, but was
00232   // switched to a map to get more deterministic memory usage.  The
00233   // unordered_map was eating memory by allocating buckets and
00234   // hashtable nodes (generally when createNode was called) and caused
00235   // the overall memory usage of import_las to grow over time, until
00236   // it used up all the machine's memory.  After changing to std::map,
00237   // the memory usage now remains flat after the initial cache fill.
00238   //
00239   // The memory usage of std::map is much better, and the speed did
00240   // not measurably change.
00241   typedef std::map<ShortId, Node*> NodeCache;
00242   //std::map<ShortId, Node*, std::less<ShortId>, StdSingletonAllocator <std::pair<const ShortId, Node*> > > node_cache;
00243   std::map<ShortId, Node*, std::less<ShortId> > node_cache;
00244 
00245   static void serializeNode(const Node* node, const ShortId& short_id, ByteVec& buffer, unsigned& offset);
00246   static void deserializeNode(Node* node, ShortId& short_id, const ByteVec& buffer, unsigned& offse);
00247 
00248   boost::shared_ptr<NodeAllocator> node_allocator;
00249   boost::shared_ptr<PairAllocator> pair_allocator;
00250 
00251   size_t use_count;
00252   bool is_modified;
00253 };
00254 
00255 }
00256 
00257 #endif
00258 ;


megatree_cpp
Author(s): Stuart Glaser
autogenerated on Thu Nov 28 2013 11:30:34