62 bbx_min(rhs.bbx_min), bbx_max(rhs.bbx_max),
63 bbx_min_key(rhs.bbx_min_key), bbx_max_key(rhs.bbx_max_key),
64 use_change_detection(rhs.use_change_detection), changed_keys(rhs.changed_keys)
81 insertPointCloud(cloud, sensor_origin, frame_origin, maxrange, lazy_eval, discretize);
87 double maxrange,
bool lazy_eval,
bool discretize) {
89 KeySet free_cells, occupied_cells;
91 computeDiscreteUpdate(scan, sensor_origin, free_cells, occupied_cells, maxrange);
93 computeUpdate(scan, sensor_origin, free_cells, occupied_cells, maxrange);
96 for (KeySet::iterator it = free_cells.begin(); it != free_cells.end(); ++it) {
97 updateNode(*it,
false, lazy_eval);
99 for (KeySet::iterator it = occupied_cells.begin(); it != occupied_cells.end(); ++it) {
100 updateNode(*it,
true, lazy_eval);
104 template <
class NODE>
106 double maxrange,
bool lazy_eval,
bool discretize) {
109 transformed_scan.
transform(frame_origin);
111 insertPointCloud(transformed_scan, transformed_sensor_origin, maxrange, lazy_eval, discretize);
115 template <
class NODE>
121 omp_set_num_threads(this->keyrays.size());
122 #pragma omp parallel for
124 for (
int i = 0; i < (int)pc.
size(); ++i) {
126 unsigned threadIdx = 0;
128 threadIdx = omp_get_thread_num();
130 KeyRay* keyray = &(this->keyrays.at(threadIdx));
132 if (this->computeRayKeys(origin, p, *keyray)){
138 updateNode(*it,
false, lazy_eval);
140 updateNode(p,
true, lazy_eval);
147 template <
class NODE>
156 for (
int i = 0; i < (int)scan.
size(); ++i) {
158 std::pair<KeySet::iterator,bool> ret = endpoints.insert(k);
160 discretePC.
push_back(this->keyToCoord(k));
164 computeUpdate(discretePC, origin, free_cells, occupied_cells, maxrange);
168 template <
class NODE>
177 omp_set_num_threads(this->keyrays.size());
178 #pragma omp parallel for schedule(guided)
180 for (
int i = 0; i < (int)scan.
size(); ++i) {
182 unsigned threadIdx = 0;
184 threadIdx = omp_get_thread_num();
186 KeyRay* keyray = &(this->keyrays.at(threadIdx));
189 if (!use_bbx_limit) {
190 if ((maxrange < 0.0) || ((p - origin).norm() <= maxrange) ) {
192 if (this->computeRayKeys(origin, p, *keyray)){
194 #pragma omp critical (free_insert)
197 free_cells.insert(keyray->
begin(), keyray->
end());
202 if (this->coordToKeyChecked(p, key)){
204 #pragma omp critical (occupied_insert)
207 occupied_cells.insert(key);
211 point3d direction = (p - origin).normalized ();
212 point3d new_end = origin + direction * (float) maxrange;
213 if (this->computeRayKeys(origin, new_end, *keyray)){
215 #pragma omp critical (free_insert)
218 free_cells.insert(keyray->
begin(), keyray->
end());
224 if ( inBBX(p) && ((maxrange < 0.0) || ((p - origin).norm () <= maxrange) ) ) {
228 if (this->coordToKeyChecked(p, key)){
230 #pragma omp critical (occupied_insert)
233 occupied_cells.insert(key);
238 if (this->computeRayKeys(origin, p, *keyray)){
242 #pragma omp critical (free_insert)
245 free_cells.insert(*rit);
257 for(KeySet::iterator it = free_cells.begin(), end=free_cells.end(); it!= end; ){
258 if (occupied_cells.find(*it) != occupied_cells.end()){
259 it = free_cells.erase(it);
266 template <
class NODE>
269 log_odds_value = std::min(std::max(log_odds_value, this->clamping_thres_min), this->clamping_thres_max);
271 bool createdRoot =
false;
272 if (this->root == NULL){
273 this->root =
new NODE();
278 return setNodeValueRecurs(this->root, createdRoot, key, 0, log_odds_value, lazy_eval);
281 template <
class NODE>
284 if (!this->coordToKeyChecked(value, key))
287 return setNodeValue(key, log_odds_value, lazy_eval);
290 template <
class NODE>
293 if (!this->coordToKeyChecked(x, y, z, key))
296 return setNodeValue(key, log_odds_value, lazy_eval);
300 template <
class NODE>
304 NODE* leaf = this->search(key);
307 && ((log_odds_update >= 0 && leaf->getLogOdds() >= this->clamping_thres_max)
308 || ( log_odds_update <= 0 && leaf->getLogOdds() <= this->clamping_thres_min)))
313 bool createdRoot =
false;
314 if (this->root == NULL){
315 this->root =
new NODE();
320 return updateNodeRecurs(this->root, createdRoot, key, 0, log_odds_update, lazy_eval);
323 template <
class NODE>
326 if (!this->coordToKeyChecked(value, key))
329 return updateNode(key, log_odds_update, lazy_eval);
332 template <
class NODE>
335 if (!this->coordToKeyChecked(x, y, z, key))
338 return updateNode(key, log_odds_update, lazy_eval);
341 template <
class NODE>
343 float logOdds = this->prob_miss_log;
345 logOdds = this->prob_hit_log;
347 return updateNode(key, logOdds, lazy_eval);
350 template <
class NODE>
353 if (!this->coordToKeyChecked(value, key))
355 return updateNode(key, occupied, lazy_eval);
358 template <
class NODE>
361 if (!this->coordToKeyChecked(x, y, z, key))
363 return updateNode(key, occupied, lazy_eval);
366 template <
class NODE>
368 unsigned int depth,
const float& log_odds_update,
bool lazy_eval) {
369 bool created_node =
false;
374 if (depth < this->tree_depth) {
376 if (!this->nodeChildExists(node, pos)) {
378 if (!this->nodeHasChildren(node) && !node_just_created ) {
381 this->expandNode(node);
385 this->createNodeChild(node, pos);
391 return updateNodeRecurs(this->getNodeChild(node, pos), created_node, key, depth+1, log_odds_update, lazy_eval);
393 NODE* retval = updateNodeRecurs(this->getNodeChild(node, pos), created_node, key, depth+1, log_odds_update, lazy_eval);
396 if (this->pruneNode(node)){
400 node->updateOccupancyChildren();
409 if (use_change_detection) {
410 bool occBefore = this->isNodeOccupied(node);
411 updateNodeLogOdds(node, log_odds_update);
413 if (node_just_created){
414 changed_keys.insert(std::pair<OcTreeKey,bool>(key,
true));
415 }
else if (occBefore != this->isNodeOccupied(node)) {
416 KeyBoolMap::iterator it = changed_keys.find(key);
417 if (it == changed_keys.end())
418 changed_keys.insert(std::pair<OcTreeKey,bool>(key,
false));
419 else if (it->second ==
false)
420 changed_keys.erase(it);
423 updateNodeLogOdds(node, log_odds_update);
430 template <
class NODE>
432 unsigned int depth,
const float& log_odds_value,
bool lazy_eval) {
433 bool created_node =
false;
438 if (depth < this->tree_depth) {
440 if (!this->nodeChildExists(node, pos)) {
442 if (!this->nodeHasChildren(node) && !node_just_created ) {
445 this->expandNode(node);
449 this->createNodeChild(node, pos);
455 return setNodeValueRecurs(this->getNodeChild(node, pos), created_node, key, depth+1, log_odds_value, lazy_eval);
457 NODE* retval = setNodeValueRecurs(this->getNodeChild(node, pos), created_node, key, depth+1, log_odds_value, lazy_eval);
460 if (this->pruneNode(node)){
464 node->updateOccupancyChildren();
473 if (use_change_detection) {
474 bool occBefore = this->isNodeOccupied(node);
475 node->setLogOdds(log_odds_value);
477 if (node_just_created){
478 changed_keys.insert(std::pair<OcTreeKey,bool>(key,
true));
479 }
else if (occBefore != this->isNodeOccupied(node)) {
480 KeyBoolMap::iterator it = changed_keys.find(key);
481 if (it == changed_keys.end())
482 changed_keys.insert(std::pair<OcTreeKey,bool>(key,
false));
483 else if (it->second ==
false)
484 changed_keys.erase(it);
487 node->setLogOdds(log_odds_value);
493 template <
class NODE>
496 this->updateInnerOccupancyRecurs(this->root, 0);
499 template <
class NODE>
504 if (this->nodeHasChildren(node)){
506 if (depth < this->tree_depth){
507 for (
unsigned int i=0; i<8; i++) {
508 if (this->nodeChildExists(node, i)) {
509 updateInnerOccupancyRecurs(this->getNodeChild(node, i), depth+1);
513 node->updateOccupancyChildren();
517 template <
class NODE>
519 if (this->root == NULL)
523 for (
unsigned int depth=this->tree_depth; depth>0; depth--) {
524 toMaxLikelihoodRecurs(this->root, 0, depth);
528 nodeToMaxLikelihood(this->root);
531 template <
class NODE>
533 unsigned int max_depth) {
537 if (depth < max_depth) {
538 for (
unsigned int i=0; i<8; i++) {
539 if (this->nodeChildExists(node, i)) {
540 toMaxLikelihoodRecurs(this->getNodeChild(node, i), depth+1, max_depth);
546 nodeToMaxLikelihood(node);
550 template <
class NODE>
552 bool unknownStatus)
const {
563 int vertex_values[8];
570 int x_index[4][4] = {{1, 1, 0, 0}, {1, 1, 0, 0}, {0, 0 -1, -1}, {0, 0 -1, -1}};
571 int y_index[4][4] = {{1, 0, 0, 1}, {0, -1, -1, 0}, {0, -1, -1, 0}, {1, 0, 0, 1}};
572 int z_index[2][2] = {{0, 1}, {-1, 0}};
575 for(
int m = 0; m < 2; ++m){
576 for(
int l = 0; l < 4; ++l){
580 for(
int j = 0; j < 2; ++j){
581 for(
int i = 0; i < 4; ++i){
582 current_key[0] = init_key[0] + x_index[l][i];
583 current_key[1] = init_key[1] + y_index[l][i];
584 current_key[2] = init_key[2] + z_index[m][j];
585 current_node = this->search(current_key);
588 vertex_values[k] = this->isNodeOccupied(current_node);
594 vertex_values[k] = unknownStatus;
601 if (vertex_values[0]) cube_index |= 1;
602 if (vertex_values[1]) cube_index |= 2;
603 if (vertex_values[2]) cube_index |= 4;
604 if (vertex_values[3]) cube_index |= 8;
605 if (vertex_values[4]) cube_index |= 16;
606 if (vertex_values[5]) cube_index |= 32;
607 if (vertex_values[6]) cube_index |= 64;
608 if (vertex_values[7]) cube_index |= 128;
617 for(
int i = 0;
triTable[cube_index][i] != -1; i += 3){
638 template <
class NODE>
640 bool ignoreUnknown,
double maxRange)
const {
651 NODE* startingNode = this->search(current_key);
653 if (this->isNodeOccupied(startingNode)){
656 end = this->keyToCoord(current_key);
659 }
else if(!ignoreUnknown){
660 end = this->keyToCoord(current_key);
665 bool max_range_set = (maxRange > 0.0);
671 for(
unsigned int i=0; i < 3; ++i) {
673 if (direction(i) > 0.0) step[i] = 1;
674 else if (direction(i) < 0.0) step[i] = -1;
680 double voxelBorder = this->keyToCoord(current_key[i]);
681 voxelBorder += double(step[i] * this->resolution * 0.5);
683 tMax[i] = ( voxelBorder - origin(i) ) / direction(i);
684 tDelta[i] = this->resolution / fabs( direction(i) );
687 tMax[i] = std::numeric_limits<double>::max();
688 tDelta[i] = std::numeric_limits<double>::max();
692 if (step[0] == 0 && step[1] == 0 && step[2] == 0){
693 OCTOMAP_ERROR(
"Raycasting in direction (0,0,0) is not possible!");
698 double maxrange_sq = maxRange *maxRange;
708 if (tMax[0] < tMax[1]){
709 if (tMax[0] < tMax[2]) dim = 0;
713 if (tMax[1] < tMax[2]) dim = 1;
718 if ((step[dim] < 0 && current_key[dim] == 0)
719 || (step[dim] > 0 && current_key[dim] == 2* this->tree_max_val-1))
721 OCTOMAP_WARNING(
"Coordinate hit bounds in dim %d, aborting raycast\n", dim);
723 end = this->keyToCoord(current_key);
728 current_key[dim] += step[dim];
729 tMax[dim] += tDelta[dim];
733 end = this->keyToCoord(current_key);
737 double dist_from_origin_sq(0.0);
738 for (
unsigned int j = 0; j < 3; j++) {
739 dist_from_origin_sq += ((end(j) - origin(j)) * (end(j) - origin(j)));
741 if (dist_from_origin_sq > maxrange_sq)
746 NODE* currentNode = this->search(current_key);
748 if (this->isNodeOccupied(currentNode)) {
753 }
else if (!ignoreUnknown){
761 template <
class NODE>
763 point3d& intersection,
double delta)
const {
770 octomap::point3d pointXNeg(center(0) -
float(this->resolution / 2.0), center(1), center(2));
771 octomap::point3d pointXPos(center(0) +
float(this->resolution / 2.0), center(1), center(2));
772 octomap::point3d pointYNeg(center(0), center(1) -
float(this->resolution / 2.0), center(2));
773 octomap::point3d pointYPos(center(0), center(1) +
float(this->resolution / 2.0), center(2));
774 octomap::point3d pointZNeg(center(0), center(1), center(2) -
float(this->resolution / 2.0));
775 octomap::point3d pointZPos(center(0), center(1), center(2) +
float(this->resolution / 2.0));
777 double lineDotNormal = 0.0;
779 double outD = std::numeric_limits<double>::max();
787 if((lineDotNormal = normalX.
dot(direction)) != 0.0){
788 d = (pointXNeg - origin).dot(normalX) / lineDotNormal;
789 intersect = direction * float(d) + origin;
790 if(!(intersect(1) < (pointYNeg(1) - 1e-6) || intersect(1) > (pointYPos(1) + 1e-6) ||
791 intersect(2) < (pointZNeg(2) - 1e-6) || intersect(2) > (pointZPos(2) + 1e-6))){
792 outD = std::min(outD, d);
796 d = (pointXPos - origin).dot(normalX) / lineDotNormal;
797 intersect = direction * float(d) + origin;
798 if(!(intersect(1) < (pointYNeg(1) - 1e-6) || intersect(1) > (pointYPos(1) + 1e-6) ||
799 intersect(2) < (pointZNeg(2) - 1e-6) || intersect(2) > (pointZPos(2) + 1e-6))){
800 outD = std::min(outD, d);
805 if((lineDotNormal = normalY.
dot(direction)) != 0.0){
806 d = (pointYNeg - origin).dot(normalY) / lineDotNormal;
807 intersect = direction * float(d) + origin;
808 if(!(intersect(0) < (pointXNeg(0) - 1e-6) || intersect(0) > (pointXPos(0) + 1e-6) ||
809 intersect(2) < (pointZNeg(2) - 1e-6) || intersect(2) > (pointZPos(2) + 1e-6))){
810 outD = std::min(outD, d);
814 d = (pointYPos - origin).dot(normalY) / lineDotNormal;
815 intersect = direction * float(d) + origin;
816 if(!(intersect(0) < (pointXNeg(0) - 1e-6) || intersect(0) > (pointXPos(0) + 1e-6) ||
817 intersect(2) < (pointZNeg(2) - 1e-6) || intersect(2) > (pointZPos(2) + 1e-6))){
818 outD = std::min(outD, d);
823 if((lineDotNormal = normalZ.
dot(direction)) != 0.0){
824 d = (pointZNeg - origin).dot(normalZ) / lineDotNormal;
825 intersect = direction * float(d) + origin;
826 if(!(intersect(0) < (pointXNeg(0) - 1e-6) || intersect(0) > (pointXPos(0) + 1e-6) ||
827 intersect(1) < (pointYNeg(1) - 1e-6) || intersect(1) > (pointYPos(1) + 1e-6))){
828 outD = std::min(outD, d);
832 d = (pointZPos - origin).dot(normalZ) / lineDotNormal;
833 intersect = direction * float(d) + origin;
834 if(!(intersect(0) < (pointXNeg(0) - 1e-6) || intersect(0) > (pointXPos(0) + 1e-6) ||
835 intersect(1) < (pointYNeg(1) - 1e-6) || intersect(1) > (pointYPos(1) + 1e-6))){
836 outD = std::min(outD, d);
844 intersection = direction * float(outD + delta) + origin;
850 template <
class NODE>
inline bool
853 if (!this->computeRayKeys(origin, end, this->keyrays.at(0))) {
857 for(
KeyRay::iterator it=this->keyrays[0].begin(); it != this->keyrays[0].end(); it++) {
858 updateNode(*it,
false, lazy_eval);
864 template <
class NODE>
bool
868 if ((maxrange > 0) && ((end - origin).norm () > maxrange))
870 point3d direction = (end - origin).normalized ();
871 point3d new_end = origin + direction * (float) maxrange;
872 return integrateMissOnRay(origin, new_end,lazy_eval);
877 if (!integrateMissOnRay(origin, end,lazy_eval))
879 updateNode(end,
true, lazy_eval);
884 template <
class NODE>
887 if (!this->coordToKeyChecked(bbx_min, bbx_min_key)) {
892 template <
class NODE>
895 if (!this->coordToKeyChecked(bbx_max, bbx_max_key)) {
901 template <
class NODE>
903 return ((p.
x() >= bbx_min.x()) && (p.
y() >= bbx_min.y()) && (p.
z() >= bbx_min.z()) &&
904 (p.
x() <= bbx_max.x()) && (p.
y() <= bbx_max.y()) && (p.
z() <= bbx_max.z()) );
908 template <
class NODE>
910 return ((key[0] >= bbx_min_key[0]) && (key[1] >= bbx_min_key[1]) && (key[2] >= bbx_min_key[2]) &&
911 (key[0] <= bbx_max_key[0]) && (key[1] <= bbx_max_key[1]) && (key[2] <= bbx_max_key[2]) );
914 template <
class NODE>
921 template <
class NODE>
925 return bbx_min + obj_bounds;
930 template <
class NODE>
938 this->root =
new NODE();
939 this->readBinaryNode(s, this->root);
940 this->size_changed =
true;
945 template <
class NODE>
947 OCTOMAP_DEBUG(
"Writing %zu nodes to output stream...", this->size());
949 this->writeBinaryNode(s, this->root);
953 template <
class NODE>
960 s.read((
char*)&child1to4_char,
sizeof(
char));
961 s.read((
char*)&child5to8_char,
sizeof(
char));
963 std::bitset<8> child1to4 ((
unsigned long long) child1to4_char);
964 std::bitset<8> child5to8 ((
unsigned long long) child5to8_char);
972 node->setLogOdds(this->clamping_thres_max);
974 for (
unsigned int i=0; i<4; i++) {
975 if ((child1to4[i*2] == 1) && (child1to4[i*2+1] == 0)) {
977 this->createNodeChild(node, i);
978 this->getNodeChild(node, i)->setLogOdds(this->clamping_thres_min);
980 else if ((child1to4[i*2] == 0) && (child1to4[i*2+1] == 1)) {
982 this->createNodeChild(node, i);
983 this->getNodeChild(node, i)->setLogOdds(this->clamping_thres_max);
985 else if ((child1to4[i*2] == 1) && (child1to4[i*2+1] == 1)) {
987 this->createNodeChild(node, i);
988 this->getNodeChild(node, i)->setLogOdds(-200.);
991 for (
unsigned int i=0; i<4; i++) {
992 if ((child5to8[i*2] == 1) && (child5to8[i*2+1] == 0)) {
994 this->createNodeChild(node, i+4);
995 this->getNodeChild(node, i+4)->setLogOdds(this->clamping_thres_min);
997 else if ((child5to8[i*2] == 0) && (child5to8[i*2+1] == 1)) {
999 this->createNodeChild(node, i+4);
1000 this->getNodeChild(node, i+4)->setLogOdds(this->clamping_thres_max);
1002 else if ((child5to8[i*2] == 1) && (child5to8[i*2+1] == 1)) {
1004 this->createNodeChild(node, i+4);
1005 this->getNodeChild(node, i+4)->setLogOdds(-200.);
1011 for (
unsigned int i=0; i<8; i++) {
1012 if (this->nodeChildExists(node, i)) {
1013 NODE* child = this->getNodeChild(node, i);
1014 if (fabs(child->getLogOdds() + 200.)<1e-3) {
1015 readBinaryNode(s, child);
1016 child->setLogOdds(child->getMaxChildLogOdds());
1024 template <
class NODE>
1030 std::bitset<8> child1to4;
1031 std::bitset<8> child5to8;
1042 for (
unsigned int i=0; i<4; i++) {
1043 if (this->nodeChildExists(node, i)) {
1044 const NODE* child = this->getNodeChild(node, i);
1045 if (this->nodeHasChildren(child)) { child1to4[i*2] = 1; child1to4[i*2+1] = 1; }
1046 else if (this->isNodeOccupied(child)) { child1to4[i*2] = 0; child1to4[i*2+1] = 1; }
1047 else { child1to4[i*2] = 1; child1to4[i*2+1] = 0; }
1050 child1to4[i*2] = 0; child1to4[i*2+1] = 0;
1054 for (
unsigned int i=0; i<4; i++) {
1055 if (this->nodeChildExists(node, i+4)) {
1056 const NODE* child = this->getNodeChild(node, i+4);
1057 if (this->nodeHasChildren(child)) { child5to8[i*2] = 1; child5to8[i*2+1] = 1; }
1058 else if (this->isNodeOccupied(child)) { child5to8[i*2] = 0; child5to8[i*2+1] = 1; }
1059 else { child5to8[i*2] = 1; child5to8[i*2+1] = 0; }
1062 child5to8[i*2] = 0; child5to8[i*2+1] = 0;
1069 char child1to4_char = (char) child1to4.to_ulong();
1070 char child5to8_char = (char) child5to8.to_ulong();
1072 s.write((
char*)&child1to4_char,
sizeof(char));
1073 s.write((
char*)&child5to8_char,
sizeof(char));
1076 for (
unsigned int i=0; i<8; i++) {
1077 if (this->nodeChildExists(node, i)) {
1078 const NODE* child = this->getNodeChild(node, i);
1079 if (this->nodeHasChildren(child)) {
1080 writeBinaryNode(s, child);
1090 template <
class NODE>
1092 occupancyNode->addValue(update);
1093 if (occupancyNode->getLogOdds() < this->clamping_thres_min) {
1094 occupancyNode->setLogOdds(this->clamping_thres_min);
1097 if (occupancyNode->getLogOdds() > this->clamping_thres_max) {
1098 occupancyNode->setLogOdds(this->clamping_thres_max);
1102 template <
class NODE>
1104 updateNodeLogOdds(occupancyNode, this->prob_hit_log);
1107 template <
class NODE>
1109 updateNodeLogOdds(occupancyNode, this->prob_miss_log);
1112 template <
class NODE>
1114 if (this->isNodeOccupied(occupancyNode))
1115 occupancyNode->setLogOdds(this->clamping_thres_max);
1117 occupancyNode->setLogOdds(this->clamping_thres_min);
1120 template <
class NODE>
1122 if (this->isNodeOccupied(occupancyNode))
1123 occupancyNode.setLogOdds(this->clamping_thres_max);
1125 occupancyNode.setLogOdds(this->clamping_thres_min);