Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Prune Operation Unexpected Results #249

Open
Levi-Armstrong opened this issue Aug 27, 2019 · 6 comments
Open

Prune Operation Unexpected Results #249

Levi-Armstrong opened this issue Aug 27, 2019 · 6 comments

Comments

@Levi-Armstrong
Copy link

Currently the octomap::OcTree prune operation leverages the compare operator on the OcTreeNode to determine if they contain the same value. This checks if two floats are equal here. The OcTreeNode uses template type float which using the 'a==b' for floats is not good, should this be changed such that the class implementing the Node must implement an equal operator for this node type?

@ahornung
Copy link
Member

ahornung commented Sep 25, 2019

That depends, in general one should be careful when comparing floats. The pruning, however, mostly works on nodes on the clamping thresholds so they actually contain the exact same values. So in the case here I don't think it's a real problem.

Is there an actual issue you're experiencing?

@Levi-Armstrong
Copy link
Author

I also thought the other intent behind prune is to reduce memory consumption. If all of the nodes children contain the same float value and with the current implementation it will not be collapsed taking up space.

Also throughout the code base you see things like what is shown below which does not work as expect when using floats.

tree->updateInnerOccupancy();
tree->prune();
tree->writeBinary("...");
tree->toMaxLikelihood();
tree->prune();
outputStatistics(tree);
tree->write("....");

Also this is very useful when leveraging octomaps for collision checking because if the prune actually collapsed nodes you would end up with few collision shapes because then it can be represented by a larger box. This is very useful for convex optimization, which would provide better results when the environment is represented by larger convex shapes along with the performance increase due to few collision shapes.

@ahornung
Copy link
Member

ahornung commented Oct 27, 2019

I also thought the other intent behind prune is to reduce memory consumption. If all of the nodes children contain the same float value and with the current implementation it will not be collapsed taking up space.

The main intent of pruning is, of course, to reduce the memory consumption. What I meant is that mostly the nodes in the clamping thresholds are affected by pruning. And they are set to exactly the same float value, so the exact float comparison works just as well.

Also throughout the code base you see things like what is shown below which does not work as expect when using floats.

What would be the specific behavior you'd expect from the code you mentioned, and what behavior did you get?

If you still have doubts, it might be worth a try to adjust the code to your needs and see if it changes anything.

@Levi-Armstrong
Copy link
Author

I understand, below is the code I am currently using. I would have expected it to produce the same results as the previous two code examples. I would have expect that if all of the children were above the threshold they would be set to the same double value and then calling prune would produce the same results as the code below but it does not.

  static bool isNodeCollapsible(octomap::OcTree& octree, octomap::OcTreeNode* node)
  {
    if (!octree.nodeChildExists(node, 0))
      return false;

    double occupancy_threshold = octree.getOccupancyThres();

    const octomap::OcTreeNode* firstChild = octree.getNodeChild(node, 0);
    if (octree.nodeHasChildren(firstChild) || firstChild->getOccupancy() < occupancy_threshold)
      return false;

    for (unsigned int i = 1; i < 8; i++)
    {
      // comparison via getChild so that casts of derived classes ensure
      // that the right == operator gets called
      if (!octree.nodeChildExists(node, i))
        return false;

      if (octree.nodeHasChildren(octree.getNodeChild(node, i)))
        return false;

      if (octree.getNodeChild(node, i)->getOccupancy() < occupancy_threshold)
        return false;
    }

    return true;
  }

  static bool pruneNode(octomap::OcTree& octree, octomap::OcTreeNode* node)
  {
    if (!isNodeCollapsible(octree, node))
      return false;

    // set value to children's values (all assumed equal)
    node->copyData(*(octree.getNodeChild(node, 0)));

    // delete children (known to be leafs at this point!)
    for (unsigned int i = 0; i < 8; i++)
    {
      octree.deleteNodeChild(node, i);
    }

    return true;
  }

  static void pruneRecurs(octomap::OcTree& octree,
                          octomap::OcTreeNode* node,
                          unsigned int depth,
                          unsigned int max_depth,
                          unsigned int& num_pruned)
  {
    assert(node);

    if (depth < max_depth)
    {
      for (unsigned int i = 0; i < 8; i++)
      {
        if (octree.nodeChildExists(node, i))
        {
          pruneRecurs(octree, octree.getNodeChild(node, i), depth + 1, max_depth, num_pruned);
        }
      }
    }  // end if depth

    else
    {
      // max level reached
      if (pruneNode(octree, node))
      {
        num_pruned++;
      }
    }
  }

  /**
   * @brief A custom octree prune which will prune if all children are above the occupency threshold.
   *
   * This is different from the octomap::OcTree::prune which requires all children to have the same
   * occupency to be collapsed.
   *
   * @param octree The octree to be pruned.
   */
  static void prune(octomap::OcTree& octree)
  {
    if (octree.getRoot() == nullptr)
      return;

    for (unsigned int depth = octree.getTreeDepth() - 1; depth > 0; --depth)
    {
      unsigned int num_pruned = 0;
      pruneRecurs(octree, octree.getRoot(), 0, depth, num_pruned);
      if (num_pruned == 0)
        break;
    }
  }

@jameskiki
Copy link

Hi all

I'm having trouble understanding how prune should work.
As I understand it, I just call prune() on my octree and that's that. however nothing seems to happen.

this is my code:
octomap::OcTree* m_occupancyMap3D = dynamic_cast<octomap::OcTree*>(octomap::AbstractOcTree::read("Logs/test_tree.ot"));
m_occupancyMap3D->prune();
m_occupancyMap3D->write("Logs/pruned.ot");

however the map size (and what it looks like in octovis) stays the same
Any chance someone can tell me what I'm doing wrong?
thanks

@Levi-Armstrong
Copy link
Author

@jameskiki If you try the code snippet above does it produce the results you expect?

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

No branches or pull requests

3 participants