megatree.cpp
Go to the documentation of this file.
00001 #include <megatree/megatree.h>
00002 #include <megatree/tree_functions.h>
00003 #include <megatree/metadata.h>
00004 
00005 #include <iostream>
00006 #include <fstream>
00007 #include <cstdio>
00008 #include <cmath>
00009 #include <vector>
00010 #include <sys/types.h>
00011 #include <sys/stat.h>
00012 #include <fcntl.h>
00013 #include <unistd.h>
00014 
00015 
00016 namespace megatree
00017 {
00018 
00019 // Loads the tree from disk, grabbing parameters from the metadata
00020 MegaTree::MegaTree(boost::shared_ptr<Storage> _storage, unsigned cache_size, bool _read_only)
00021   : storage(_storage), read_only(_read_only)
00022 {
00023   printf("Reading existing tree\n");
00024 
00025   // get tree metadata
00026   ByteVec data;
00027   storage->get("metadata.ini", data);
00028   MetaData metadata;
00029   metadata.deserialize(data);
00030 
00031   // Checks that the on-disk version matches the code version.
00032   if (metadata.version != version)
00033   {
00034     fprintf(stderr, "You are trying to read a tree with version %d from disk, but your code was compiled for version %d\n",
00035             metadata.version, version);
00036     abort();
00037   }
00038 
00039   // get params
00040   min_cell_size = metadata.min_cell_size;
00041   subtree_width = metadata.subtree_width;
00042   subfolder_depth = metadata.subfolder_depth;
00043 
00044   // Initializes the tree
00045   initTree(storage, metadata.root_center, metadata.root_size, subtree_width, subfolder_depth, cache_size, min_cell_size);
00046 }
00047 
00048 
00049 
00050 MegaTree::MegaTree(boost::shared_ptr<Storage> _storage, const std::vector<double>& cell_center, const double& cell_size,
00051                    unsigned subtree_width, unsigned subfolder_depth,
00052                    unsigned cache_size, double min_cell_size)
00053   : storage(_storage), read_only(false)
00054 {
00055   initTree(storage, cell_center, cell_size, subtree_width, subfolder_depth, cache_size, min_cell_size);
00056 
00057   // Creates the root node for this new tree.
00058   NodeHandle root;
00059   createRoot(root);
00060   releaseNode(root);
00061 
00062   // writes the metadata of this new tree
00063   writeMetaData();
00064 
00065 }
00066 
00067 MegaTree::~MegaTree()
00068 {
00069   flushCache();
00070 
00071   while (true)
00072   {
00073     {
00074       // delete node file pointers
00075       boost::mutex::scoped_lock lock(file_cache_mutex);
00076       if (file_cache.size() == 0)
00077         break;
00078 
00079       CacheIterator<IdType, NodeFile> it = file_cache.iterate();
00080       while (!it.finished())
00081       {
00082         NodeFile* to_delete(NULL);
00083         {
00084           // lock node file
00085           boost::mutex::scoped_try_lock file_lock(it.get()->mutex);
00086 
00087           // delete node file and remove it form cache
00088           if (file_lock && it.get()->getNodeState() == LOADED)
00089           {
00090             CacheIterator<IdType, NodeFile> it_to_delete = it;
00091             it.next();
00092             to_delete = it_to_delete.get();
00093             file_cache.erase(it_to_delete);
00094             current_cache_size -= to_delete->cacheSize();
00095           }
00096           else
00097             it.next();
00098         }
00099 
00100         if (to_delete)
00101           delete to_delete;
00102 
00103       }
00104     }
00105     // sleep
00106     usleep(100000);
00107   }
00108 
00109   if (singleton_allocator) {
00110     singleton_allocator->destruct();
00111     delete singleton_allocator;
00112   }
00113 }
00114 
00115 
00116 
00117 void MegaTree::initTree(boost::shared_ptr<Storage> _storage, const std::vector<double>& _cell_center, const double& _cell_size,
00118                         unsigned _subtree_width, unsigned _subfolder_depth,
00119                         unsigned _cache_size, double _min_cell_size)
00120 {
00121   storage = _storage;
00122   subtree_width = _subtree_width;
00123   subfolder_depth = _subfolder_depth;
00124   max_cache_size = _cache_size;
00125   current_cache_size = 0;
00126   current_write_size = 0;
00127 
00128   // reset counters
00129   resetCount();
00130 
00131   // Pre-allocates memory for the nodes.
00132   node_allocator.reset(new Allocator<Node>(_cache_size + _cache_size / 2));
00133 
00134   // TODO: the singleton allocator is disabled for now.  The mapreduce
00135   // programs couldn't run with it enabled, and tcmalloc does a decent
00136   // job of allocating for stl containers.
00137   //
00138   // Make sure to construct singleton allocator with the correct size before any of the node files start using it
00139   singleton_allocator = NULL; //StdSingletonAllocatorInstance<std::_Rb_tree_node<std::pair<const ShortId, Node*> > >::getInstance(_cache_size + _cache_size / 5);
00140 
00141   // compute tree min and max corners
00142   assert(_cell_center.size() == 3);
00143   root_geometry = NodeGeometry(_cell_center, _cell_size);
00144   min_cell_size = _min_cell_size;
00145 
00146   printf("Created tree with min cell size: %.4f, root (%lf, %lf, %lf)--(%lf, %lf, %lf), subtree width: %d, subfolder depth: %d\n",
00147          min_cell_size,
00148          root_geometry.getLo(0), root_geometry.getLo(1), root_geometry.getLo(2),
00149          root_geometry.getHi(0), root_geometry.getHi(1), root_geometry.getHi(2),
00150          subtree_width, subfolder_depth);
00151 }
00152 
00153 
00154 
00155 
00156 void MegaTree::writeMetaData()
00157 {
00158   printf("Writing metadata of a new MegaTree\n");
00159 
00160   if (read_only)
00161   {
00162     fprintf(stderr, "You are trying to write metadata of a read-only tree\n");
00163     abort();
00164   }
00165 
00166   std::vector<double> root_center(3);
00167   root_center[0] = (root_geometry.getHi(0) + root_geometry.getLo(0)) / 2.0;
00168   root_center[1] = (root_geometry.getHi(1) + root_geometry.getLo(1)) / 2.0;
00169   root_center[2] = (root_geometry.getHi(2) + root_geometry.getLo(2)) / 2.0;
00170   MetaData metadata(version, subtree_width, subfolder_depth,
00171                     min_cell_size, root_geometry.getSize(), root_center);
00172 
00173   ByteVec data;
00174   metadata.serialize(data);
00175   storage->put("metadata.ini", data);
00176 }
00177 
00178 
00179 
00180 
00181 bool MegaTree::checkEqualRecursive(MegaTree& tree1, MegaTree& tree2, NodeHandle& node1, NodeHandle& node2)
00182 {
00183   //if these nodes are not equal, just return false
00184   printf("%s  ----   %s\n", node1.toString().c_str(), node2.toString().c_str());
00185   if(!(node1 == node2))
00186   {
00187     return false;
00188   }
00189 
00190   //if the nodes are leaves, and we know they're already equal, we can just
00191   //return true
00192   if(node1.isLeaf())
00193   {
00194     return true;
00195   }
00196 
00197   // Loops through the children and recurses
00198   for(uint8_t i = 0; i < 8; ++i)
00199   {
00200     if(node1.hasChild(i))
00201     {
00202       NodeHandle child1;
00203       tree1.getChildNode(node1, i, child1);
00204       NodeHandle child2;
00205       tree2.getChildNode(node2, i, child2);
00206 
00207       child1.waitUntilLoaded();
00208       child2.waitUntilLoaded();
00209       bool child_is_equal = checkEqualRecursive(tree1, tree2, child1, child2);
00210       tree1.releaseNode(child1);
00211       tree2.releaseNode(child2);
00212       if (!child_is_equal)
00213         return false;
00214     }
00215   }
00216 
00217   return true;
00218 }
00219 
00220 
00221 
00222 bool MegaTree::operator==(MegaTree& tree)
00223 {
00224   NodeHandle my_root;
00225   getRoot(my_root);
00226   NodeHandle other_root;
00227   tree.getRoot(other_root);
00228   bool equal = checkEqualRecursive(*this, tree, my_root, other_root);
00229   releaseNode(my_root);
00230   tree.releaseNode(other_root);
00231   return equal;
00232 }
00233 
00234 
00235 
00236 // create a new node file
00237 NodeFile* MegaTree::createNodeFile(const IdType& file_id)
00238 {
00239   // get file path
00240   std::string relative_path, filename;
00241   file_id.toPath(subfolder_depth, relative_path, filename);
00242   boost::filesystem::path path = boost::filesystem::path(relative_path) / filename;
00243 
00244   // Create a new NodeFile and add it to the cache
00245   NodeFile* file = new NodeFile(path, node_allocator);
00246   file->addUser();  // make sure file cannot get deleted in cache maintenance
00247 
00248   // The file doesn't exist, so we create it from scratch.
00249   file->deserialize();
00250 
00251   {
00252     // TODO: Don't we need to check that this file hasn't been added in the meantime by another thread?
00253     boost::mutex::scoped_lock lock(file_cache_mutex);
00254     file_cache.push_front(file_id, file);
00255   }
00256 
00257   cacheMaintenance();
00258 
00259   return file;
00260 }
00261 
00262 
00263 // internal method to get node file based on file id
00264 NodeFile* MegaTree::getNodeFile(const IdType& file_id)
00265 {
00266   NodeFile* file(NULL);
00267 
00268   {
00269     //lock the file cache
00270     boost::mutex::scoped_lock lock(file_cache_mutex);
00271 
00272     // get the file from the file cache
00273     Cache<IdType, NodeFile>::iterator it = file_cache.find(file_id);
00274     if (!it.finished())
00275     {
00276       count_hit++;
00277 
00278       file = it.get();
00279 
00280       //lock the file
00281       boost::mutex::scoped_lock file_lock(file->mutex);
00282 
00283       assert(file->getNodeState() != INVALID);
00284 
00285       //we need to check if this file is being evicted, and set the state to loading
00286       if(file->getNodeState() == EVICTING)
00287         file->setNodeState(LOADING);
00288 
00289       file->addUser();  // make sure file cannot get deleted in cache maintenance
00290 
00291       // Now that the write pointer is definitely elsewhere, moves
00292       // this file to the front on the LRU cache.
00293       file_cache.move_to_front(it);
00294     }
00295   }
00296 
00297 
00298   // The file wasn't found in the cache, so we load it from storage.
00299   if (!file)
00300   {
00301     // get file path
00302     std::string relative_path, filename;
00303     file_id.toPath(subfolder_depth, relative_path, filename);
00304     boost::filesystem::path path = boost::filesystem::path(relative_path) / filename;
00305 
00306     // create new nodefile
00307     file = new NodeFile(path, node_allocator);
00308     file->addUser();  // make sure file cannot get deleted in cache maintenance
00309 
00310     // Async request to read the nodefile
00311     storage->getAsync(path, boost::bind(&MegaTree::readNodeFileCb, this, file, _1));
00312 
00313     // add nodefile to cache
00314     {
00315       boost::mutex::scoped_lock lock(file_cache_mutex);
00316       file_cache.push_front(file_id, file);
00317     }
00318     count_miss++;
00319   }
00320 
00321   return file;
00322 }
00323 
00324 
00325 // Allow the node file to get deleted in cache maintenance
00326 void MegaTree::releaseNodeFile(NodeFile*& node_file)
00327 {
00328   boost::mutex::scoped_lock lock(node_file->mutex);
00329   node_file->removeUser();
00330 }
00331 
00332 
00333 
00334 NodeHandle* MegaTree::createChildNode(NodeHandle& parent_node, uint8_t child)
00335 {
00336   NodeHandle* nh = new NodeHandle;
00337   createChildNode(parent_node, child, *nh);
00338   return nh;
00339 }
00340 
00341 
00342 // Create a new node that does not exist yet
00343 void MegaTree::createChildNode(NodeHandle& parent_node, uint8_t child, NodeHandle& child_node_handle)
00344 {
00345   // get child info
00346   assert(!parent_node.hasChild(child));
00347 
00348   IdType child_id = parent_node.getId().getChild(child);
00349   IdType child_file_id = getFileId(child_id);
00350   NodeGeometry child_geometry = parent_node.getNodeGeometry().getChild(child);
00351 
00352   // Checks if the child node file exists.  If it doesn't exist, then
00353   // we don't need to hit storage to load it.
00354   NodeFile* child_file = NULL;
00355   IdType parent_file_id = getFileId(parent_node.getId());
00356   NodeFile* parent_node_file = getNodeFile(parent_file_id);
00357   parent_node_file->waitUntilLoaded();
00358   assert(parent_node_file->getNodeState() == LOADED);
00359 
00360   // Checks if the child file exists, without going to disk
00361   uint8_t which_child_file = child_file_id.getChildNr();
00362   if (child_file_id.isRootFile() || parent_node_file->hasChildFile(which_child_file))
00363   {
00364     child_file = getNodeFile(child_file_id);
00365     child_file->waitUntilLoaded();  // always blocking for creating nodes
00366   }
00367   else
00368   {
00369     // Fast creation for non-existant node files.
00370     child_file = createNodeFile(child_file_id);
00371     // tell parent file it has a new child file
00372     parent_node_file->setChildFile(which_child_file);
00373   }
00374   releaseNodeFile(parent_node_file);
00375 
00376   // tell parent node it has a new child node
00377   parent_node.setChild(child);
00378 
00379   // create new node and node handle
00380   Node* child_node = child_file->createNode(getShortId(child_id));
00381   child_node_handle.initialize(child_node, child_id, child_file, child_geometry);
00382 
00383   current_cache_size++;
00384 
00385   releaseNodeFile(child_file);  // we have a Node from this file, so unlock file
00386 }
00387 
00388 NodeHandle* MegaTree::getChildNode(const NodeHandle& parent_node, uint8_t child)
00389 {
00390   NodeHandle* nh = new NodeHandle;
00391   getChildNode(parent_node, child, *nh);
00392   return nh;
00393 }
00394 
00395 // Get a child node form a parent node
00396 void MegaTree::getChildNode(const NodeHandle& parent_node, uint8_t child, NodeHandle& child_node_handle)
00397 {
00398   // get child info
00399   assert(parent_node.hasChild(child));
00400   IdType child_id = parent_node.getId().getChild(child);
00401   IdType child_file_id = getFileId(child_id);
00402   NodeGeometry child_geometry = parent_node.getNodeGeometry().getChild(child);
00403 
00404   // retrieve the child from the nodefile
00405   NodeFile* child_file = getNodeFile(child_file_id);
00406 
00407   // unlock file after we got a node from the file
00408   Node* child_node = NULL;
00409   {
00410     boost::mutex::scoped_lock lock(child_file->mutex);
00411     child_node = child_file->readNode(getShortId(child_id));
00412   }
00413   child_node_handle.initialize(child_node, child_id, child_file, child_geometry);
00414 
00415   // DEBUGGING CODE
00416   if (!child_file_id.isRootFile())
00417   {
00418     const NodeFile* parent_file = parent_node.getNodeFile();
00419     unsigned which_child_file = child_file_id.getChildNr();
00420     if (!parent_file->hasChildFile(which_child_file))
00421     {
00422     fprintf(stderr, "Parent file of %s does not know is has child nr %d, child id is %s\n",
00423             child_file_id.toString().c_str(), which_child_file, child_id.toString().c_str());
00424     }
00425   }
00426 
00427 
00428   releaseNodeFile(child_file);
00429 }
00430 
00431 
00432 
00433 void MegaTree::releaseNode(NodeHandle& node_handle)
00434 {
00435   if(!node_handle.hasNode())
00436   {
00437     fprintf(stderr, "Trying to release a node_handle that doesn't have a node\n");
00438   }
00439   else
00440   {
00441 
00442     boost::mutex::scoped_lock lock(node_handle.getNodeFile()->mutex);
00443     // release node inside nodehandle
00444     node_handle.getNodeFile()->releaseNode(node_handle.getNode(), getShortId(node_handle.getId()), node_handle.isModified());
00445   }
00446 
00447   // Invalidates the NodeHandle
00448   node_handle.invalidate();
00449 }
00450 
00451 
00452 
00453 
00454 
00455 void MegaTree::flushCache()
00456 {
00457   boost::mutex::scoped_lock lock(file_cache_mutex);
00458   boost::condition condition;
00459   boost::mutex mutex;
00460 
00461   // iterate over all files, and write data
00462   printf("Flushing %d files...\n", (int)file_cache.size());
00463   unsigned remaining = 0;
00464   for (CacheIterator<IdType, NodeFile> file_it = file_cache.iterate(); !file_it.finished(); file_it.next())
00465   {
00466     //The file needs to be locked when it is written
00467     boost::mutex::scoped_lock file_lock(file_it.get()->mutex);
00468 
00469     if (file_it.get()->getNodeState() != LOADING && file_it.get()->isModified())
00470     {
00471       if (read_only)
00472       {
00473         fprintf(stderr, "You are trying to write node files of a read-only tree\n");
00474         abort();
00475       }
00476 
00477       {
00478         boost::mutex::scoped_lock remaining_lock(mutex);
00479         remaining++;
00480       }
00481 
00482       // get data to write
00483       ByteVec byte_data;
00484       file_it.get()->serialize(byte_data);
00485 
00486       // start asynchronous writing
00487       storage->putAsync(file_it.get()->getPath(), byte_data,
00488                         boost::bind(&MegaTree::flushNodeFileCb, this, file_it, boost::ref(mutex), boost::ref(condition), boost::ref(remaining)));
00489     }
00490   }
00491 
00492   // wait for async writing to finish
00493   boost::mutex::scoped_lock remaining_lock(mutex);
00494   if (remaining > 0)
00495     condition.wait(remaining_lock);
00496 
00497   printf("Finished flushing %d files\n", (int)file_cache.size());
00498 }
00499 
00500 
00501 
00502 //manage the cache
00503 void MegaTree::cacheMaintenance()
00504 {
00505   //A list of node files that we want to be written
00506   std::vector<CacheIterator<IdType, NodeFile> > write_list;
00507 
00508   {
00509     // Locks the file cache
00510     boost::mutex::scoped_lock lock(file_cache_mutex);
00511 
00512     // Starts evicting at the back of the LRU cache.
00513     Cache<IdType, NodeFile>::iterator it = file_cache.iterateBack();
00514 
00515     // How many nodes we need to evict
00516     int number_to_evict = current_cache_size - max_cache_size - current_write_size;
00517     int number_evicted = 0;
00518 
00519     //we want to remove nodes from the cache until we're under our overflow
00520     while(!it.finished() && number_to_evict > number_evicted)
00521     {
00522       NodeFile* delete_file(NULL);
00523       {
00524         boost::mutex::scoped_try_lock file_lock(it.get()->mutex);
00525         //if the file is unavailable for eviction, we'll just skip it
00526         if(!file_lock || it.get()->getNodeState() != LOADED || it.get()->users() > 0)
00527         {
00528           // skip file
00529           it.previous();
00530         }
00531         else if(!it.get()->isModified())
00532         {
00533           // immediately evict file
00534           delete_file = it.get();  // postpone delete
00535           current_cache_size -= it.get()->cacheSize();
00536           number_evicted += it.get()->cacheSize();
00537           Cache<IdType, NodeFile>::iterator evicted_it = it;
00538           it.previous();
00539           file_cache.erase(evicted_it);
00540         }
00541         else
00542         {
00543           if (read_only)
00544           {
00545             fprintf(stderr, "You are trying to write node files of a read-only tree\n");
00546             abort();
00547           }
00548 
00549           // start evicting this file
00550           it.get()->setNodeState(EVICTING);
00551 
00552           // get data to write
00553           ByteVec byte_data;
00554           it.get()->serialize(byte_data);
00555 
00556           // Start asynchronous writing
00557           number_evicted += it.get()->cacheSize();
00558           current_write_size += it.get()->cacheSize();
00559           storage->putAsync(it.get()->getPath(), byte_data, boost::bind(&MegaTree::evictNodeFileCb, this, it));
00560           it.previous();
00561         }
00562       }
00563       if (delete_file)
00564         delete delete_file;
00565     }
00566 
00567     if(number_to_evict >= number_evicted && it.finished())
00568     {
00569       fprintf(stderr, "We are out of space in our cache but cannot evict any more\n");
00570       abort();
00571     }
00572   }
00573 }
00574 
00575 
00576 
00577 
00578 // get the file_id and node short_id from the node_id
00579 IdType MegaTree::getFileId(const IdType& node_id)
00580 {
00581   return node_id.getParent(subtree_width);
00582 }
00583 
00584 
00585 ShortId MegaTree::getShortId(const IdType& node_id)
00586 {
00587   unsigned shift = std::min(node_id.level(), subtree_width);
00588   return node_id.getBits(shift*3);
00589 }
00590 
00591 
00592 void MegaTree::createRoot(NodeHandle &root_node_handle)
00593 {
00594   // get root node info
00595   IdType root_id = IdType(1L);
00596   IdType root_file_id = getFileId(root_id);
00597 
00598   // the nodefile will create an pointer for this child
00599   NodeFile* root_file = createNodeFile(root_file_id);
00600   Node* root_node = root_file->createNode(getShortId(root_id));
00601   assert(getShortId(root_id) == 1);
00602 
00603   root_node_handle.initialize(root_node, root_id, root_file, root_geometry);
00604 
00605   current_cache_size++;
00606   root_file->removeUser();
00607 }
00608 
00609 void MegaTree::getRoot(NodeHandle &root_node_handle)
00610 {
00611   // get root node info
00612   IdType root_id = IdType(1L);
00613   IdType root_file_id = getFileId(root_id);
00614 
00615   // retrieve the root node from the nodefile
00616   NodeFile* root_file = getNodeFile(root_file_id);
00617   root_file->waitUntilLoaded();    // always blocking
00618 
00619   Node* root_node = NULL;
00620   {
00621     boost::mutex::scoped_lock lock(root_file->mutex);
00622     root_node = root_file->readNode(getShortId(root_id));
00623   }
00624 
00625   root_node_handle.initialize(root_node, root_id, root_file, root_geometry);
00626   root_file->removeUser();
00627 }
00628 
00629 NodeHandle* MegaTree::getRoot()
00630 {
00631   NodeHandle* nh = new NodeHandle;
00632   getRoot(*nh);
00633   return nh;
00634 }
00635 
00636 void MegaTree::dumpNodesInUse()
00637 {
00638   boost::mutex::scoped_lock lock(file_cache_mutex);
00639 
00640   printf("Nodes in use:\n");
00641   for (Cache<IdType, NodeFile>::ObjListIterator it(file_cache.list_.frontIterator()); !it.finished(); it.next())
00642   {
00643     if (it.get().object->users() > 0) {
00644       printf("    %3d %s\n", it.get().object->users(), it.get().id.toString().c_str());
00645     }
00646   }
00647 }
00648 
00649 
00650 
00651 void MegaTree::flushNodeFileCb(CacheIterator<IdType, NodeFile> it, boost::mutex& mutex, boost::condition& condition, unsigned& remaining)
00652 {
00653   // Locks the node file
00654   boost::mutex::scoped_lock file_lock(it.get()->mutex);
00655 
00656   // File is written
00657   it.get()->setWritten();
00658   count_file_write++;
00659 
00660   // Locks the remaining count
00661   boost::mutex::scoped_lock lock(mutex);
00662   remaining--;
00663   if (remaining == 0)
00664     condition.notify_one();
00665 }
00666 
00667 
00668 
00669 void MegaTree::evictNodeFileCb(CacheIterator<IdType, NodeFile> it)
00670 {
00671   NodeFile* delete_file(NULL);
00672   {
00673     // Locks the cache
00674     boost::mutex::scoped_lock lock(file_cache_mutex);
00675 
00676     // Locks the node file
00677     boost::mutex::scoped_lock file_lock(it.get()->mutex);
00678     NodeState state = it.get()->getNodeState();
00679 
00680     // File is written
00681     assert(it.get()->isModified());
00682     it.get()->setWritten();
00683     count_file_write++;
00684 
00685 
00686     // File is no longer in use.  Removes it from the cache.
00687     if (state == EVICTING)
00688     {
00689       it.get()->setNodeState(INVALID);
00690       delete_file = it.get();  // postpone delete
00691 
00692       // update file cache
00693       current_cache_size -= it.get()->cacheSize();
00694       current_write_size -= it.get()->cacheSize();
00695       file_cache.erase(it);
00696     }
00697 
00698     // The file was requested again while we were writing it.  Returns the file to the loaded state.
00699     else
00700     {
00701       assert(state == LOADING);
00702       it.get()->setNodeState(LOADED);
00703 
00704       // update file cache
00705       boost::mutex::scoped_lock lock(file_cache_mutex);
00706       current_write_size -= it.get()->cacheSize();
00707     }
00708   }
00709 
00710   if (delete_file)
00711     delete delete_file; // delete pointer outside of node file lock
00712 
00713 }
00714 
00715 
00716 
00717 void MegaTree::readNodeFileCb(NodeFile* node_file, const ByteVec& buffer)
00718 {
00719   {
00720     boost::mutex::scoped_lock lock(node_file->mutex);
00721     node_file->deserialize(buffer);
00722     current_cache_size += node_file->cacheSize();
00723   }
00724   cacheMaintenance();
00725 }
00726 
00727 
00728 
00729 }


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