Build an Occupancy OcTree "manually"

563 views
Skip to first unread message

federico...@gmail.com

unread,
Feb 23, 2016, 8:45:04 AM2/23/16
to OctoMap developers and users discussion
Hi,

let's say I have the ability to measure the occupancy of an arbitrarily sized box region.
The outcome of the measure can be 1) free or 2) occupied.

I could design a process to create an OcTree, by just following the structure of the resulting OcTree.
I.e. let's say my bounding box is BxBxB, I could first measure the occupancy of that box. If it is free, I'm finished, and if it's occupied, I measure the occupancy of the 8 B'xB'xB' (B'=B/2) boxes, and repeat the process recursively, until a maximum depth is reached.

However, I can't easily find how to implement this with the Octomap API. For example I see public functions for deleting nodes, but not for adding. Also looking at the implementation of insertPointCloud it does not clarify me ideas.

Can anyone point me in the right direction of manually creating an OcTree?

Cheers,
Federico Ferri

Federico Ferri

unread,
Feb 24, 2016, 12:23:01 PM2/24/16
to oct...@googlegroups.com
Update:

I managed to individually update single voxel at maximum depth [1], but still I have the problem of updating a box of voxels at once (i.e. a node at non-maximum depth).

How to update node at a non-maximum depth?
 or, better:
How to update occupancy of leaf nodes in a bounding box?


[1]:

    octomap::OcTree *tree = new octomap::OcTree(in->resolution);
    createProximitySensor(res);
    for(float z = z_min; z <= z_max; z += res)
    {
        for(float y = y_min; y <= y_max; y += res)
        {
            for(float x = x_min; x <= x_max; x += res)
            {
                // measure the occupancy of a cube of size res*res*res centered at x,y,z:
                bool occ = measureOccupancy(x, y, z, res);
                tree->updateNode(x, y, z, occ);
            }
        }
    }
    removeProximitySensor();

--
You received this message because you are subscribed to the Google Groups "OctoMap developers and users discussion" group.
To unsubscribe from this group and stop receiving emails from it, send an email to octomap+u...@googlegroups.com.
To post to this group, send email to oct...@googlegroups.com.
Visit this group at https://groups.google.com/group/octomap.
For more options, visit https://groups.google.com/d/optout.

Armin Hornung

unread,
Mar 2, 2016, 4:42:21 PM3/2/16
to oct...@googlegroups.com
Hello Federico,

Modifying the tree at this level is not exposed in the API, the usual
case that's covered is to address leaf nodes at the lowest tree level
like a voxel grid.

What you would want is a version of updateNode / updateNodeRecurs taking
a specified maximum depth as argument. You could implement this function
in a derived octree class or in an OctoMap fork of yours. If it works as
desired we can integrate it back into the main repo as well.

Best regards,
Armin

Sandip Kumar

unread,
Sep 20, 2017, 5:19:28 PM9/20/17
to OctoMap developers and users discussion
Hi Armin,

If I have the (x,y,z, occupancyValue, depth), can I do the following and will it be right:

1. setNodeValue(x,y,z, occupancyValue) --> sets the occupancy at the maxDepth (16)
2. search(x,y,z, depth) ---> returns the node at that depth (which now got created as we inserted/updated value of one of its children)
3. node->setLogOdds(logodds(occupancyValue));

Question1: Am I correct in assuming in STEP 2? this should not return "NULL" right?

Question2: Step 3 force update all the children nodes of the node (not at the lower depth) - am I correct?

Thanks
Sandip

Armin Hornung

unread,
Sep 24, 2017, 1:53:00 PM9/24/17
to oct...@googlegroups.com
Hi Sandip,


>
> If I have the (x,y,z, occupancyValue, depth), can I do the following
> and will it be right:
>
> 1. setNodeValue(x,y,z, occupancyValue) --> sets the occupancy at the
> maxDepth (16)
> 2. search(x,y,z, depth) ---> returns the node at that depth (which now
> got created as we inserted/updated value of one of its children)
> 3. node->setLogOdds(logodds(occupancyValue));
>
> Question1: Am I correct in assuming in STEP 2? this should not return
> "NULL" right?
That's correct. Step 1 already returns a NODE*, so the result is usually
identical. The automatic pruning could interfere in a way that after
setNodeValue, 8 children share an identical value and get pruned to only
one parent node, which search will then return.


>
> Question2: Step 3 force update all the children nodes of the node (not
> at the lower depth) - am I correct?
No, setLogOdds(...) simply assigns the value to the Node:
https://github.com/OctoMap/octomap/blob/devel/octomap/include/octomap/OcTreeNode.h#L70

Best,
Armin

Sandip Kumar

unread,
Sep 25, 2017, 3:29:52 PM9/25/17
to OctoMap developers and users discussion
Thanks for your reply.

What would be the best way to update all children (if any) with a single value of logdds?
-
Thanks
Sandip

Armin Hornung

unread,
Oct 1, 2017, 6:54:32 AM10/1/17
to oct...@googlegroups.com
You would have to write that functionality yourself or "abuse" expandNode: delete all children of the node, then an expansion will create them with identical values. On a second thought, you could just leave the last step out since the information is already stored in the node itself, just like after pruning the tree.
Reply all
Reply to author
Forward
0 new messages