Boctree.h
Go to the documentation of this file.
1 
9 #ifndef BOCTREE_H
10 #define BOCTREE_H
11 
12 #include "searchTree.h"
13 #include "point_type.h"
14 #include "data_types.h"
15 #include "allocator.h"
16 #include "limits.h"
17 #include "nnparams.h"
18 #include "globals.icc"
19 
20 
21 #include <stdio.h>
22 
23 #include <vector>
24 using std::vector;
25 #include <deque>
26 using std::deque;
27 #include <set>
28 using std::set;
29 #include <list>
30 using std::list;
31 #include <iostream>
32 #include <fstream>
33 #include <string>
34 
35 #if __GNUC__ > 3 || (__GNUC__ == 3 && __GNUC_MINOR__ >= 4)
36  #define POPCOUNT(mask) __builtin_popcount(mask)
37 #else
38  #define POPCOUNT(mask) _my_popcount_3(mask)
39 #endif
40 
41 #include <boost/interprocess/offset_ptr.hpp> // to avoid ifdeffing for offset_ptr.get(), use &(*ptr)
42 namespace { namespace ip = boost::interprocess; }
43 
44 
45 // forward declaration
46 template <class T> union bitunion;
47 
53 template <class T> union dunion {
54  T v;
55  unsigned int length;
56  dunion() : length(0) {};
57 
58 };
59 // typedefs in combination with templates are weird
60 //typedef dunion<T> pointrep<T>;
61 #define pointrep union dunion<T>
62 
63 
64 
65 
82 class bitoct{
83  public:
84 
85 #ifdef _MSC_VER
86  __int64 child_pointer : 48;
87  unsigned valid : 8;
88  unsigned leaf : 8;
89 #else
90  signed long child_pointer : 48;
91  unsigned valid : 8;
92  unsigned leaf : 8;
93 #endif
94 
97  template <class T>
98  static inline void link(bitoct &parent, bitunion<T> *child) {
99  parent.child_pointer = (long)((char*)child - (char*)&parent);
100  }
101 
105  template <class T>
106  static inline void getChildren(const bitoct &parent, bitunion<T>* &children) {
107  children = (bitunion<T>*)((char*)&parent + parent.child_pointer);
108  }
109 
110  template <class T>
111  inline bitunion<T>* getChild(unsigned char index) {
112  bitunion<T> *children = (bitunion<T>*)((char*)this + this->child_pointer);
113  for (unsigned char i = 0; i < index; i++) {
114  if ( ( 1 << i ) & valid ) { // if ith node exists
115  children++;
116  }
117  }
118  return children;
119  }
120 };
121 
122 
132 template <class T> union bitunion {
134  //union dunion<T> *points;
136 
138  bitunion(bitoct b) : node(b) {};
139  bitunion() : points(0) {
140  node.child_pointer = 0;
141  node.valid = 0;
142  node.leaf = 0;
143  }; // needed for new []
144 
146  static inline void link(bitunion<T>* leaf, pointrep* points) {
147  // use node child_pointer as offset_ptr, not pointrep
148  leaf->node.child_pointer = (long)((char*)points - (char*)leaf);
149  }
150 
152  inline T* getPoints() const {
153  // absolute pointer
154  //return &(this->points[1].v);
155  // offset pointer
156  return reinterpret_cast<T*>(
157  reinterpret_cast<pointrep*>((char*)this + node.child_pointer) + 1
158  );
159  }
160 
162  inline unsigned int getLength() const {
163  // absolute pointer
164  //return this->points[0].length;
165  // offset pointer
166  return (reinterpret_cast<pointrep*>((char*)this + node.child_pointer))[0].length;
167  }
168 
170  inline pointrep* getPointreps() const {
171  return reinterpret_cast<pointrep*>((char*)this + node.child_pointer);
172  }
173 
174  inline bitunion<T>* getChild(unsigned char index) const {
175  bitunion<T> *children = (bitunion<T>*)((char*)this + this->node.child_pointer);
176  for (unsigned char i = 0; i < index; i++) {
177  if ( ( 1 << i ) & node.valid ) { // if ith node exists
178  children++;
179  }
180  }
181  return children;
182  }
183 
184  inline bool isValid(unsigned char index) {
185  return ( ( 1 << index ) & node.valid );
186  }
187  /*
188  inline pointrep* getChild(unsigned char index) {
189  bitunion<T> *children = (bitunion<T>*)((char*)this + this->node.child_pointer);
190  return children[index].points;
191  }*/
192 
193  inline bool childIsLeaf(unsigned char index) {
194  return ( ( 1 << index ) & node.leaf ); // if ith node is leaf get center
195  }
196 };
197 
198 
199 // initialized in Boctree.cc, sequence intialized on startup
200 extern char amap[8][8];
201 extern char imap[8][8];
202 extern char sequence2ci[8][256][8]; // maps preference to index in children array for every valid_mask and every case
203 
204 
205 
214 template <typename T>
215 class BOctTree : public SearchTree {
216 public:
218  }
219 
220  template <class P>
221  BOctTree(P * const* pts, int n, T voxelSize, PointType _pointtype = PointType(), bool _earlystop = false ) : pointtype(_pointtype), earlystop(_earlystop)
222  {
224 
225  this->voxelSize = voxelSize;
226 
227  this->POINTDIM = pointtype.getPointDim();
228 
229  mins = alloc->allocate<T>(POINTDIM);
230  maxs = alloc->allocate<T>(POINTDIM);
231 
232  // initialising
233  for (unsigned int i = 0; i < POINTDIM; i++) {
234  mins[i] = pts[0][i];
235  maxs[i] = pts[0][i];
236  }
237 
238  for (unsigned int i = 0; i < POINTDIM; i++) {
239  for (int j = 1; j < n; j++) {
240  mins[i] = min(mins[i], (T)pts[j][i]);
241  maxs[i] = max(maxs[i], (T)pts[j][i]);
242  }
243  }
244 
245  center[0] = 0.5 * (mins[0] + maxs[0]);
246  center[1] = 0.5 * (mins[1] + maxs[1]);
247  center[2] = 0.5 * (mins[2] + maxs[2]);
248  size = max(max(0.5 * (maxs[0] - mins[0]), 0.5 * (maxs[1] - mins[1])), 0.5 * (maxs[2] - mins[2]));
249  size += 1.0; // for numerical reasons we increase size
250 
251  // calculate new buckets
252  T newcenter[8][3];
253  T sizeNew = size / 2.0;
254 
255  for (unsigned char i = 0; i < 8; i++) {
256  childcenter(center, newcenter[i], size, i);
257  }
258  // set up values
260  root = &uroot->node;
261 
262  countPointsAndQueueFast(pts, n, newcenter, sizeNew, *root, center);
263  init();
264  }
265 
266  BOctTree(std::string filename) {
269  init();
270  }
271 
272  template <class P>
273  BOctTree(vector<P *> &pts, T voxelSize, PointType _pointtype = PointType(), bool _earlystop = false) : earlystop(_earlystop)
274  {
276 
277  this->voxelSize = voxelSize;
278 
279  this->POINTDIM = pointtype.getPointDim();
280 
281  mins = alloc->allocate<T>(POINTDIM);
282  maxs = alloc->allocate<T>(POINTDIM);
283 
284  // initialising
285  for (unsigned int i = 0; i < POINTDIM; i++) {
286  mins[i] = pts[0][i];
287  maxs[i] = pts[0][i];
288  }
289 
290  for (unsigned int i = 0; i < POINTDIM; i++) {
291  for (unsigned int j = 1; j < pts.size(); j++) {
292  mins[i] = min(mins[i], pts[j][i]);
293  maxs[i] = max(maxs[i], pts[j][i]);
294  }
295  }
296 
297  center[0] = 0.5 * (mins[0] + maxs[0]);
298  center[1] = 0.5 * (mins[1] + maxs[1]);
299  center[2] = 0.5 * (mins[2] + maxs[2]);
300  size = max(max(0.5 * (maxs[0] - mins[0]), 0.5 * (maxs[1] - mins[1])), 0.5 * (maxs[2] - mins[2]));
301 
302  size += 1.0; // for numerical reasons we increase size
303 
304  // calculate new buckets
305  T newcenter[8][3];
306  T sizeNew = size / 2.0;
307 
308  for (unsigned char i = 0; i < 8; i++) {
309  childcenter(center, newcenter[i], size, i);
310  }
311  // set up values
313  root = &uroot->node;
314 
315  countPointsAndQueue(pts, newcenter, sizeNew, *root, center);
316  }
317 
318  virtual ~BOctTree()
319  {
320  if(alloc) {
321  delete alloc;
322  }
323  }
324 
325  void init() {
326  // compute maximal depth as well as the size of the smalles leaf
328  max_depth = 1;
329  while (real_voxelSize > voxelSize) {
331  max_depth++;
332  }
333 
334  child_bit_depth = alloc->allocate<unsigned int>(max_depth);
335  child_bit_depth_inv = alloc->allocate<unsigned int>(max_depth);
336 
337  for(int d=0; d < max_depth; d++) {
338  child_bit_depth[d] = 1 << (max_depth - d - 1);
340  }
341 
342  mult = 1.0/real_voxelSize;
343  add[0] = -center[0] + size;
344  add[1] = -center[1] + size;
345  add[2] = -center[2] + size;
346 
347  largest_index = child_bit_depth[0] * 2 -1;
348  }
349 
350 protected:
351 
355  ip::offset_ptr<bitoct> root;
357  ip::offset_ptr<bitunion<T> > uroot;
358 
360  T center[3];
361 
363  T size;
364 
367 
370 
372  T add[3];
373  T mult;
374 
376  unsigned int POINTDIM;
377 
379  ip::offset_ptr<T> mins;
380  ip::offset_ptr<T> maxs;
381 
384 
386  unsigned char max_depth;
387  ip::offset_ptr<unsigned int> child_bit_depth;
388  ip::offset_ptr<unsigned int> child_bit_depth_inv;
390 
395  static NNParams params[100];
397 
402  bool earlystop;
404 
407 
408 public:
409 
410  inline const T* getMins() const { return &(*mins); }
411  inline const T* getMaxs() const { return &(*maxs); }
412  inline const T* getCenter() const { return center; }
413  inline T getSize() const { return size; }
414  inline unsigned int getPointdim() const { return POINTDIM; }
415  inline const bitoct& getRoot() const { return *root; }
416  inline unsigned int getMaxDepth() const { return max_depth; }
417 
418  inline void getCenter(double _center[3]) const {
419  _center[0] = center[0];
420  _center[1] = center[1];
421  _center[2] = center[2];
422  }
423 
424  void GetOctTreeCenter(vector<T*>&c) { GetOctTreeCenter(c, *root, center, size); }
425  void GetOctTreeRandom(vector<T*>&c) { GetOctTreeRandom(c, *root); }
426  void GetOctTreeRandom(vector<T*>&c, unsigned int ptspervoxel) { GetOctTreeRandom(c, ptspervoxel, *root); }
427  void AllPoints(vector<T *> &vp) { AllPoints(*BOctTree<T>::root, vp); }
428 
429  long countNodes() { return 1 + countNodes(*root); } // computes number of inner nodes
430  long countLeaves() { return countLeaves(*root); } // computes number of leaves + points
431  long countOctLeaves() { return countOctLeaves(*root); } // computes number of leaves
432 
433  void deserialize(std::string filename ) {
434  char buffer[sizeof(T) * 20];
435  T *p = reinterpret_cast<T*>(buffer);
436 
437  std::ifstream file;
438  file.open (filename.c_str(), std::ios::in | std::ios::binary);
439 
440  // read magic bits
441  file.read(buffer, 2);
442  if ( buffer[0] != 'X' || buffer[1] != 'T') {
443  std::cerr << "Not an octree file!!" << endl;
444  file.close();
445  return;
446  }
447 
448  // read header
450 
451  file.read(buffer, 5 * sizeof(T));
452  voxelSize = p[0];
453  center[0] = p[1];
454  center[1] = p[2];
455  center[2] = p[3];
456  size = p[4];
457 
458  file.read(buffer, sizeof(int));
459  int *ip = reinterpret_cast<int*>(buffer);
460  POINTDIM = *ip;
461 
462  mins = alloc->allocate<T>(POINTDIM);
463  maxs = alloc->allocate<T>(POINTDIM);
464 
465  file.read(reinterpret_cast<char*>(&(*mins)), POINTDIM * sizeof(T));
466  file.read(reinterpret_cast<char*>(&(*maxs)), POINTDIM * sizeof(T));
467 
468  // read root node
470  root = &uroot->node;
471 
472  deserialize(file, *root);
473  file.close();
474  }
475 
476  static void deserialize(std::string filename, vector<Point> &points ) {
477  char buffer[sizeof(T) * 20];
478 
479  std::ifstream file;
480  file.open (filename.c_str(), std::ios::in | std::ios::binary);
481 
482  // read magic bits
483  file.read(buffer, 2);
484  if ( buffer[0] != 'X' || buffer[1] != 'T') {
485  std::cerr << "Not an octree file!!" << endl;
486  file.close();
487  return;
488  }
489 
490  // read header
492 
493  file.read(buffer, 5 * sizeof(T)); // read over voxelsize, center and size
494  file.read(buffer, sizeof(int));
495 
496  int *ip = reinterpret_cast<int*>(buffer);
497  unsigned int POINTDIM = *ip;
498 
499  file.read(buffer, POINTDIM * sizeof(T));
500  file.read(buffer, POINTDIM * sizeof(T));
501 
502  // read root node
503  deserialize(file, points, pointtype);
504  file.close();
505  }
506 
507  void serialize(std::string filename) {
508  char buffer[sizeof(T) * 20];
509  T *p = reinterpret_cast<T*>(buffer);
510 
511  std::ofstream file;
512  file.open (filename.c_str(), std::ios::out | std::ios::binary);
513 
514  // write magic bits
515  buffer[0] = 'X';
516  buffer[1] = 'T';
517  file.write(buffer, 2);
518 
519  // write header
521 
522  p[0] = voxelSize;
523  p[1] = center[0];
524  p[2] = center[1];
525  p[3] = center[2];
526  p[4] = size;
527 
528  int *ip = reinterpret_cast<int*>(&(buffer[5 * sizeof(T)]));
529  *ip = POINTDIM;
530 
531  file.write(buffer, 5 * sizeof(T) + sizeof(int));
532 
533 
534  for (unsigned int i = 0; i < POINTDIM; i++) {
535  p[i] = mins[i];
536  }
537  for (unsigned int i = 0; i < POINTDIM; i++) {
538  p[i+POINTDIM] = maxs[i];
539  }
540 
541  file.write(buffer, 2*POINTDIM * sizeof(T));
542 
543  // write root node
544  serialize(file, *root);
545 
546  file.close();
547  }
548 
549  static PointType readType(std::string filename ) {
550  char buffer[sizeof(T) * 20];
551 
552  std::ifstream file;
553  file.open (filename.c_str(), std::ios::in | std::ios::binary);
554 
555  // read magic bits
556  file.read(buffer, 2);
557  if ( buffer[0] != 'X' || buffer[1] != 'T') {
558  std::cerr << "Not an octree file!!" << endl;
559  file.close();
560  return PointType();
561  }
562 
563  // read header
565 
566  file.close();
567 
568  return pointtype;
569  }
570 
571 
576  T* pickPoint(bitoct &node) {
577  bitunion<T> *children;
578  bitoct::getChildren(node, children);
579 
580  for (short i = 0; i < 8; i++) {
581  if ( ( 1 << i ) & node.valid ) { // if ith node exists
582  if ( ( 1 << i ) & node.leaf ) { // if ith node is leaf
583  // absolute pointer
584  //return &(children->points[1].v);
585  // offset pointer
586  return children->getPoints();
587  } else { // recurse
588  return pickPoint(children->node);
589  }
590  ++children; // next child
591  }
592  }
593  return 0;
594  }
595 
596  static void childcenter(const T *pcenter, T *ccenter, T size, unsigned char i) {
597  switch (i) {
598  case 0: // 000
599  ccenter[0] = pcenter[0] - size / 2.0;
600  ccenter[1] = pcenter[1] - size / 2.0;
601  ccenter[2] = pcenter[2] - size / 2.0;
602  break;
603  case 1: // 001
604  ccenter[0] = pcenter[0] + size / 2.0;
605  ccenter[1] = pcenter[1] - size / 2.0;
606  ccenter[2] = pcenter[2] - size / 2.0;
607  break;
608  case 2: // 010
609  ccenter[0] = pcenter[0] - size / 2.0;
610  ccenter[1] = pcenter[1] + size / 2.0;
611  ccenter[2] = pcenter[2] - size / 2.0;
612  break;
613  case 3: // 011
614  ccenter[0] = pcenter[0] + size / 2.0;
615  ccenter[1] = pcenter[1] + size / 2.0;
616  ccenter[2] = pcenter[2] - size / 2.0;
617  break;
618  case 4: // 100
619  ccenter[0] = pcenter[0] - size / 2.0;
620  ccenter[1] = pcenter[1] - size / 2.0;
621  ccenter[2] = pcenter[2] + size / 2.0;
622  break;
623  case 5: // 101
624  ccenter[0] = pcenter[0] + size / 2.0;
625  ccenter[1] = pcenter[1] - size / 2.0;
626  ccenter[2] = pcenter[2] + size / 2.0;
627  break;
628  case 6: // 110
629  ccenter[0] = pcenter[0] - size / 2.0;
630  ccenter[1] = pcenter[1] + size / 2.0;
631  ccenter[2] = pcenter[2] + size / 2.0;
632  break;
633  case 7: // 111
634  ccenter[0] = pcenter[0] + size / 2.0;
635  ccenter[1] = pcenter[1] + size / 2.0;
636  ccenter[2] = pcenter[2] + size / 2.0;
637  break;
638  default:
639  break;
640  }
641  }
642 
643  static void childcenter(int x, int y, int z, int &cx, int &cy, int &cz, char i, int size) {
644  switch (i) {
645  case 0: // 000
646  cx = x - size ;
647  cy = y - size ;
648  cz = z - size ;
649  break;
650  case 1: // 001
651  cx = x + size ;
652  cy = y - size ;
653  cz = z - size ;
654  break;
655  case 2: // 010
656  cx = x - size ;
657  cy = y + size ;
658  cz = z - size ;
659  break;
660  case 3: // 011
661  cx = x + size ;
662  cy = y + size ;
663  cz = z - size ;
664  break;
665  case 4: // 100
666  cx = x - size ;
667  cy = y - size ;
668  cz = z + size ;
669  break;
670  case 5: // 101
671  cx = x + size ;
672  cy = y - size ;
673  cz = z + size ;
674  break;
675  case 6: // 110
676  cx = x - size ;
677  cy = y + size ;
678  cz = z + size ;
679  break;
680  case 7: // 111
681  cx = x + size ;
682  cy = y + size ;
683  cz = z + size ;
684  break;
685  default:
686  break;
687  }
688  }
689 
690 protected:
691 
692  void AllPoints( bitoct &node, vector<T*> &vp) {
693  bitunion<T> *children;
694  bitoct::getChildren(node, children);
695 
696  for (short i = 0; i < 8; i++) {
697  if ( ( 1 << i ) & node.valid ) { // if ith node exists
698  if ( ( 1 << i ) & node.leaf ) { // if ith node is leaf get center
699  // absolute pointer
700  //pointrep *points = children->points;
701  // offset pointer
702  pointrep* points = children->getPointreps();
703  unsigned int length = points[0].length;
704  T *point = &(points[1].v); // first point
705  for(unsigned int iterator = 0; iterator < length; iterator++ ) {
706  //T *p = new T[BOctTree<T>::POINTDIM];
707 // T *p = new T[3];
708 // p[0] = point[0]; p[1] = point[1]; p[2] = point[2];
709  T *p = new T[BOctTree<T>::POINTDIM];
710  for (unsigned int k = 0; k < BOctTree<T>::POINTDIM; k++)
711  p[k] = point[k];
712 
713  vp.push_back(p);
714 
715  //glVertex3f( point[0], point[1], point[2]);
716  point+=BOctTree<T>::POINTDIM;
717  }
718  } else { // recurse
719  AllPoints( children->node, vp);
720  }
721  ++children; // next child
722  }
723  }
724  }
725 
726  static void deserialize(std::ifstream &f, vector<Point> &vpoints, PointType &pointtype) {
727  char buffer[2];
728  pointrep *point = new pointrep[pointtype.getPointDim()];
729  f.read(buffer, 2);
730  bitoct node;
731  node.valid = buffer[0];
732  node.leaf = buffer[1];
733 
734  for (short i = 0; i < 8; i++) {
735  if ( ( 1 << i ) & node.valid ) { // if ith node exists
736  if ( ( 1 << i ) & node.leaf ) { // if ith node is leaf read points
737  pointrep first;
738  f.read(reinterpret_cast<char*>(&first), sizeof(pointrep));
739  unsigned int length = first.length; // read first element, which is the length
740  for (unsigned int k = 0; k < length; k++) {
741  f.read(reinterpret_cast<char*>(point), sizeof(pointrep) * pointtype.getPointDim()); // read the points
742  vpoints.push_back( pointtype.createPoint( &(point->v ) ) );
743  }
744  } else { // write child
745  deserialize(f, vpoints, pointtype);
746  }
747  }
748  }
749  delete [] point;
750  }
751 
752  void deserialize(std::ifstream &f, bitoct &node) {
753  char buffer[2];
754  f.read(buffer, 2);
755  node.valid = buffer[0];
756  node.leaf = buffer[1];
757 
758  unsigned short n_children = POPCOUNT(node.valid);
759 
760  // create children
761  bitunion<T> *children = alloc->allocate<bitunion<T> >(n_children);
762  bitoct::link(node, children);
763 
764  for (short i = 0; i < 8; i++) {
765  if ( ( 1 << i ) & node.valid ) { // if ith node exists
766  if ( ( 1 << i ) & node.leaf ) { // if ith node is leaf read points
767  pointrep first;
768  f.read(reinterpret_cast<char*>(&first), sizeof(pointrep));
769  unsigned int length = first.length; // read first element, which is the length
770  pointrep *points = alloc->allocate<pointrep> (POINTDIM*length + 1);
771  // absolute pointer
772  //children->points = points;
773  // offset pointer
774  bitunion<T>::link(children, points);
775  points[0] = first;
776  points++;
777  f.read(reinterpret_cast<char*>(points), sizeof(pointrep) * length * POINTDIM); // read the points
778  } else { // write child
779  deserialize(f, children->node);
780  }
781  ++children; // next child
782  }
783  }
784  }
785 
786  void serialize(std::ofstream &of, bitoct &node) {
787  char buffer[2];
788  buffer[0] = node.valid;
789  buffer[1] = node.leaf;
790  of.write(buffer, 2);
791 
792 
793  // write children
794  bitunion<T> *children;
795  bitoct::getChildren(node, children);
796  for (short i = 0; i < 8; i++) {
797  if ( ( 1 << i ) & node.valid ) { // if ith node exists
798  if ( ( 1 << i ) & node.leaf ) { // if ith node is leaf write points
799  // absolute pointer
800  //pointrep *points = children->points;
801  // offset pointer
802  pointrep* points = children->getPointreps();
803  unsigned int length = points[0].length;
804  of.write(reinterpret_cast<char*>(points), sizeof(pointrep) * (length * POINTDIM +1));
805  } else { // write child
806  serialize(of, children->node);
807  }
808  ++children; // next child
809  }
810  }
811  }
812 
813  void GetOctTreeCenter(vector<T*>&c, bitoct &node, T *center, T size) {
814  T ccenter[3];
815  bitunion<T> *children;
816  bitoct::getChildren(node, children);
817 
818  for (unsigned char i = 0; i < 8; i++) {
819  if ( ( 1 << i ) & node.valid ) { // if ith node exists
820  childcenter(center, ccenter, size, i); // childrens center
821  if ( ( 1 << i ) & node.leaf ) { // if ith node is leaf get center
822  T * cp = new T[3];
823  for (unsigned int iterator = 0; iterator < 3; iterator++) {
824  cp[iterator] = ccenter[iterator];
825  }
826  c.push_back(cp);
827  } else { // recurse
828  GetOctTreeCenter(c, children->node, ccenter, size/2.0);
829  }
830  ++children; // next child
831  }
832  }
833  }
834 
835  void GetOctTreeRandom(vector<T*>&c, bitoct &node) {
836  bitunion<T> *children;
837  bitoct::getChildren(node, children);
838 
839  for (short i = 0; i < 8; i++) {
840  if ( ( 1 << i ) & node.valid ) { // if ith node exists
841  if ( ( 1 << i ) & node.leaf ) { // if ith node is leaf
842  // absolute pointer
843  //pointrep *points = children->points;
844  // offset pointer
845  pointrep* points = children->getPointreps();
846  // new version to ignore leaves with less than 3 points
847  /*
848  if(points[0].length > 2) {
849  for(int tmp = 0; tmp < points[0].length; tmp++) {
850  T *point = &(points[POINTDIM*tmp+1].v);
851  c.push_back(point);
852  }
853  }
854  */
855  //old version
856 
857  int tmp = rand(points[0].length);
858  T *point = &(points[POINTDIM*tmp+1].v);
859  c.push_back(point);
860 
861 
862  } else { // recurse
863  GetOctTreeRandom(c, children->node);
864  }
865  ++children; // next child
866  }
867  }
868  }
869 
870  void GetOctTreeRandom(vector<T*>&c, unsigned int ptspervoxel, bitoct &node) {
871  bitunion<T> *children;
872  bitoct::getChildren(node, children);
873 
874  for (short i = 0; i < 8; i++) {
875  if ( ( 1 << i ) & node.valid ) { // if ith node exists
876  if ( ( 1 << i ) & node.leaf ) { // if ith node is leaf
877  // absolute pointer
878  //pointrep *points = children->points;
879  // offset pointer
880  pointrep* points = children->getPointreps();
881  unsigned int length = points[0].length;
882  if (ptspervoxel >= length) {
883  for (unsigned int j = 0; j < length; j++)
884  c.push_back(&(points[POINTDIM*j+1].v));
885 
886  ++children; // next child
887  continue;
888  }
889  set<int> indices;
890  while(indices.size() < ptspervoxel) {
891  int tmp = rand(length-1);
892  indices.insert(tmp);
893  }
894  for(set<int>::iterator it = indices.begin(); it != indices.end(); it++)
895  c.push_back(&(points[POINTDIM*(*it)+1].v));
896 
897  } else { // recurse
898  GetOctTreeRandom(c, ptspervoxel, children->node);
899  }
900  ++children; // next child
901  }
902  }
903  }
904 
905  long countNodes(bitoct &node) {
906  long result = 0;
907  bitunion<T> *children;
908  bitoct::getChildren(node, children);
909 
910  for (short i = 0; i < 8; i++) {
911  if ( ( 1 << i ) & node.valid ) { // if ith node exists
912  if ( ( 1 << i ) & node.leaf ) { // if ith node is leaf
913  //++result;
914  } else { // recurse
915  result += countNodes(children->node) + 1;
916  }
917  ++children; // next child
918  }
919  }
920  return result;
921  }
922 
923  long countLeaves(bitoct &node) {
924  long result = 0;
925  bitunion<T> *children;
926  bitoct::getChildren(node, children);
927 
928  for (short i = 0; i < 8; i++) {
929  if ( ( 1 << i ) & node.valid ) { // if ith node exists
930  if ( ( 1 << i ) & node.leaf ) { // if ith node is leaf
931  long nrpts = children->getLength();
932  result += POINTDIM*nrpts;
933  } else { // recurse
934  result += countLeaves(children->node);
935  }
936  ++children; // next child
937  }
938  }
939  return result;
940  }
941 
942  long countOctLeaves(bitoct &node) {
943  long result = 0;
944  bitunion<T> *children;
945  bitoct::getChildren(node, children);
946 
947  for (short i = 0; i < 8; i++) {
948  if ( ( 1 << i ) & node.valid ) { // if ith node exists
949  if ( ( 1 << i ) & node.leaf ) { // if ith node is leaf
950  result ++;
951  } else { // recurse
952  result += countTrueLeaves(children->node);
953  }
954  ++children; // next child
955  }
956  }
957  return result;
958  }
959 
960  // TODO: is this still needed? nodes and pointreps are all in the Allocator
961  void deletetNodes(bitoct &node) {
962  bitunion<T> *children;
963  bitoct::getChildren(node, children);
964  bool haschildren = false;
965 
966  for (short i = 0; i < 8; i++) {
967  if ( ( 1 << i ) & node.valid ) { // if ith node exists
968  if ( ( 1 << i ) & node.leaf ) { // if ith node is leaf
969  // absolute pointer
970  //delete [] children->points;
971  // offset pointer
972  delete [] children->getPointreps();
973  } else { // recurse
974  deletetNodes(children->node);
975  }
976  ++children; // next child
977  haschildren = true;
978  }
979  }
980  // delete children
981  if (haschildren) {
982  bitoct::getChildren(node, children);
983  }
984  }
985 
986  template <class P>
987  void* branch( bitoct &node, P * const * splitPoints, int n, T _center[3], T _size) {
988  // if bucket is too small stop building tree
989  // -----------------------------------------
990  if ((_size <= voxelSize) || (earlystop && n <= 10) ) {
991 
992  // copy points
993  pointrep *points = alloc->allocate<pointrep> (POINTDIM*n + 1);
994 
995  points[0].length = n;
996  int i = 1;
997  for (int j = 0; j < n; j++) {
998  for (unsigned int iterator = 0; iterator < POINTDIM; iterator++) {
999  points[i++].v = splitPoints[j][iterator];
1000  }
1001  }
1002  return points;
1003  }
1004 
1005  // calculate new buckets
1006  T newcenter[8][3];
1007  T sizeNew;
1008 
1009  sizeNew = _size / 2.0;
1010 
1011  for (unsigned char i = 0; i < 8; i++) {
1012  childcenter(_center, newcenter[i], _size, i);
1013  }
1014 
1015  countPointsAndQueueFast(splitPoints, n, newcenter, sizeNew, node, _center);
1016  return 0;
1017  }
1018 
1019  template <class P>
1020  void* branch( bitoct &node, vector<P*> &splitPoints, T _center[3], T _size) {
1021  // if bucket is too small stop building tree
1022  // -----------------------------------------
1023  if ((_size <= voxelSize) || (earlystop && splitPoints.size() <= 10) ) {
1024  // copy points
1025  pointrep *points = alloc->allocate<pointrep> (POINTDIM*splitPoints.size() + 1);
1026  points[0].length = splitPoints.size();
1027  int i = 1;
1028  for (typename vector<P *>::iterator itr = splitPoints.begin();
1029  itr != splitPoints.end(); itr++) {
1030  for (unsigned int iterator = 0; iterator < POINTDIM; iterator++) {
1031  points[i++].v = (*itr)[iterator];
1032  }
1033  }
1034  return points;
1035  }
1036 
1037  // calculate new buckets
1038  T newcenter[8][3];
1039  T sizeNew;
1040 
1041  sizeNew = _size / 2.0;
1042 
1043  for (unsigned char i = 0; i < 8; i++) {
1044  childcenter(_center, newcenter[i], _size, i);
1045  }
1046 
1047  countPointsAndQueue(splitPoints, newcenter, sizeNew, node, _center);
1048  return 0;
1049  }
1050 
1051  template <class P>
1052  void countPointsAndQueue(vector<P*> &i_points, T center[8][3], T size, bitoct &parent, T *pcenter) {
1053  vector<P*> points[8];
1054  int n_children = 0;
1055  for (typename vector<P *>::iterator itr = i_points.begin(); itr != i_points.end(); itr++) {
1056  points[childIndex<P>(pcenter, *itr)].push_back( *itr );
1057  }
1058 
1059  i_points.clear();
1060  vector<P*>().swap(i_points);
1061  for (int j = 0; j < 8; j++) {
1062  if (!points[j].empty()) {
1063  parent.valid = ( 1 << j ) | parent.valid;
1064  ++n_children;
1065  }
1066  }
1067  // create children
1068  bitunion<T> *children = alloc->allocate<bitunion<T> >(n_children);
1069  bitoct::link(parent, children);
1070 
1071  int count = 0;
1072  for (int j = 0; j < 8; j++) {
1073  if (!points[j].empty()) {
1074  pointrep *c = (pointrep*)branch(children[count].node, points[j], center[j], size); // leaf node
1075  if (c) {
1076  // absolute pointer
1077  //children[count].points = c; // set this child to deque of points
1078  // offset pointer
1079  bitunion<T>::link(&children[count], c);
1080  parent.leaf = ( 1 << j ) | parent.leaf; // remember this is a leaf
1081  }
1082  points[j].clear();
1083  vector<P*>().swap(points[j]);
1084  ++count;
1085  }
1086  }
1087  }
1088 
1089  template <class P>
1090  void countPointsAndQueueFast(P * const* points, int n, T center[8][3], T size, bitoct &parent, T pcenter[3]) {
1091  P * const *blocks[9];
1092  blocks[0] = points;
1093  blocks[8] = points + n;
1094  fullsort(points, n, pcenter, blocks+1);
1095 
1096  int n_children = 0;
1097 
1098  for (int j = 0; j < 8; j++) {
1099  // if non-empty set valid flag for this child
1100  if (blocks[j+1] - blocks[j] > 0) {
1101  parent.valid = ( 1 << j ) | parent.valid;
1102  ++n_children;
1103  }
1104  }
1105 
1106  // create children
1107  bitunion<T> *children = alloc->allocate<bitunion<T> >(n_children);
1108  bitoct::link(parent, children);
1109  int count = 0;
1110  for (int j = 0; j < 8; j++) {
1111  if (blocks[j+1] - blocks[j] > 0) {
1112  pointrep *c = (pointrep*)branch(children[count].node, blocks[j], blocks[j+1] - blocks[j], center[j], size); // leaf node
1113  if (c) {
1114  // absolute pointer
1115  //children[count].points = c; // set this child to vector of points
1116  // offset pointer
1117  bitunion<T>::link(&children[count], c); // set this child to vector of points
1118  parent.leaf = ( 1 << j ) | parent.leaf; // remember this is a leaf
1119  }
1120  ++count;
1121  }
1122  }
1123  }
1124 
1125 
1126  void getByIndex(T *point, T *&points, unsigned int &length) {
1127  unsigned int x,y,z;
1128  x = (point[0] + add[0]) * mult;
1129  y = (point[1] + add[1]) * mult;
1130  z = (point[2] + add[2]) * mult;
1131 
1132  bitunion<T> *node = uroot;
1133  unsigned char child_index;
1134  unsigned int child_bit;
1135  unsigned int depth = 0;
1136 
1137  while (true) {
1138  child_bit = child_bit_depth[depth];
1139  child_index = ((x & child_bit )!=0) | (((y & child_bit )!=0 )<< 1) | (((z & child_bit )!=0) << 2);
1140  if (node->childIsLeaf(child_index) ) {
1141  node = node->getChild(child_index);
1142  points = node->getPoints();
1143  length = node->getLength();
1144  return;
1145  } else {
1146  node = node->getChild(child_index);
1147  }
1148  depth++;
1149  }
1150  }
1151 
1152  template <class P>
1153  inline unsigned char childIndex(const T *center, const P *point) {
1154  return (point[0] > center[0] ) | ((point[1] > center[1] ) << 1) | ((point[2] > center[2] ) << 2) ;
1155  }
1156 
1161  inline void findClosestInLeaf(bitunion<T> *node, int threadNum) const {
1162  if (params[threadNum].count >= params[threadNum].max_count) return;
1163  params[threadNum].count++;
1164  T* points = node->getPoints();
1165  unsigned int length = node->getLength();
1166  for(unsigned int iterator = 0; iterator < length; iterator++ ) {
1167  double myd2 = Dist2(params[threadNum].p, points);
1168  if (myd2 < params[threadNum].closest_d2) {
1169  params[threadNum].closest_d2 = myd2;
1170  params[threadNum].closest = points;
1171  if (myd2 <= 0.0001) {
1172  params[threadNum].closest_v = 0; // the search radius in units of voxelSize
1173  } else {
1174  params[threadNum].closest_v = sqrt(myd2) * mult + 1; // the search radius in units of voxelSize
1175  }
1176  }
1177  points+=BOctTree<T>::POINTDIM;
1178  }
1179  }
1180 
1181 
1182 
1190  double *FindClosest(double *point, double maxdist2, int threadNum) const
1191  {
1192  params[threadNum].closest = 0; // no point found currently
1193  params[threadNum].closest_d2 = maxdist2;
1194  params[threadNum].p = point;
1195  params[threadNum].x = (point[0] + add[0]) * mult;
1196  params[threadNum].y = (point[1] + add[1]) * mult;
1197  params[threadNum].z = (point[2] + add[2]) * mult;
1198  params[threadNum].closest_v = sqrt(maxdist2) * mult + 1; // the search radius in units of voxelSize
1199  params[threadNum].count = 0;
1200  params[threadNum].max_count = 10000; // stop looking after this many buckets
1201 
1202 
1203  // box within bounds in voxel coordinates
1204  int xmin, ymin, zmin, xmax, ymax, zmax;
1205  xmin = max(params[threadNum].x-params[threadNum].closest_v, 0);
1206  ymin = max(params[threadNum].y-params[threadNum].closest_v, 0);
1207  zmin = max(params[threadNum].z-params[threadNum].closest_v, 0);
1208 
1209 // int largest_index = child_bit_depth[0] * 2 -1;
1210 
1211  xmax = min(params[threadNum].x+params[threadNum].closest_v, largest_index);
1212  ymax = min(params[threadNum].y+params[threadNum].closest_v, largest_index);
1213  zmax = min(params[threadNum].z+params[threadNum].closest_v, largest_index);
1214 
1215  unsigned char depth = 0;
1216  unsigned int child_bit;
1217  unsigned int child_index_min;
1218  unsigned int child_index_max;
1219 
1220  bitunion<T> *node = &(*uroot);
1221 
1222  int cx, cy, cz;
1223 
1224  child_bit = child_bit_depth[depth];
1225  cx = child_bit_depth[depth];
1226  cy = child_bit_depth[depth];
1227  cz = child_bit_depth[depth];
1228 
1229  while (true) { // find the first node where branching is required
1230  child_index_min = ((xmin & child_bit )!=0) | (((ymin & child_bit )!=0 )<< 1) | (((zmin & child_bit )!=0) << 2);
1231  child_index_max = ((xmax & child_bit )!=0) | (((ymax & child_bit )!=0 )<< 1) | (((zmax & child_bit )!=0) << 2);
1232 
1233  // if these are the same, go there
1234  // TODO: optimization: also traverse if only single child...
1235  if (child_index_min == child_index_max) {
1236  if (node->childIsLeaf(child_index_min) ) { // luckily, no branching is required
1237  findClosestInLeaf(node->getChild(child_index_min), threadNum);
1238  return static_cast<double*>(params[threadNum].closest);
1239  } else {
1240  if (node->isValid(child_index_min) ) { // only descend when there is a child
1241  childcenter(cx,cy,cz, cx,cy,cz, child_index_min, child_bit/2 );
1242  node = node->getChild(child_index_min);
1243  child_bit /= 2;
1244  } else { // there is no child containing the bounding box => no point is close enough
1245  return 0;
1246  }
1247  }
1248  } else {
1249  // if min and max are not in the same child we must branch
1250  break;
1251  }
1252  }
1253 
1254  // node contains all box-within-bounds cells, now begin best bin first search
1255  _FindClosest(threadNum, node->node, child_bit/2, cx, cy, cz);
1256  return static_cast<double*>(params[threadNum].closest);
1257  }
1258 
1264  void _FindClosest(int threadNum, bitoct &node, int size, int x, int y, int z) const
1265  {
1266  // Recursive case
1267 
1268  // compute which child is closest to the query point
1269  unsigned char child_index = ((params[threadNum].x - x) >= 0) |
1270  (((params[threadNum].y - y) >= 0) << 1) |
1271  (((params[threadNum].z - z) >= 0) << 2);
1272 
1273  char *seq2ci = sequence2ci[child_index][node.valid]; // maps preference to index in children array
1274  char *mmap = amap[child_index]; // maps preference to area index
1275 
1276  bitunion<T> *children;
1277  bitoct::getChildren(node, children);
1278  int cx, cy, cz;
1279  cx = cy = cz = 0; // just to shut up the compiler warnings
1280  for (unsigned char i = 0; i < 8; i++) { // in order of preference
1281  child_index = mmap[i]; // the area index of the node
1282  if ( ( 1 << child_index ) & node.valid ) { // if ith node exists
1283  childcenter(x,y,z, cx,cy,cz, child_index, size);
1284  if ( params[threadNum].closest_v == 0 || max(max(abs( cx - params[threadNum].x ),
1285  abs( cy - params[threadNum].y )),
1286  abs( cz - params[threadNum].z )) - size
1287  > params[threadNum].closest_v ) {
1288  continue;
1289  }
1290  // find the closest point in leaf seq2ci[i]
1291  if ( ( 1 << child_index ) & node.leaf ) { // if ith node is leaf
1292  findClosestInLeaf( &children[seq2ci[i]], threadNum);
1293  } else { // recurse
1294  _FindClosest(threadNum, children[seq2ci[i]].node, size/2, cx, cy, cz);
1295  }
1296  }
1297  }
1298  }
1299 
1300 
1308  double *FindClosestInBucket(double *point, double maxdist2, int threadNum) {
1309  params[threadNum].closest = 0;
1310  params[threadNum].closest_d2 = maxdist2;
1311  params[threadNum].p = point;
1312  unsigned int x,y,z;
1313  x = (point[0] + add[0]) * mult;
1314  y = (point[1] + add[1]) * mult;
1315  z = (point[2] + add[2]) * mult;
1316  T * points;
1317  unsigned int length;
1318 
1319  bitunion<T> *node = uroot;
1320  unsigned char child_index;
1321 
1322  unsigned int child_bit = child_bit_depth[0];
1323 
1324  while (true) {
1325  child_index = ((x & child_bit )!=0) | (((y & child_bit )!=0 )<< 1) | (((z & child_bit )!=0) << 2);
1326  if (node->childIsLeaf(child_index) ) {
1327  node = node->getChild(child_index);
1328  points = node->getPoints();
1329  length = node->getLength();
1330 
1331  for(unsigned int iterator = 0; iterator < length; iterator++ ) {
1332  double myd2 = Dist2(params[threadNum].p, points);
1333  if (myd2 < params[threadNum].closest_d2) {
1334  params[threadNum].closest_d2 = myd2;
1335  params[threadNum].closest = points;
1336  }
1337  points+=BOctTree<T>::POINTDIM;
1338  }
1339  return static_cast<double*>(params[threadNum].closest);
1340  } else {
1341  if (node->isValid(child_index) ) {
1342  node = node->getChild(child_index);
1343  } else {
1344  return 0;
1345  }
1346  }
1347  child_bit >>= 1;
1348  }
1349  return static_cast<double*>(params[threadNum].closest);
1350  }
1351 
1352 
1353 template <class P>
1354  void fullsort(P * const * points, int n, T splitval[3], P * const * blocks[9]) {
1355  P* const * L0;
1356  P* const * L1;
1357  P* const * L2;
1358  unsigned int n0L, n0R, n1L, n1R ;
1359 
1360  // sort along Z
1361  L0 = sort(points, n, splitval[2], 2);
1362 
1363  n0L = L0 - points;
1364  // sort along Y (left of Z) points -- L0
1365  L1 = sort(points, n0L, splitval[1], 1);
1366 
1367  n1L = L1 - points;
1368  // sort along X (left of Y) points -- L1
1369  L2 = sort(points, n1L, splitval[0], 0);
1370 
1371  blocks[0] = L2;
1372 
1373  n1R = n0L - n1L;
1374  // sort along X (right of Y) // L1 -- L0
1375  L2 = sort(L1, n1R, splitval[0], 0);
1376 
1377  blocks[1] = L1;
1378  blocks[2] = L2;
1379 
1380  n0R = n - n0L;
1381  // sort along Y (right of Z) L0 -- end
1382  L1 = sort(L0, n0R, splitval[1], 1);
1383 
1384  n1L = L1 - L0;
1385  // sort along X (left of Y) points -- L1
1386  L2 = sort(L0, n1L, splitval[0], 0);
1387 
1388  blocks[3] = L0;
1389  blocks[4] = L2;
1390 
1391  n1R = n0R - n1L;
1392  // sort along X (right of Y) // L1 -- L0
1393  L2 = sort(L1, n1R, splitval[0], 0);
1394 
1395  blocks[5] = L1;
1396  blocks[6] = L2;
1397  }
1398 
1399 
1400  template <class P>
1401  P* const * sort(P* const * points, unsigned int n, T splitval, unsigned char index) {
1402  if (n==0) return points;
1403 
1404  if (n==1) {
1405  if (points[0][index] < splitval)
1406  return points+1;
1407  else
1408  return points;
1409  }
1410 
1411  P **left = const_cast<P**>(points);
1412  P **right = const_cast<P**>(points + n - 1);
1413 
1414 
1415  while (1) {
1416  while ((*left)[index] < splitval)
1417  {
1418  left++;
1419  if (right < left)
1420  break;
1421  }
1422  while ((*right)[index] >= splitval)
1423  {
1424  right--;
1425  if (right < left)
1426  break;
1427  }
1428  if (right < left)
1429  break;
1430 
1431  std::swap(*left, *right);
1432  }
1433  return left;
1434  }
1435 
1436 public:
1440  BOctTree(const BOctTree& other, unsigned char* mem_ptr, unsigned int mem_max)
1441  {
1442  alloc = new SequentialAllocator(mem_ptr, mem_max);
1443 
1444  // "allocate" space for *this
1445  alloc->allocate<BOctTree<T> >();
1446 
1447  // take members
1448  unsigned int i;
1449  for(i = 0; i < 3; ++i)
1450  center[i] = other.center[i];
1451  size = other.size;
1452  voxelSize = other.voxelSize;
1454  for(i = 0; i < 3; ++i)
1455  add[i] = other.add[i];
1456  mult = other.mult;
1457  POINTDIM = other.POINTDIM;
1458  mins = alloc->allocate<T>(POINTDIM);
1459  maxs = alloc->allocate<T>(POINTDIM);
1460  for(i = 0; i < POINTDIM; ++i) {
1461  mins[i] = other.mins[i];
1462  maxs[i] = other.maxs[i];
1463  }
1464  pointtype = other.pointtype;
1465  max_depth = other.max_depth;
1466  child_bit_depth = alloc->allocate<unsigned int>(max_depth);
1467  child_bit_depth_inv = alloc->allocate<unsigned int>(max_depth);
1468  for(i = 0; i < max_depth; ++i) {
1469  child_bit_depth[i] = other.child_bit_depth[i];
1471  }
1472  largest_index = other.largest_index;
1473 
1474  // take node structure
1475  uroot = alloc->allocate<bitunion<T> >();
1476  root = &uroot->node;
1477  copy_children(*other.root, *root);
1478 
1479  // test if allocator has used up his space
1480  //alloc->printSize();
1481 
1482  // discard allocator, space is managed by the cache manager
1483  delete alloc; alloc = 0;
1484  }
1485 
1486 private:
1487  void copy_children(const bitoct& other, bitoct& my) {
1488  // copy node attributes
1489  my.valid = other.valid;
1490  my.leaf = other.leaf;
1491 
1492  // other children
1493  bitunion<T>* other_children;
1494  bitoct::getChildren(other, other_children);
1495 
1496  // create own children
1497  unsigned int n_children = POPCOUNT(other.valid);
1498  bitunion<T>* my_children = alloc->allocate<bitunion<T> >(n_children);
1499  bitoct::link(my, my_children);
1500 
1501  // iterate over all (valid) children and copy them
1502  for(unsigned int i = 0; i < 8; ++i) {
1503  if((1<<i) & other.valid) {
1504  if((1<<i) & other.leaf) {
1505  // copy points
1506  unsigned int length = other_children->getLength();
1507  pointrep* other_pointreps = other_children->getPointreps();
1508  pointrep* my_pointreps = alloc->allocate<pointrep>(POINTDIM * length + 1);
1509  for(unsigned int j = 0; j < POINTDIM * length + 1; ++j)
1510  my_pointreps[j] = other_pointreps[j];
1511  // assign
1512  bitunion<T>::link(my_children, my_pointreps);
1513  } else {
1514  // child is already created, copy and create children for it
1515  copy_children(other_children->node, my_children->node);
1516  }
1517  ++other_children;
1518  ++my_children;
1519  }
1520  }
1521  }
1522 
1523 public:
1525  unsigned int getMemorySize()
1526  {
1527  return sizeof(*this) // all member variables
1528  + 2*POINTDIM*sizeof(T) // mins, maxs
1529  + 2*max_depth*sizeof(unsigned int) // child_bit_depth(_inv)
1530  + sizeof(bitunion<T>) // uroot
1531  + sizeChildren(*root); // all nodes
1532  }
1533 
1534 private:
1536  unsigned int sizeChildren(const bitoct& node) {
1537  unsigned int s = 0;
1538  bitunion<T>* children;
1539  bitoct::getChildren(node, children);
1540 
1541  // size of children allocation
1542  unsigned int n_children = POPCOUNT(node.valid);
1543  s += sizeof(bitunion<T>)*n_children;
1544 
1545  // iterate over all (valid) children and sum them up
1546  for(unsigned int i = 0; i < 8; ++i) {
1547  if((1<<i) & node.valid) {
1548  if((1<<i) & node.leaf) {
1549  // leaf only accounts for its points
1550  s += sizeof(pointrep)*(children->getLength()*POINTDIM+1);
1551  } else {
1552  // childe node is already accounted for, add its children
1553  s += sizeChildren(children->node);
1554  }
1555  ++children; // next (valid) child
1556  }
1557  }
1558  return s;
1559  }
1560 };
1561 
1563 
1564 template <class T>
1566 
1567 #endif
BOctTree::getCenter
void getCenter(double _center[3]) const
Definition: Boctree.h:418
BOctTree::getRoot
const bitoct & getRoot() const
Definition: Boctree.h:415
BOctTree::POINTDIM
unsigned int POINTDIM
Dimension of each point: 3 (xyz) + N (attributes)
Definition: Boctree.h:376
NNParams::count
int count
Definition: nnparams.h:33
dunion::length
unsigned int length
Definition: Boctree.h:55
BOctTree::findClosestInLeaf
void findClosestInLeaf(bitunion< T > *node, int threadNum) const
Definition: Boctree.h:1161
data_types.h
Basic DataPointer class and its derivates SingleArray and TripleArray.
searchTree.h
Representation of a general search trees.
BOctTree::center
T center[3]
storing the center
Definition: Boctree.h:360
BOctTree::params
static NNParams params[100]
Threadlocal storage of parameters used in SearchTree operations.
Definition: Boctree.h:396
BOctTree::AllPoints
void AllPoints(bitoct &node, vector< T * > &vp)
Definition: Boctree.h:692
bitoct::getChild
bitunion< T > * getChild(unsigned char index)
Definition: Boctree.h:111
BOctTree::deserialize
static void deserialize(std::string filename, vector< Point > &points)
Definition: Boctree.h:476
BOctTree::countLeaves
long countLeaves()
Definition: Boctree.h:430
Allocator
Definition: allocator.h:12
BOctTree::countPointsAndQueue
void countPointsAndQueue(vector< P * > &i_points, T center[8][3], T size, bitoct &parent, T *pcenter)
Definition: Boctree.h:1052
PointType::getPointDim
unsigned int getPointDim()
Definition: point_type.cc:124
dunion
Definition: Boctree.h:53
bitunion::getPoints
T * getPoints() const
Leaf node: points in the array.
Definition: Boctree.h:152
BOctTree::child_bit_depth_inv
ip::offset_ptr< unsigned int > child_bit_depth_inv
Definition: Boctree.h:388
BOctTree::BOctTree
BOctTree(vector< P * > &pts, T voxelSize, PointType _pointtype=PointType(), bool _earlystop=false)
Definition: Boctree.h:273
BOctTree::child_bit_depth
ip::offset_ptr< unsigned int > child_bit_depth
Definition: Boctree.h:387
BOctTree::maxs
ip::offset_ptr< T > maxs
Definition: Boctree.h:380
BOctTree::uroot
ip::offset_ptr< bitunion< T > > uroot
Definition: Boctree.h:357
POPCOUNT
#define POPCOUNT(mask)
Definition: Boctree.h:38
BOctTree::getMins
const T * getMins() const
Definition: Boctree.h:410
BOctTree::deserialize
void deserialize(std::ifstream &f, bitoct &node)
Definition: Boctree.h:752
BOctTree::countOctLeaves
long countOctLeaves(bitoct &node)
Definition: Boctree.h:942
DataOcttree
SingleObject< BOctTree< float > > DataOcttree
Definition: Boctree.h:1562
nnparams.h
BOctTree::fullsort
void fullsort(P *const *points, int n, T splitval[3], P *const *blocks[9])
Definition: Boctree.h:1354
PointType::deserialize
static PointType deserialize(std::ifstream &f)
Definition: point_type.cc:126
p
SharedPointer p
Definition: ConvertShared.hpp:42
BOctTree::~BOctTree
virtual ~BOctTree()
Definition: Boctree.h:318
BOctTree::childcenter
static void childcenter(const T *pcenter, T *ccenter, T size, unsigned char i)
Definition: Boctree.h:596
BOctTree::GetOctTreeRandom
void GetOctTreeRandom(vector< T * > &c, unsigned int ptspervoxel, bitoct &node)
Definition: Boctree.h:870
BOctTree::deletetNodes
void deletetNodes(bitoct &node)
Definition: Boctree.h:961
NNParams::closest_d2
double closest_d2
Definition: nnparams.h:13
BOctTree::branch
void * branch(bitoct &node, vector< P * > &splitPoints, T _center[3], T _size)
Definition: Boctree.h:1020
bitunion::link
static void link(bitunion< T > *leaf, pointrep *points)
Leaf node: links a pointrep array [length+values] to this union, saved as an offset pointer.
Definition: Boctree.h:146
bitoct
Definition: Boctree.h:82
point_type.h
Representation of a 3D point type.
BOctTree::branch
void * branch(bitoct &node, P *const *splitPoints, int n, T _center[3], T _size)
Definition: Boctree.h:987
BOctTree::countNodes
long countNodes(bitoct &node)
Definition: Boctree.h:905
BOctTree::GetOctTreeRandom
void GetOctTreeRandom(vector< T * > &c, bitoct &node)
Definition: Boctree.h:835
BOctTree::getMaxs
const T * getMaxs() const
Definition: Boctree.h:411
BOctTree::countPointsAndQueueFast
void countPointsAndQueueFast(P *const *points, int n, T center[8][3], T size, bitoct &parent, T pcenter[3])
Definition: Boctree.h:1090
BOctTree::GetOctTreeRandom
void GetOctTreeRandom(vector< T * > &c, unsigned int ptspervoxel)
Definition: Boctree.h:426
NNParams::closest
void * closest
Definition: nnparams.h:8
BOctTree::sort
P *const * sort(P *const *points, unsigned int n, T splitval, unsigned char index)
Definition: Boctree.h:1401
bitunion::getChild
bitunion< T > * getChild(unsigned char index) const
Definition: Boctree.h:174
dunion::v
T v
Definition: Boctree.h:54
BOctTree::alloc
Allocator * alloc
Allocator used for creating nodes in the constructor.
Definition: Boctree.h:406
bitoct::valid
unsigned valid
Definition: Boctree.h:91
BOctTree::size
T size
storing the dimension
Definition: Boctree.h:363
BOctTree::serialize
void serialize(std::ofstream &of, bitoct &node)
Definition: Boctree.h:786
BOctTree::pointtype
PointType pointtype
Details of point attributes.
Definition: Boctree.h:383
BOctTree::_FindClosest
void _FindClosest(int threadNum, bitoct &node, int size, int x, int y, int z) const
Definition: Boctree.h:1264
BOctTree::getCenter
const T * getCenter() const
Definition: Boctree.h:412
BOctTree::voxelSize
T voxelSize
storing the voxel size
Definition: Boctree.h:366
PointType::createPoint
T * createPoint(const Point &P, unsigned int index=0)
Definition: point_type.h:120
BOctTree::GetOctTreeRandom
void GetOctTreeRandom(vector< T * > &c)
Definition: Boctree.h:425
dunion::dunion
dunion()
Definition: Boctree.h:56
BOctTree::sizeChildren
unsigned int sizeChildren(const bitoct &node)
Recursive size of a node's children.
Definition: Boctree.h:1536
BOctTree::getSize
T getSize() const
Definition: Boctree.h:413
BOctTree::BOctTree
BOctTree(std::string filename)
Definition: Boctree.h:266
PointType
Definition: point_type.h:25
NNParams::y
int y
Definition: nnparams.h:20
BOctTree::pickPoint
T * pickPoint(bitoct &node)
Definition: Boctree.h:576
imap
char imap[8][8]
Definition: Boctree.cc:48
bitunion::bitunion
bitunion()
Definition: Boctree.h:139
NNParams::p
double * p
Definition: nnparams.h:26
NNParams::z
int z
Definition: nnparams.h:21
PointType::serialize
void serialize(std::ofstream &f)
Definition: point_type.cc:132
scripts.normalize_multiple.filename
filename
Definition: normalize_multiple.py:60
BOctTree::init
void init()
Definition: Boctree.h:325
BOctTree::mins
ip::offset_ptr< T > mins
storing minimal and maximal values for all dimensions
Definition: Boctree.h:379
BOctTree::earlystop
bool earlystop
Whether to stop subdividing at N<10 nodes or not.
Definition: Boctree.h:403
pointrep
#define pointrep
Definition: Boctree.h:61
BOctTree::real_voxelSize
T real_voxelSize
The real voxelsize of the leaves.
Definition: Boctree.h:369
BOctTree::BOctTree
BOctTree()
Definition: Boctree.h:217
bitunion::childIsLeaf
bool childIsLeaf(unsigned char index)
Definition: Boctree.h:193
NNParams::x
int x
Definition: nnparams.h:19
SequentialAllocator
Definition: allocator.h:60
BOctTree::countOctLeaves
long countOctLeaves()
Definition: Boctree.h:431
bitunion::bitunion
bitunion(pointrep *p)
Definition: Boctree.h:137
BOctTree::getByIndex
void getByIndex(T *point, T *&points, unsigned int &length)
Definition: Boctree.h:1126
BOctTree::countLeaves
long countLeaves(bitoct &node)
Definition: Boctree.h:923
BOctTree::copy_children
void copy_children(const bitoct &other, bitoct &my)
Definition: Boctree.h:1487
BOctTree::deserialize
static void deserialize(std::ifstream &f, vector< Point > &vpoints, PointType &pointtype)
Definition: Boctree.h:726
BOctTree::GetOctTreeCenter
void GetOctTreeCenter(vector< T * > &c, bitoct &node, T *center, T size)
Definition: Boctree.h:813
BOctTree::BOctTree
BOctTree(const BOctTree &other, unsigned char *mem_ptr, unsigned int mem_max)
Definition: Boctree.h:1440
lvr2::splitPoints
int splitPoints(Vector3f *points, int n, int axis, double splitValue)
Sorts a Point array so that all Points smaller than splitValue are on the left.
Definition: TreeUtils.cpp:47
bitoct::child_pointer
signed long child_pointer
Definition: Boctree.h:90
file
FILE * file
Definition: arithmeticencoder.cpp:77
BOctTree::readType
static PointType readType(std::string filename)
Definition: Boctree.h:549
bitoct::link
static void link(bitoct &parent, bitunion< T > *child)
Definition: Boctree.h:98
NNParams
Definition: nnparams.h:4
allocator.h
allocator object that gets chunks of memory and then hands parts of them to a user
SingleObject
Definition: data_types.h:163
BOctTree::deserialize
void deserialize(std::string filename)
Definition: Boctree.h:433
BOctTree::add
T add[3]
Offset and real voxelsize inverse factor for manipulation points.
Definition: Boctree.h:372
kfusion::device::swap
__kf_hdevice__ void swap(T &a, T &b)
Definition: temp_utils.hpp:10
amap
char amap[8][8]
Definition: Boctree.cc:38
bitunion::isValid
bool isValid(unsigned char index)
Definition: Boctree.h:184
BOctTree::mult
T mult
Definition: Boctree.h:373
NNParams::max_count
int max_count
Definition: nnparams.h:34
BOctTree::serialize
void serialize(std::string filename)
Definition: Boctree.h:507
BOctTree::FindClosest
double * FindClosest(double *point, double maxdist2, int threadNum) const
Definition: Boctree.h:1190
BOctTree::childIndex
unsigned char childIndex(const T *center, const P *point)
Definition: Boctree.h:1153
BOctTree::getMaxDepth
unsigned int getMaxDepth() const
Definition: Boctree.h:416
BOctTree::BOctTree
BOctTree(P *const *pts, int n, T voxelSize, PointType _pointtype=PointType(), bool _earlystop=false)
Definition: Boctree.h:221
BOctTree::FindClosestInBucket
double * FindClosestInBucket(double *point, double maxdist2, int threadNum)
Definition: Boctree.h:1308
bitunion::node
bitoct node
Definition: Boctree.h:135
BOctTree::childcenter
static void childcenter(int x, int y, int z, int &cx, int &cy, int &cz, char i, int size)
Definition: Boctree.h:643
NNParams::closest_v
int closest_v
Definition: nnparams.h:16
SearchTree
The search tree structure.
Definition: searchTree.h:39
bitunion
Definition: Boctree.h:46
Allocator::allocate
T * allocate(unsigned int nr=1)
Definition: allocator.h:17
bitoct::getChildren
static void getChildren(const bitoct &parent, bitunion< T > *&children)
Definition: Boctree.h:106
first
void first(int id)
Definition: example.cpp:7
BOctTree
Octree.
Definition: Boctree.h:215
BOctTree::max_depth
unsigned char max_depth
?
Definition: Boctree.h:386
PackedChunkAllocator
Definition: allocator.h:44
BOctTree::root
ip::offset_ptr< bitoct > root
the root of the octree
Definition: Boctree.h:356
sequence2ci
char sequence2ci[8][256][8]
Definition: Boctree.cc:36
nanoflann::abs
T abs(T x)
Definition: nanoflann.hpp:267
BOctTree::countNodes
long countNodes()
Definition: Boctree.h:429
bitoct::leaf
unsigned leaf
Definition: Boctree.h:92
BOctTree::largest_index
int largest_index
Definition: Boctree.h:389
BOctTree::getMemorySize
unsigned int getMemorySize()
Size of the whole tree structure, including the main class, its serialize critical allocated variable...
Definition: Boctree.h:1525
bitunion::points
pointrep * points
Definition: Boctree.h:133
BOctTree::GetOctTreeCenter
void GetOctTreeCenter(vector< T * > &c)
Definition: Boctree.h:424
bitunion::getLength
unsigned int getLength() const
Leaf node: length in the array.
Definition: Boctree.h:162
bitunion::getPointreps
pointrep * getPointreps() const
Leaf node: all points.
Definition: Boctree.h:170
BOctTree::getPointdim
unsigned int getPointdim() const
Definition: Boctree.h:414
bitunion::bitunion
bitunion(bitoct b)
Definition: Boctree.h:138
BOctTree::AllPoints
void AllPoints(vector< T * > &vp)
Definition: Boctree.h:427


lvr2
Author(s): Thomas Wiemann , Sebastian Pütz , Alexander Mock , Lars Kiesow , Lukas Kalbertodt , Tristan Igelbrink , Johan M. von Behren , Dominik Feldschnieders , Alexander Löhr
autogenerated on Wed Mar 2 2022 00:37:22