octomap::OccupancyOcTreeBase with lazy_eval = false or True

classic Classic list List threaded Threaded
2 messages Options
Reply | Threaded
Open this post in threaded view
|

octomap::OccupancyOcTreeBase with lazy_eval = false or True

heshamhendy
I was wondering how the OcTree is built the reason is I do have limited computational power and I was looking into possibilities of load reduction caused through OcTree. There are many possibilities to do process it after subscribe the topic. However I'm not sure how the OcTree is updated. As stated in the implementation (https://octomap.github.io/octomap/doc/classoctomap_1_1OccupancyOcTreeBase.html)  the tree can be converted into multi-resolution if it's built with lazy evaluation. Can anybody confirm if it's built with or without lazy evaluation?


I would be grateful if I hear suggestions about ideas to optimize the tree after subscribing the tree. I already took some measurements like subscribing to the binary version and pruning. Yet I'm interested to do more...

Cheers
Reply | Threaded
Open this post in threaded view
|

Re: octomap::OccupancyOcTreeBase with lazy_eval = false or True

matlabbe
Administrator
Hi,

The OctoMap in RTAB-Map is updated in this file.

It adds individual points to OctoMap instead of a full point cloud / rays like the functions you pointed with "lazy_eval" option. For a more direct comparison, look at this OctoMap code:
    // insert data into tree  -----------------------
    for (KeySet::iterator it = free_cells.begin(); it != free_cells.end(); ++it) {
      updateNode(*it, false, lazy_eval);
    }
    for (KeySet::iterator it = occupied_cells.begin(); it != occupied_cells.end(); ++it) {
      updateNode(*it, true, lazy_eval);
    }

On RTAB-Map side, we use updateNode() function too here:
 * ray traced free cells
RtabmapColorOcTreeNode * n = octree_->updateNode(*it, false,  true);
 * Empty cells (ground)
RtabmapColorOcTreeNode * n = octree_->updateNode(key, false, true);
 * obstacle cells
RtabmapColorOcTreeNode * n = octree_->updateNode(key, true);

It seems only for obstacle cells, the lazy flag is not explicitly set to true. As explained in the doc here, rtabmap will eventually call updateInnerOccupancy() here:
if((occupancyIter != cache_.end() && occupancyIter->second.second.cols) || !free_cells.empty())
{
	octree_->updateInnerOccupancy();
}

The OctoMap is a pretty structure for fast 3d obstacle detection when it is static. However, to update it while doing SLAM, in particularly when a loop closure is detected, it can be quite costly to use online. If you plan to do a SLAM session, then doing navigation during on a localization session with a previously built map, I suggest to build the OctoMap offline after the SLAM session:
 1. setting RGBD/CreateOccupancyGrid=false during SLAM, then
 2. do "rtabmap-reprocess RGBD/CreateOccupancyGrid=true map.db map_with_octomap.db" afterwards.

If you want to build the OctoMap during SLAM, there is a parameter called GridGlobal/MaxNodes that can be used to limit the size of the OctoMap to update around the current position of the robot. See also this paper RTAB-Map as an Open-Source Lidar and Visual SLAM Library for Large-Scale and Long-Term Online Operation about time performance of updating OctoMap while doing SLAM (in particular table 10).

cheers,
Mathieu