OctoMap / octomap

An Efficient Probabilistic 3D Mapping Framework Based on Octrees. Contains the main OctoMap library, the viewer octovis, and dynamicEDT3D.
http://octomap.github.io
1.87k stars 652 forks source link

OcTree update not fully deterministic? #404

Open christofschroeter opened 9 months ago

christofschroeter commented 9 months ago

I found that generating an OcTree from a point cloud does not yield the same result when repeated with same input:

octomap::Pointcloud pc;
for (int n = 0; n < 100000; ++ n) {
    // insert random point
}

octomap::OcTreeStamped tree1(0.02);
tree1.insertPointCloud(pc, octomap::point3d(0.f, 0.f, 0.f));

octomap::OcTreeStamped tree2(0.02);
tree2.insertPointCloud(pc, octomap::point3d(0.f, 0.f, 0.f));

std::cout << tree1.size() < " vs. " << tree2.size() << std::endl;

The size is different. Is this expected?

I am using octomap built from source. Enabling or disabling OMP does not affect the observed behaviour (I was suspicious it could change the order of updates). Also, setting discretize to true or false in the call to insertPointCloud does not change anything.

The size difference is small, I have not yet further analyzed the difference between both trees (e.g. nodes existing in both but with different occupancy). My main motivation was to write test cases for auxiliary tree access functions I wrote. For this purpose it would be good to know what I can or cannot do to expect reproducible results.

ahornung commented 9 months ago

That's weird, the result should definitely be deterministic and reproducible.

Do you observe the same effect when using the OcTree class (instead of OcTreeStamped)?

christofschroeter commented 9 months ago

Indeed this only happens with OcTreeStamped, not with OcTree. I had only used the OcTreeStamped class so far, so I was not aware of such a difference.

When doing the update in this way, is there some logic that takes the current time into account, and may be affected by minor differences of time passing over the course of the insertion of all points? Although, without any timestamp, the points should all be considered to be observed at the same time, or should they not?