Classes | Public Member Functions | Private Member Functions | Private Attributes
megatree::MegaTree Class Reference

#include <megatree.h>

List of all members.

Classes

class  ChildIterator

Public Member Functions

void createChildNode (NodeHandle &parent_node, uint8_t child, NodeHandle &child_node)
NodeHandlecreateChildNode (NodeHandle &parent_node, uint8_t child)
void dumpNodesInUse ()
void flushCache ()
void getChildNode (const NodeHandle &parent_node, uint8_t child, NodeHandle &child_node)
NodeHandlegetChildNode (const NodeHandle &parent_node, uint8_t child)
IdType getFileId (const IdType &node_id)
double getMinCellSize () const
unsigned long getNumPoints ()
void getRoot (NodeHandle &root_node)
NodeHandlegetRoot ()
const NodeGeometrygetRootGeometry () const
ShortId getShortId (const IdType &node_id)
 MegaTree (boost::shared_ptr< Storage > storage, unsigned cache_size, bool read_only)
 MegaTree (boost::shared_ptr< Storage > storage, const std::vector< double > &cell_center, const double &cell_size, unsigned subtree_width, unsigned subfolder_depth, unsigned cache_size=CACHE_SIZE, double _min_cell_size=MIN_CELL_SIZE)
bool operator== (MegaTree &tree)
void recenter (double x, double y, double z)
void releaseNode (NodeHandle &node)
void resetCount ()
std::string toString ()
 ~MegaTree ()

Private Member Functions

void cacheMaintenance ()
unsigned cacheSize () const
bool checkEqualRecursive (MegaTree &tree1, MegaTree &tree2, NodeHandle &node1, NodeHandle &node2)
NodeFilecreateNodeFile (const IdType &file_id)
void createRoot (NodeHandle &root)
void evictNodeFileCb (CacheIterator< IdType, NodeFile > it)
void flushNodeFileCb (CacheIterator< IdType, NodeFile > it, boost::mutex &mutex, boost::condition &condition, unsigned &remaining)
NodeFilegetNodeFile (const IdType &file_id)
void initTree (boost::shared_ptr< Storage > storage, const std::vector< double > &_cell_center, const double &_cell_size, unsigned _subtree_width, unsigned _subfolder_depth, unsigned _cache_size, double _min_cell_size)
void readNodeFileCb (NodeFile *node_file, const ByteVec &buffer)
void releaseNodeFile (NodeFile *&node_file)
void writeMetaData ()

Private Attributes

unsigned count_file_write
unsigned count_hit
unsigned count_miss
unsigned count_nodes_read
unsigned current_cache_size
unsigned current_write_size
Cache< IdType, NodeFilefile_cache
boost::mutex file_cache_mutex
unsigned max_cache_size
double min_cell_size
boost::shared_ptr< Allocator
< Node > > 
node_allocator
bool read_only
NodeGeometry root_geometry
StdSingletonAllocatorInstance
< std::_Rb_tree_node
< std::pair< const ShortId,
Node * > > > * 
singleton_allocator
boost::shared_ptr< Storagestorage
unsigned subfolder_depth
unsigned subtree_width

Detailed Description

Definition at line 33 of file megatree.h.


Constructor & Destructor Documentation

megatree::MegaTree::MegaTree ( boost::shared_ptr< Storage storage,
unsigned  cache_size,
bool  read_only 
)

Definition at line 20 of file megatree.cpp.

megatree::MegaTree::MegaTree ( boost::shared_ptr< Storage storage,
const std::vector< double > &  cell_center,
const double &  cell_size,
unsigned  subtree_width,
unsigned  subfolder_depth,
unsigned  cache_size = CACHE_SIZE,
double  _min_cell_size = MIN_CELL_SIZE 
)

Definition at line 50 of file megatree.cpp.

Definition at line 67 of file megatree.cpp.


Member Function Documentation

Definition at line 503 of file megatree.cpp.

unsigned megatree::MegaTree::cacheSize ( ) const [inline, private]

Definition at line 122 of file megatree.h.

bool megatree::MegaTree::checkEqualRecursive ( MegaTree tree1,
MegaTree tree2,
NodeHandle node1,
NodeHandle node2 
) [private]

Definition at line 181 of file megatree.cpp.

void megatree::MegaTree::createChildNode ( NodeHandle parent_node,
uint8_t  child,
NodeHandle child_node 
)

Definition at line 343 of file megatree.cpp.

NodeHandle * megatree::MegaTree::createChildNode ( NodeHandle parent_node,
uint8_t  child 
)

Definition at line 334 of file megatree.cpp.

NodeFile * megatree::MegaTree::createNodeFile ( const IdType file_id) [private]

Definition at line 237 of file megatree.cpp.

void megatree::MegaTree::createRoot ( NodeHandle root) [private]

Definition at line 592 of file megatree.cpp.

Definition at line 636 of file megatree.cpp.

Definition at line 669 of file megatree.cpp.

Definition at line 455 of file megatree.cpp.

void megatree::MegaTree::flushNodeFileCb ( CacheIterator< IdType, NodeFile it,
boost::mutex &  mutex,
boost::condition &  condition,
unsigned &  remaining 
) [private]

Definition at line 651 of file megatree.cpp.

void megatree::MegaTree::getChildNode ( const NodeHandle parent_node,
uint8_t  child,
NodeHandle child_node 
)

Definition at line 396 of file megatree.cpp.

NodeHandle * megatree::MegaTree::getChildNode ( const NodeHandle parent_node,
uint8_t  child 
)

Definition at line 388 of file megatree.cpp.

Definition at line 579 of file megatree.cpp.

double megatree::MegaTree::getMinCellSize ( ) const [inline]

Definition at line 102 of file megatree.h.

NodeFile * megatree::MegaTree::getNodeFile ( const IdType file_id) [private]

Definition at line 264 of file megatree.cpp.

unsigned long megatree::MegaTree::getNumPoints ( ) [inline]

Definition at line 73 of file megatree.h.

void megatree::MegaTree::getRoot ( NodeHandle root_node)

Definition at line 609 of file megatree.cpp.

Definition at line 629 of file megatree.cpp.

Definition at line 96 of file megatree.h.

Definition at line 585 of file megatree.cpp.

void megatree::MegaTree::initTree ( boost::shared_ptr< Storage storage,
const std::vector< double > &  _cell_center,
const double &  _cell_size,
unsigned  _subtree_width,
unsigned  _subfolder_depth,
unsigned  _cache_size,
double  _min_cell_size 
) [private]

Definition at line 117 of file megatree.cpp.

bool megatree::MegaTree::operator== ( MegaTree tree)

Definition at line 222 of file megatree.cpp.

void megatree::MegaTree::readNodeFileCb ( NodeFile node_file,
const ByteVec buffer 
) [private]

Definition at line 717 of file megatree.cpp.

void megatree::MegaTree::recenter ( double  x,
double  y,
double  z 
) [inline]

Definition at line 106 of file megatree.h.

Definition at line 433 of file megatree.cpp.

void megatree::MegaTree::releaseNodeFile ( NodeFile *&  node_file) [private]

Definition at line 326 of file megatree.cpp.

void megatree::MegaTree::resetCount ( ) [inline]

Definition at line 67 of file megatree.h.

std::string megatree::MegaTree::toString ( ) [inline]

Definition at line 83 of file megatree.h.

Definition at line 156 of file megatree.cpp.


Member Data Documentation

Definition at line 168 of file megatree.h.

unsigned megatree::MegaTree::count_hit [private]

Definition at line 168 of file megatree.h.

unsigned megatree::MegaTree::count_miss [private]

Definition at line 168 of file megatree.h.

Definition at line 168 of file megatree.h.

Definition at line 158 of file megatree.h.

Definition at line 159 of file megatree.h.

Definition at line 157 of file megatree.h.

boost::mutex megatree::MegaTree::file_cache_mutex [private]

Definition at line 156 of file megatree.h.

Definition at line 164 of file megatree.h.

Definition at line 162 of file megatree.h.

boost::shared_ptr<Allocator<Node> > megatree::MegaTree::node_allocator [private]

Definition at line 165 of file megatree.h.

Definition at line 170 of file megatree.h.

Definition at line 163 of file megatree.h.

StdSingletonAllocatorInstance<std::_Rb_tree_node<std::pair<const ShortId, Node*> > >* megatree::MegaTree::singleton_allocator [private]

Definition at line 166 of file megatree.h.

boost::shared_ptr<Storage> megatree::MegaTree::storage [private]

Definition at line 153 of file megatree.h.

Definition at line 164 of file megatree.h.

Definition at line 164 of file megatree.h.


The documentation for this class was generated from the following files:


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