Go to the documentation of this file.00001 #ifndef MEGATREE_TREE_FUNCTIONS_H
00002 #define MEGATREE_TREE_FUNCTIONS_H
00003
00004 #include <vector>
00005 #include <boost/shared_ptr.hpp>
00006
00007 #include "megatree/node.h"
00008 #include "megatree/megatree.h"
00009
00010 #define __STDC_FORMAT_MACROS
00011 #include <inttypes.h>
00012 #include <stdio.h>
00013
00014 namespace megatree
00015 {
00016 void addPoint(MegaTree &tree, const std::vector<double> &pt, const std::vector<double>& color = std::vector<double>(3, 0));
00017
00018
00019 void queryRange(MegaTree &tree, const std::vector<double>& lo, const std::vector<double>&hi,
00020 double resolution, std::vector<double> &results, std::vector<double> &colors);
00021
00022 void numChildren(MegaTree& tree, NodeHandle* node, unsigned count_cutoff, unsigned& num_children, unsigned& count);
00023 void dumpTimers();
00024
00025 void queryRangeIntersecting(MegaTree &tree, NodeHandle& node,
00026 const double* range_mid, const double* range_size,
00027 std::vector<double> &results, std::vector<double> &colors);
00028
00029 bool nodeInsideRange(const NodeGeometry& node_geom, const double* range_mid, const double* range_size);
00030 bool nodeOutsideRange(const NodeGeometry& node_geom, const double* range_mid, const double* range_size);
00031
00032
00033 void rangeQueryLoop(MegaTree& tree, std::vector<double> lo, std::vector<double> hi,
00034 double resolution, std::vector<double>& results, std::vector<double>& colors);
00035
00036
00037
00038
00039 class NodeCache
00040 {
00041 public:
00042 NodeCache(NodeHandle* nh_p)
00043 : nh(nh_p)
00044 {
00045
00046 orig_cnt = nh->getCount();
00047 Point* pnt = nh->getNode()->point;
00048 Color* col = nh->getNode()->color;
00049 for (unsigned i=0; i<3; i++){
00050 orig_pnt[i] = pnt[i];
00051 orig_col[i] = col[i];
00052 }
00053 }
00054
00055 NodeCache(const NodeCache& nc)
00056 {
00057 nh = nc.nh;
00058 orig_cnt= nc.orig_cnt;
00059
00060 for (unsigned i=0; i<3; i++){
00061 orig_pnt[i] = nc.orig_pnt[i];
00062 orig_col[i] = nc.orig_col[i];
00063 }
00064 }
00065
00066 NodeCache& operator =(const NodeCache& nc)
00067 {
00068 nh = nc.nh;
00069 orig_cnt= nc.orig_cnt;
00070
00071 for (unsigned i=0; i<3; i++){
00072 orig_pnt[i] = nc.orig_pnt[i];
00073 orig_col[i] = nc.orig_col[i];
00074 }
00075 return *this;
00076 }
00077
00078
00079 ~NodeCache()
00080 {
00081 }
00082
00083
00084
00085 void release(MegaTree& tree)
00086 {
00087 tree.releaseNode(*nh);
00088 delete nh;
00089 nh = NULL;
00090 }
00091
00092
00093 void mergeChild(const NodeCache& nc)
00094 {
00095 assert(nc.nh);
00096 assert(nh);
00097
00098
00099 uint64_t child_offset[3];
00100 nh->getNode()->getChildBitOffset(nc.nh->getId().getChildNr(), child_offset);
00101
00102
00103 uint64_t child_cnt_curr = nc.nh->getCount();
00104 uint64_t diff_sum_pnt[3], diff_sum_col[3];
00105 uint64_t diff_cnt = child_cnt_curr-nc.orig_cnt;
00106 for (unsigned i=0; i<3; i++){
00107 diff_sum_pnt[i] = nc.nh->getNode()->point[i]*child_cnt_curr - nc.orig_pnt[i]*nc.orig_cnt + child_offset[i]*diff_cnt;
00108 diff_sum_col[i] = nc.nh->getNode()->color[i]*child_cnt_curr - nc.orig_col[i]*nc.orig_cnt;
00109 }
00110
00111
00112 Point* pnt = nh->getNode()->point;
00113 Color* col = nh->getNode()->color;
00114 uint64_t& cnt = nh->getNode()->count;
00115 for (unsigned i=0; i<3; i++){
00116 pnt[i] = (pnt[i]*cnt + diff_sum_pnt[i]) / (cnt + diff_cnt);
00117 col[i] = (col[i]*cnt + diff_sum_col[i]) / (cnt + diff_cnt);
00118 }
00119 cnt += diff_cnt;
00120 }
00121
00122
00123 NodeHandle* nh;
00124 uint64_t orig_pnt[3];
00125 uint64_t orig_col[3];
00126 uint64_t orig_cnt;
00127 };
00128
00129
00130
00131
00132 class TreeFastCache
00133 {
00134 public:
00135 TreeFastCache(MegaTree &tree_p):
00136 tree(tree_p)
00137 {
00138 push(NodeCache(tree.getRoot()));
00139 }
00140
00141 ~TreeFastCache()
00142 {
00143 while (!nodes.empty())
00144 pop();
00145 }
00146
00147 void clear()
00148 {
00149 while (!nodes.empty())
00150 pop();
00151
00152 push(NodeCache(tree.getRoot()));
00153 }
00154
00155 void addPoint(std::vector<double> &pt, const std::vector<double>& color = std::vector<double>(3, 0));
00156
00157
00158 private:
00159 NodeCache& top()
00160 {
00161 assert(!nodes.empty());
00162 return nodes.top();
00163 }
00164
00165 void push(NodeCache nc)
00166 {
00167 nodes.push(nc);
00168 }
00169
00170 void pop()
00171 {
00172 assert(!nodes.empty());
00173
00174 NodeCache child = nodes.top();
00175 nodes.pop();
00176 if (!nodes.empty())
00177 nodes.top().mergeChild(child);
00178
00179 child.release(tree);
00180 }
00181
00182 void addPointRecursive(const double pt[3], const double color[3], double point_accuracy);
00183
00184 std::stack<NodeCache> nodes;
00185 MegaTree& tree;
00186 };
00187
00188
00189
00190 }
00191
00192 #endif