ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

Update node back to unknown in octomap

asked 2013-01-23 04:52:04 -0500

bcoenen gravatar image

updated 2013-01-23 21:28:18 -0500

When a scan from a sensor is inserted into an octomap the nodes of the octree are updated. Depending on a sensor hit or miss the occupancy probability, initialized at 0.5, changes. According to the default values, the probability of a node being occupied is 0.7 and of a node being free is 0.4. So if a node has been reported as free a number of times it is marked as free. Now I'm interested in lowering the probability of a node being free as time passes by and no measurement has been received. Such that free space becomes unknown again if it has not been seen free for a while. Is this possible and how can this best be done?

Update: In reply to the answer of @dornhege: I do assume setting the probability to 0.5, i.e., setting the value/logOdds to 0.0. However I notice that when a node has been updated to occupied, it can not be updated back to unknown. While traversing all leafs of the tree after a scan insertion I do the following:

OcTreeNode* node = octoMap_->octree.search(it.getKey());
node->setLogOdds(octomap::logodds(0.5f));
octoMap_->octree.updateInnerOccupancy();

When I next check if the node is occupied with

octoMap_->octree.isNodeOccupied(node)

true is returned and the occupancy is 0.5. How should I deal with this?

edit retag flag offensive close merge delete

Comments

For general OctoMap questions and discussions (not related to ROS), I would suggest using our new mailing list: https://groups.google.com/d/forum/octomap

AHornung gravatar image AHornung  ( 2013-01-23 21:59:05 -0500 )edit

2 Answers

Sort by ยป oldest newest most voted
1

answered 2013-01-23 21:35:36 -0500

AHornung gravatar image

As @dornhege wrote, you will have to do it manually. Once nodes are created in OctoMap they are assumed to never disappear, i.e., they don't go back to unknown. After an update, you could check the updated nodes (or regularly traverse through all) and then delete the ones that have a log-odds of 0 (or close by).

You could also look at OcTreeStamped (since you mention lowering probabilities after timeouts), and how it is used in collider. It offers you time stamps of the last update.

edit flag offensive delete link more
1

answered 2013-01-23 04:59:09 -0500

dornhege gravatar image

Sure, you can do that, but you'll have to do it manually AFAIK.

I assume, you mean increasing (i.e. towards 0.5). You'd need to iterator over all free cells and update them according to your needs.

edit flag offensive delete link more

Question Tools

Stats

Asked: 2013-01-23 04:52:04 -0500

Seen: 1,731 times

Last updated: Jan 23 '13